Implements the functionalities for a robot. More...
#include <stdr_gui_robot.h>
Public Member Functions | |
CGuiRobot (const stdr_msgs::RobotIndexedMsg &msg) | |
Default contructor. | |
bool | checkEventProximity (QPoint p) |
Checks if the robot is near a specific point. | |
void | destroy (void) |
Destroys the robot object. | |
void | draw (QImage *m, float ocgd, tf::TransformListener *listener) |
Paints the robot and it's sensors to the image. | |
void | drawLabel (QImage *m, float ocgd) |
Draws the robot's label. | |
char | getCO2SensorVisualizationStatus (std::string frame_id) |
Returns the rfid reader visibility status. | |
QPoint | getCurrentPose (void) |
Returns the current robot pose. | |
geometry_msgs::Pose2D | getCurrentPoseM (void) |
Returns the current robot pose in meters. | |
std::string | getFrameId (void) |
Returns the frame id of the specific robot. | |
int | getLasersNumber (void) |
Returns the lasers number. | |
char | getLaserVisualizationStatus (std::string frame_id) |
Returns the laser visibility status. | |
char | getRfidReaderVisualizationStatus (std::string frame_id) |
Returns the rfid reader visibility status. | |
bool | getShowLabel (void) |
Gets the show_label_ flag. | |
int | getSonarsNumber (void) |
Returns the sonars number. | |
char | getSonarVisualizationStatus (std::string frame_id) |
Returns the sonar visibility status. | |
char | getSoundSensorVisualizationStatus (std::string frame_id) |
Returns the rfid reader visibility status. | |
std::pair< float, float > | getSpeeds (void) |
Returns the current robot speed. | |
char | getThermalSensorVisualizationStatus (std::string frame_id) |
Returns the rfid reader visibility status. | |
QImage | getVisualization (float ocgd) |
Returns the visualization image of the robot. | |
char | getVisualizationStatus (void) |
Returns the visibility status. | |
void | setEnvironmentalCO2Sources (stdr_msgs::CO2SourceVector env_co2_sources) |
Sets the tags existent in the environment. | |
void | setEnvironmentalSoundSources (stdr_msgs::SoundSourceVector env_sound_sources) |
Sets the sound sources existent in the environment. | |
void | setEnvironmentalTags (stdr_msgs::RfidTagVector env_tags) |
Sets the tags existent in the environment. | |
void | setEnvironmentalThermalSources (stdr_msgs::ThermalSourceVector env_thermal_sources) |
Sets the thermal sources existent in the environment. | |
void | setShowLabel (bool b) |
Sets the show_label_ flag. | |
void | speedsCallback (const geometry_msgs::Twist &msg) |
Callback for the ros laser message. | |
void | toggleCO2SensorVisualizationStatus (std::string frame_id) |
Toggles the rfid reader visibility status. | |
void | toggleLaserVisualizationStatus (std::string frame_id) |
Toggles the laser visibility status. | |
void | toggleRfidReaderVisualizationStatus (std::string frame_id) |
Toggles the rfid reader visibility status. | |
void | toggleShowCircles (void) |
Toggles the show_circles_ flag. | |
void | toggleShowLabel (void) |
Toggles the show_label_ flag. | |
void | toggleSonarVisualizationStatus (std::string frame_id) |
Toggles the sonar visibility status. | |
void | toggleSoundSensorVisualizationStatus (std::string frame_id) |
Toggles the rfid reader visibility status. | |
void | toggleThermalSensorVisualizationStatus (std::string frame_id) |
Toggles the rfid reader visibility status. | |
void | toggleVisualizationStatus (void) |
Toggles the visibility status. | |
~CGuiRobot (void) | |
Default destructor. | |
Private Member Functions | |
void | drawSelf (QImage *m) |
Draws the robot body. | |
Private Attributes | |
float | angular_speed_ |
Radius of robot if shape is circular. | |
std::vector< CGuiCO2 * > | co2_sensors_ |
Robot Rfid antenna sensors. | |
geometry_msgs::Pose2D | current_pose_ |
Robot footprint if not circular. | |
stdr_msgs::FootprintMsg | footprint_ |
Visualization image. | |
std::string | frame_id_ |
Initial robot pose. | |
geometry_msgs::Pose2D | initial_pose_ |
Current robot pose. | |
std::vector< CGuiLaser * > | lasers_ |
Robot sonar sensors. | |
float | linear_speed_ |
Robot current angular speed. | |
float | radius_ |
Map resolution. | |
float | resolution_ |
Robot laser sensors. | |
std::vector< CGuiRfid * > | rfids_ |
Robot Rfid antenna sensors. | |
bool | robot_initialized_ |
Check for start. | |
bool | show_circles_ |
True when robot is initialized. | |
bool | show_label_ |
< If true the robot's label is visible | |
std::vector< CGuiSonar * > | sonars_ |
Robot Rfid antenna sensors. | |
std::vector< CGuiSound * > | sound_sensors_ |
Robot frame id. | |
ros::Subscriber | speeds_subscriber_ |
Robot current linear speed. | |
bool | started_ |
Subscriber for the speeds twist message. | |
std::vector< CGuiThermal * > | thermal_sensors_ |
Robot Rfid antenna sensors. | |
QImage | visualization |
char | visualization_status_ |
Implements the functionalities for a robot.
Definition at line 43 of file stdr_gui_robot.h.
stdr_gui::CGuiRobot::CGuiRobot | ( | const stdr_msgs::RobotIndexedMsg & | msg | ) |
Default contructor.
msg | [const stdr_msgs::RobotIndexedMsg&] The robot description msg |
Definition at line 31 of file stdr_gui_robot.cpp.
stdr_gui::CGuiRobot::~CGuiRobot | ( | void | ) |
bool stdr_gui::CGuiRobot::checkEventProximity | ( | QPoint | p | ) |
Checks if the robot is near a specific point.
p | [QPoint] A point |
Definition at line 250 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::destroy | ( | void | ) |
void stdr_gui::CGuiRobot::draw | ( | QImage * | m, |
float | ocgd, | ||
tf::TransformListener * | listener | ||
) |
Paints the robot and it's sensors to the image.
m | [QImage*] The image to be drawn |
ocgd | [float] The map's resolution |
listener | [tf::TransformListener *] ROS tf listener to get the robot's current pose |
Definition at line 94 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::drawLabel | ( | QImage * | m, |
float | ocgd | ||
) |
Draws the robot's label.
m | [QImage*] The image to be drawn |
ocgd | [float] The map's resolution |
Definition at line 297 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::drawSelf | ( | QImage * | m | ) | [private] |
Draws the robot body.
m | [QImage*] The image for the robot to draw itself |
m | [QImage*] The image for the robot to draw itself |
Definition at line 166 of file stdr_gui_robot.cpp.
char stdr_gui::CGuiRobot::getCO2SensorVisualizationStatus | ( | std::string | frame_id | ) |
Returns the rfid reader visibility status.
Returns the co2 sensor visibility status.
frame_id | [std::string] The rfid reader frame id |
frame_id | [std::string] The co2 sensor frame id |
Definition at line 476 of file stdr_gui_robot.cpp.
QPoint stdr_gui::CGuiRobot::getCurrentPose | ( | void | ) |
Returns the current robot pose.
Definition at line 368 of file stdr_gui_robot.cpp.
geometry_msgs::Pose2D stdr_gui::CGuiRobot::getCurrentPoseM | ( | void | ) |
Returns the current robot pose in meters.
Definition at line 378 of file stdr_gui_robot.cpp.
std::string stdr_gui::CGuiRobot::getFrameId | ( | void | ) |
Returns the frame id of the specific robot.
Definition at line 286 of file stdr_gui_robot.cpp.
int stdr_gui::CGuiRobot::getLasersNumber | ( | void | ) |
Returns the lasers number.
Definition at line 387 of file stdr_gui_robot.cpp.
char stdr_gui::CGuiRobot::getLaserVisualizationStatus | ( | std::string | frame_id | ) |
Returns the laser visibility status.
frame_id | [std::string] The laser frame id |
Definition at line 442 of file stdr_gui_robot.cpp.
char stdr_gui::CGuiRobot::getRfidReaderVisualizationStatus | ( | std::string | frame_id | ) |
Returns the rfid reader visibility status.
frame_id | [std::string] The rfid reader frame id |
Definition at line 459 of file stdr_gui_robot.cpp.
bool stdr_gui::CGuiRobot::getShowLabel | ( | void | ) |
Gets the show_label_ flag.
Definition at line 341 of file stdr_gui_robot.cpp.
int stdr_gui::CGuiRobot::getSonarsNumber | ( | void | ) |
Returns the sonars number.
Definition at line 396 of file stdr_gui_robot.cpp.
char stdr_gui::CGuiRobot::getSonarVisualizationStatus | ( | std::string | frame_id | ) |
Returns the sonar visibility status.
frame_id | [std::string] The sonar frame id |
Definition at line 543 of file stdr_gui_robot.cpp.
char stdr_gui::CGuiRobot::getSoundSensorVisualizationStatus | ( | std::string | frame_id | ) |
Returns the rfid reader visibility status.
Returns the sound sensor visibility status.
frame_id | [std::string] The rfid reader frame id |
frame_id | [std::string] The sound sensor frame id |
Definition at line 510 of file stdr_gui_robot.cpp.
std::pair< float, float > stdr_gui::CGuiRobot::getSpeeds | ( | void | ) |
Returns the current robot speed.
Definition at line 678 of file stdr_gui_robot.cpp.
char stdr_gui::CGuiRobot::getThermalSensorVisualizationStatus | ( | std::string | frame_id | ) |
Returns the rfid reader visibility status.
Returns the thermal sensor visibility status.
frame_id | [std::string] The rfid reader frame id |
frame_id | [std::string] The thermal sensor frame id |
Definition at line 493 of file stdr_gui_robot.cpp.
QImage stdr_gui::CGuiRobot::getVisualization | ( | float | ocgd | ) |
Returns the visualization image of the robot.
Returns the visibility status.
ocgd | [float] The map resolution |
Definition at line 405 of file stdr_gui_robot.cpp.
char stdr_gui::CGuiRobot::getVisualizationStatus | ( | void | ) |
void stdr_gui::CGuiRobot::setEnvironmentalCO2Sources | ( | stdr_msgs::CO2SourceVector | env_co2_sources | ) |
Sets the tags existent in the environment.
Sets the co2 sources existent in the environment.
env_tags | [stdr_msgs::RfidTagVector] The tag vector |
Definition at line 699 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::setEnvironmentalSoundSources | ( | stdr_msgs::SoundSourceVector | env_sound_sources | ) |
Sets the sound sources existent in the environment.
Definition at line 719 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::setEnvironmentalTags | ( | stdr_msgs::RfidTagVector | env_tags | ) |
Sets the tags existent in the environment.
env_tags | [stdr_msgs::RfidTagVector] The tag vector |
Definition at line 688 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::setEnvironmentalThermalSources | ( | stdr_msgs::ThermalSourceVector | env_thermal_sources | ) |
Sets the thermal sources existent in the environment.
Definition at line 709 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::setShowLabel | ( | bool | b | ) |
Sets the show_label_ flag.
b | [bool] True for showing the label |
Definition at line 332 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::speedsCallback | ( | const geometry_msgs::Twist & | msg | ) |
Callback for the ros laser message.
msg | [const sensor_msgs::LaserScan&] The new laser scan message |
Definition at line 81 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::toggleCO2SensorVisualizationStatus | ( | std::string | frame_id | ) |
Toggles the rfid reader visibility status.
Toggles the co2 sensor visibility status.
frame_id | [std::string] The rfid reader frame id |
frame_id | [std::string] The co2 sensor frame id |
Definition at line 591 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::toggleLaserVisualizationStatus | ( | std::string | frame_id | ) |
Toggles the laser visibility status.
frame_id | [std::string] The laser frame id |
Definition at line 527 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::toggleRfidReaderVisualizationStatus | ( | std::string | frame_id | ) |
Toggles the rfid reader visibility status.
frame_id | [std::string] The rfid reader frame id |
Definition at line 576 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::toggleShowCircles | ( | void | ) |
void stdr_gui::CGuiRobot::toggleShowLabel | ( | void | ) |
Toggles the show_label_ flag.
Gets the show_label_ flag.
Definition at line 350 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::toggleSonarVisualizationStatus | ( | std::string | frame_id | ) |
Toggles the sonar visibility status.
frame_id | [std::string] The sonar frame id |
Definition at line 560 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::toggleSoundSensorVisualizationStatus | ( | std::string | frame_id | ) |
Toggles the rfid reader visibility status.
Toggles the sound sensor visibility status.
frame_id | [std::string] The rfid reader frame id |
frame_id | [std::string] The sound sensor frame id |
Definition at line 621 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::toggleThermalSensorVisualizationStatus | ( | std::string | frame_id | ) |
Toggles the rfid reader visibility status.
Toggles the thermal sensor visibility status.
frame_id | [std::string] The rfid reader frame id |
frame_id | [std::string] The thermal sensor frame id |
Definition at line 606 of file stdr_gui_robot.cpp.
void stdr_gui::CGuiRobot::toggleVisualizationStatus | ( | void | ) |
float stdr_gui::CGuiRobot::angular_speed_ [private] |
Radius of robot if shape is circular.
Definition at line 66 of file stdr_gui_robot.h.
std::vector<CGuiCO2*> stdr_gui::CGuiRobot::co2_sensors_ [private] |
Robot Rfid antenna sensors.
Definition at line 79 of file stdr_gui_robot.h.
geometry_msgs::Pose2D stdr_gui::CGuiRobot::current_pose_ [private] |
Robot footprint if not circular.
Definition at line 91 of file stdr_gui_robot.h.
stdr_msgs::FootprintMsg stdr_gui::CGuiRobot::footprint_ [private] |
Visualization image.
Definition at line 94 of file stdr_gui_robot.h.
std::string stdr_gui::CGuiRobot::frame_id_ [private] |
Initial robot pose.
Definition at line 86 of file stdr_gui_robot.h.
geometry_msgs::Pose2D stdr_gui::CGuiRobot::initial_pose_ [private] |
Current robot pose.
Definition at line 88 of file stdr_gui_robot.h.
std::vector<CGuiLaser*> stdr_gui::CGuiRobot::lasers_ [private] |
Robot sonar sensors.
Definition at line 73 of file stdr_gui_robot.h.
float stdr_gui::CGuiRobot::linear_speed_ [private] |
Robot current angular speed.
Definition at line 63 of file stdr_gui_robot.h.
float stdr_gui::CGuiRobot::radius_ [private] |
Map resolution.
Definition at line 68 of file stdr_gui_robot.h.
float stdr_gui::CGuiRobot::resolution_ [private] |
Robot laser sensors.
Definition at line 71 of file stdr_gui_robot.h.
std::vector<CGuiRfid*> stdr_gui::CGuiRobot::rfids_ [private] |
Robot Rfid antenna sensors.
Definition at line 77 of file stdr_gui_robot.h.
bool stdr_gui::CGuiRobot::robot_initialized_ [private] |
Check for start.
Definition at line 55 of file stdr_gui_robot.h.
bool stdr_gui::CGuiRobot::show_circles_ [private] |
True when robot is initialized.
Definition at line 52 of file stdr_gui_robot.h.
bool stdr_gui::CGuiRobot::show_label_ [private] |
< If true the robot's label is visible
If true the proximity circles are visible
Definition at line 50 of file stdr_gui_robot.h.
std::vector<CGuiSonar*> stdr_gui::CGuiRobot::sonars_ [private] |
Robot Rfid antenna sensors.
Definition at line 75 of file stdr_gui_robot.h.
std::vector<CGuiSound*> stdr_gui::CGuiRobot::sound_sensors_ [private] |
Robot frame id.
Definition at line 84 of file stdr_gui_robot.h.
Robot current linear speed.
Definition at line 61 of file stdr_gui_robot.h.
bool stdr_gui::CGuiRobot::started_ [private] |
Subscriber for the speeds twist message.
Definition at line 58 of file stdr_gui_robot.h.
std::vector<CGuiThermal*> stdr_gui::CGuiRobot::thermal_sensors_ [private] |
Robot Rfid antenna sensors.
Definition at line 81 of file stdr_gui_robot.h.
QImage stdr_gui::CGuiRobot::visualization [private] |
Definition at line 95 of file stdr_gui_robot.h.
char stdr_gui::CGuiRobot::visualization_status_ [private] |
Definition at line 105 of file stdr_gui_robot.h.