22 #ifndef STDR_GUI_ROBOT_CONTAINER 23 #define STDR_GUI_ROBOT_CONTAINER 116 CGuiRobot(
const stdr_msgs::RobotIndexedMsg& msg);
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.
char visualization_status_
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'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'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'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.