stdr_gui_robot.h
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16  Authors :
17  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
21 
22 #ifndef STDR_GUI_ROBOT_CONTAINER
23 #define STDR_GUI_ROBOT_CONTAINER
24 
25 #include "stdr_gui/stdr_tools.h"
32 
37 namespace stdr_gui
38 {
43  class CGuiRobot
44  {
45  //------------------------------------------------------------------------//
46  private:
47 
54 
56  bool started_;
57 
60 
67 
69  float radius_;
71  float resolution_;
72 
74  std::vector<CGuiLaser*> lasers_;
76  std::vector<CGuiSonar*> sonars_;
78  std::vector<CGuiRfid*> rfids_;
80  std::vector<CGuiCO2*> co2_sensors_;
82  std::vector<CGuiThermal*> thermal_sensors_;
84  std::vector<CGuiSound*> sound_sensors_;
85 
87  std::string frame_id_;
89  geometry_msgs::Pose2D initial_pose_;
91  geometry_msgs::Pose2D current_pose_;
92 
94  stdr_msgs::FootprintMsg footprint_;
95 
97  QImage visualization;
98 
104  void drawSelf(QImage *m);
105 
108  //------------------------------------------------------------------------//
109  public:
110 
116  CGuiRobot(const stdr_msgs::RobotIndexedMsg& msg);
117 
122  ~CGuiRobot(void);
123 
128  std::string getFrameId(void);
129 
137  void draw(QImage *m,float ocgd,tf::TransformListener *listener);
138 
145  void drawLabel(QImage *m,float ocgd);
146 
152  bool checkEventProximity(QPoint p);
153 
159  void setShowLabel(bool b);
160 
165  void toggleShowLabel(void);
166 
171  bool getShowLabel(void);
172 
177  void toggleShowCircles(void);
178 
183  QPoint getCurrentPose(void);
184 
189  void destroy(void);
190 
195  int getLasersNumber(void);
196 
201  int getSonarsNumber(void);
202 
207  char getVisualizationStatus(void);
208 
213  void toggleVisualizationStatus(void);
214 
220  char getLaserVisualizationStatus(std::string frame_id);
221 
227  void toggleLaserVisualizationStatus(std::string frame_id);
228 
234  char getRfidReaderVisualizationStatus(std::string frame_id);
240  char getCO2SensorVisualizationStatus(std::string frame_id);
246  char getThermalSensorVisualizationStatus(std::string frame_id);
252  char getSoundSensorVisualizationStatus(std::string frame_id);
253 
259  void toggleRfidReaderVisualizationStatus(std::string frame_id);
265  void toggleCO2SensorVisualizationStatus(std::string frame_id);
271  void toggleThermalSensorVisualizationStatus(std::string frame_id);
277  void toggleSoundSensorVisualizationStatus(std::string frame_id);
278 
284  char getSonarVisualizationStatus(std::string frame_id);
285 
291  void toggleSonarVisualizationStatus(std::string frame_id);
292 
298  QImage getVisualization(float ocgd);
299 
304  geometry_msgs::Pose2D getCurrentPoseM(void);
305 
311  void speedsCallback(const geometry_msgs::Twist& msg);
312 
317  std::vector<float> getSpeeds(void);
318 
324  void setEnvironmentalTags(stdr_msgs::RfidTagVector env_tags);
330  void setEnvironmentalCO2Sources(stdr_msgs::CO2SourceVector env_co2_sources);
331  void setEnvironmentalThermalSources(stdr_msgs::ThermalSourceVector env_thermal_sources);
332  void setEnvironmentalSoundSources(stdr_msgs::SoundSourceVector env_sound_sources);
333  };
334 }
335 
336 #endif
void setEnvironmentalTags(stdr_msgs::RfidTagVector env_tags)
Sets the tags existent in the environment.
char getThermalSensorVisualizationStatus(std::string frame_id)
Returns the rfid reader visibility status.
char getCO2SensorVisualizationStatus(std::string frame_id)
Returns the rfid reader visibility status.
bool robot_initialized_
Check for start.
void setEnvironmentalThermalSources(stdr_msgs::ThermalSourceVector env_thermal_sources)
Sets the thermal sources existent in the environment.
bool getShowLabel(void)
Gets the show_label_ flag.
float linear_speed_y_
Robot current angular speed.
geometry_msgs::Pose2D initial_pose_
Current robot pose.
void setEnvironmentalCO2Sources(stdr_msgs::CO2SourceVector env_co2_sources)
Sets the tags existent in the environment.
void toggleVisualizationStatus(void)
Toggles the visibility status.
bool show_label_
< If true the robot&#39;s label is visible
std::vector< CGuiSonar * > sonars_
Robot Rfid antenna sensors.
void destroy(void)
Destroys the robot object.
CGuiRobot(const stdr_msgs::RobotIndexedMsg &msg)
Default contructor.
void draw(QImage *m, float ocgd, tf::TransformListener *listener)
Paints the robot and it&#39;s sensors to the image.
std::string frame_id_
Initial robot pose.
char getSoundSensorVisualizationStatus(std::string frame_id)
Returns the rfid reader visibility status.
char getRfidReaderVisualizationStatus(std::string frame_id)
Returns the rfid reader visibility status.
float radius_
Map resolution.
std::vector< CGuiRfid * > rfids_
Robot Rfid antenna sensors.
float angular_speed_
Radius of robot if shape is circular.
Implements the functionalities for a robot.
std::vector< CGuiCO2 * > co2_sensors_
Robot Rfid antenna sensors.
void toggleSonarVisualizationStatus(std::string frame_id)
Toggles the sonar visibility status.
void toggleLaserVisualizationStatus(std::string frame_id)
Toggles the laser visibility status.
bool checkEventProximity(QPoint p)
Checks if the robot is near a specific point.
void speedsCallback(const geometry_msgs::Twist &msg)
Callback for the ros laser message.
char getVisualizationStatus(void)
Returns the visibility status.
bool started_
Subscriber for the speeds twist message.
void toggleThermalSensorVisualizationStatus(std::string frame_id)
Toggles the rfid reader visibility status.
void toggleSoundSensorVisualizationStatus(std::string frame_id)
Toggles the rfid reader visibility status.
void drawLabel(QImage *m, float ocgd)
Draws the robot&#39;s label.
ros::Subscriber speeds_subscriber_
Robot current linear speed.
int getSonarsNumber(void)
Returns the sonars number.
~CGuiRobot(void)
Default destructor.
void toggleCO2SensorVisualizationStatus(std::string frame_id)
Toggles the rfid reader visibility status.
std::string getFrameId(void)
Returns the frame id of the specific robot.
int getLasersNumber(void)
Returns the lasers number.
QPoint getCurrentPose(void)
Returns the current robot pose.
geometry_msgs::Pose2D current_pose_
Robot footprint if not circular.
bool show_circles_
True when robot is initialized.
std::vector< CGuiLaser * > lasers_
Robot sonar sensors.
void toggleShowLabel(void)
Toggles the show_label_ flag.
The main namespace for STDR GUI.
char getSonarVisualizationStatus(std::string frame_id)
Returns the sonar visibility status.
void toggleRfidReaderVisualizationStatus(std::string frame_id)
Toggles the rfid reader visibility status.
stdr_msgs::FootprintMsg footprint_
Visualization image.
float linear_speed_
Robot current linear speed by Y.
QImage getVisualization(float ocgd)
Returns the visualization image of the robot.
geometry_msgs::Pose2D getCurrentPoseM(void)
Returns the current robot pose in meters.
void setEnvironmentalSoundSources(stdr_msgs::SoundSourceVector env_sound_sources)
Sets the sound sources existent in the environment.
std::vector< float > getSpeeds(void)
Returns the current robot speed.
void drawSelf(QImage *m)
Draws the robot body.
std::vector< CGuiThermal * > thermal_sensors_
Robot Rfid antenna sensors.
void setShowLabel(bool b)
Sets the show_label_ flag.
char getLaserVisualizationStatus(std::string frame_id)
Returns the laser visibility status.
float resolution_
Robot laser sensors.
void toggleShowCircles(void)
Toggles the show_circles_ flag.
std::vector< CGuiSound * > sound_sensors_
Robot frame id.


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Mon Jun 10 2019 15:15:16