Public Member Functions | Private Member Functions | Private Attributes | List of all members
stdr_gui::CGuiRobot Class Reference

Implements the functionalities for a robot. More...

#include <stdr_gui_robot.h>

Public Member Functions

 CGuiRobot (const stdr_msgs::RobotIndexedMsg &msg)
 Default contructor. More...
 
bool checkEventProximity (QPoint p)
 Checks if the robot is near a specific point. More...
 
void destroy (void)
 Destroys the robot object. More...
 
void draw (QImage *m, float ocgd, tf::TransformListener *listener)
 Paints the robot and it's sensors to the image. More...
 
void drawLabel (QImage *m, float ocgd)
 Draws the robot's label. More...
 
char getCO2SensorVisualizationStatus (std::string frame_id)
 Returns the rfid reader visibility status. More...
 
QPoint getCurrentPose (void)
 Returns the current robot pose. More...
 
geometry_msgs::Pose2D getCurrentPoseM (void)
 Returns the current robot pose in meters. More...
 
std::string getFrameId (void)
 Returns the frame id of the specific robot. More...
 
int getLasersNumber (void)
 Returns the lasers number. More...
 
char getLaserVisualizationStatus (std::string frame_id)
 Returns the laser visibility status. More...
 
char getRfidReaderVisualizationStatus (std::string frame_id)
 Returns the rfid reader visibility status. More...
 
bool getShowLabel (void)
 Gets the show_label_ flag. More...
 
int getSonarsNumber (void)
 Returns the sonars number. More...
 
char getSonarVisualizationStatus (std::string frame_id)
 Returns the sonar visibility status. More...
 
char getSoundSensorVisualizationStatus (std::string frame_id)
 Returns the rfid reader visibility status. More...
 
std::vector< float > getSpeeds (void)
 Returns the current robot speed. More...
 
char getThermalSensorVisualizationStatus (std::string frame_id)
 Returns the rfid reader visibility status. More...
 
QImage getVisualization (float ocgd)
 Returns the visualization image of the robot. More...
 
char getVisualizationStatus (void)
 Returns the visibility status. More...
 
void setEnvironmentalCO2Sources (stdr_msgs::CO2SourceVector env_co2_sources)
 Sets the tags existent in the environment. More...
 
void setEnvironmentalSoundSources (stdr_msgs::SoundSourceVector env_sound_sources)
 Sets the sound sources existent in the environment. More...
 
void setEnvironmentalTags (stdr_msgs::RfidTagVector env_tags)
 Sets the tags existent in the environment. More...
 
void setEnvironmentalThermalSources (stdr_msgs::ThermalSourceVector env_thermal_sources)
 Sets the thermal sources existent in the environment. More...
 
void setShowLabel (bool b)
 Sets the show_label_ flag. More...
 
void speedsCallback (const geometry_msgs::Twist &msg)
 Callback for the ros laser message. More...
 
void toggleCO2SensorVisualizationStatus (std::string frame_id)
 Toggles the rfid reader visibility status. More...
 
void toggleLaserVisualizationStatus (std::string frame_id)
 Toggles the laser visibility status. More...
 
void toggleRfidReaderVisualizationStatus (std::string frame_id)
 Toggles the rfid reader visibility status. More...
 
void toggleShowCircles (void)
 Toggles the show_circles_ flag. More...
 
void toggleShowLabel (void)
 Toggles the show_label_ flag. More...
 
void toggleSonarVisualizationStatus (std::string frame_id)
 Toggles the sonar visibility status. More...
 
void toggleSoundSensorVisualizationStatus (std::string frame_id)
 Toggles the rfid reader visibility status. More...
 
void toggleThermalSensorVisualizationStatus (std::string frame_id)
 Toggles the rfid reader visibility status. More...
 
void toggleVisualizationStatus (void)
 Toggles the visibility status. More...
 
 ~CGuiRobot (void)
 Default destructor. More...
 

Private Member Functions

void drawSelf (QImage *m)
 Draws the robot body. More...
 

Private Attributes

float angular_speed_
 Radius of robot if shape is circular. More...
 
std::vector< CGuiCO2 * > co2_sensors_
 Robot Rfid antenna sensors. More...
 
geometry_msgs::Pose2D current_pose_
 Robot footprint if not circular. More...
 
stdr_msgs::FootprintMsg footprint_
 Visualization image. More...
 
std::string frame_id_
 Initial robot pose. More...
 
geometry_msgs::Pose2D initial_pose_
 Current robot pose. More...
 
std::vector< CGuiLaser * > lasers_
 Robot sonar sensors. More...
 
float linear_speed_
 Robot current linear speed by Y. More...
 
float linear_speed_y_
 Robot current angular speed. More...
 
float radius_
 Map resolution. More...
 
float resolution_
 Robot laser sensors. More...
 
std::vector< CGuiRfid * > rfids_
 Robot Rfid antenna sensors. More...
 
bool robot_initialized_
 Check for start. More...
 
bool show_circles_
 True when robot is initialized. More...
 
bool show_label_
 < If true the robot's label is visible More...
 
std::vector< CGuiSonar * > sonars_
 Robot Rfid antenna sensors. More...
 
std::vector< CGuiSound * > sound_sensors_
 Robot frame id. More...
 
ros::Subscriber speeds_subscriber_
 Robot current linear speed. More...
 
bool started_
 Subscriber for the speeds twist message. More...
 
std::vector< CGuiThermal * > thermal_sensors_
 Robot Rfid antenna sensors. More...
 
QImage visualization
 
char visualization_status_
 

Detailed Description

Implements the functionalities for a robot.

Definition at line 43 of file stdr_gui_robot.h.

Constructor & Destructor Documentation

stdr_gui::CGuiRobot::CGuiRobot ( const stdr_msgs::RobotIndexedMsg &  msg)

Default contructor.

Parameters
msg[const stdr_msgs::RobotIndexedMsg&] The robot description msg
Returns
void

Definition at line 31 of file stdr_gui_robot.cpp.

stdr_gui::CGuiRobot::~CGuiRobot ( void  )

Default destructor.

Returns
void

Definition at line 263 of file stdr_gui_robot.cpp.

Member Function Documentation

bool stdr_gui::CGuiRobot::checkEventProximity ( QPoint  p)

Checks if the robot is near a specific point.

Parameters
p[QPoint] A point
Returns
bool : True if the robot is in proximity with p

Definition at line 251 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::destroy ( void  )

Destroys the robot object.

Returns
void

Definition at line 272 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::draw ( QImage *  m,
float  ocgd,
tf::TransformListener listener 
)

Paints the robot and it's sensors to the image.

Parameters
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
Returns
void

Definition at line 95 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::drawLabel ( QImage *  m,
float  ocgd 
)

Draws the robot's label.

Parameters
m[QImage*] The image to be drawn
ocgd[float] The map's resolution
Returns
void

Definition at line 298 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::drawSelf ( QImage *  m)
private

Draws the robot body.

Parameters
m[QImage*] The image for the robot to draw itself
Returns
voidThe robot visibility status
Parameters
m[QImage*] The image for the robot to draw itself
Returns
void

Definition at line 167 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.

Parameters
frame_id[std::string] The rfid reader frame id
Returns
char
Parameters
frame_id[std::string] The co2 sensor frame id
Returns
char

Definition at line 477 of file stdr_gui_robot.cpp.

QPoint stdr_gui::CGuiRobot::getCurrentPose ( void  )

Returns the current robot pose.

Returns
QPoint : The current robot pose

Definition at line 369 of file stdr_gui_robot.cpp.

geometry_msgs::Pose2D stdr_gui::CGuiRobot::getCurrentPoseM ( void  )

Returns the current robot pose in meters.

Returns
geometry_msgs::Pose2D : The current robot pose

Definition at line 379 of file stdr_gui_robot.cpp.

std::string stdr_gui::CGuiRobot::getFrameId ( void  )

Returns the frame id of the specific robot.

Returns
std::string : The robot frame id

Definition at line 287 of file stdr_gui_robot.cpp.

int stdr_gui::CGuiRobot::getLasersNumber ( void  )

Returns the lasers number.

Returns
int : the lasers number

Definition at line 388 of file stdr_gui_robot.cpp.

char stdr_gui::CGuiRobot::getLaserVisualizationStatus ( std::string  frame_id)

Returns the laser visibility status.

Parameters
frame_id[std::string] The laser frame id
Returns
char

Definition at line 443 of file stdr_gui_robot.cpp.

char stdr_gui::CGuiRobot::getRfidReaderVisualizationStatus ( std::string  frame_id)

Returns the rfid reader visibility status.

Parameters
frame_id[std::string] The rfid reader frame id
Returns
char

Definition at line 460 of file stdr_gui_robot.cpp.

bool stdr_gui::CGuiRobot::getShowLabel ( void  )

Gets the show_label_ flag.

Returns
bool : show_label_

Definition at line 342 of file stdr_gui_robot.cpp.

int stdr_gui::CGuiRobot::getSonarsNumber ( void  )

Returns the sonars number.

Returns
int : the sonars number

Definition at line 397 of file stdr_gui_robot.cpp.

char stdr_gui::CGuiRobot::getSonarVisualizationStatus ( std::string  frame_id)

Returns the sonar visibility status.

Parameters
frame_id[std::string] The sonar frame id
Returns
char

Definition at line 544 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.

Parameters
frame_id[std::string] The rfid reader frame id
Returns
char
Parameters
frame_id[std::string] The sound sensor frame id
Returns
char

Definition at line 511 of file stdr_gui_robot.cpp.

std::vector< float > stdr_gui::CGuiRobot::getSpeeds ( void  )

Returns the current robot speed.

Returns
std::vector<float> : The linear and angular speeds

Definition at line 679 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.

Parameters
frame_id[std::string] The rfid reader frame id
Returns
char
Parameters
frame_id[std::string] The thermal sensor frame id
Returns
char

Definition at line 494 of file stdr_gui_robot.cpp.

QImage stdr_gui::CGuiRobot::getVisualization ( float  ocgd)

Returns the visualization image of the robot.

Returns the visibility status.

Parameters
ocgd[float] The map resolution
Returns
QImage : The drawn image
char

Definition at line 406 of file stdr_gui_robot.cpp.

char stdr_gui::CGuiRobot::getVisualizationStatus ( void  )

Returns the visibility status.

Returns
char

Definition at line 637 of file stdr_gui_robot.cpp.

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.

Parameters
env_tags[stdr_msgs::RfidTagVector] The tag vector
Returns
void

Definition at line 704 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 724 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::setEnvironmentalTags ( stdr_msgs::RfidTagVector  env_tags)

Sets the tags existent in the environment.

Parameters
env_tags[stdr_msgs::RfidTagVector] The tag vector
Returns
void

Definition at line 693 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 714 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::setShowLabel ( bool  b)

Sets the show_label_ flag.

Parameters
b[bool] True for showing the label
Returns
void

Definition at line 333 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::speedsCallback ( const geometry_msgs::Twist &  msg)

Callback for the ros laser message.

Parameters
msg[const sensor_msgs::LaserScan&] The new laser scan message
Returns
void

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.

Parameters
frame_id[std::string] The rfid reader frame id
Returns
void
Parameters
frame_id[std::string] The co2 sensor frame id
Returns
void

Definition at line 592 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::toggleLaserVisualizationStatus ( std::string  frame_id)

Toggles the laser visibility status.

Parameters
frame_id[std::string] The laser frame id
Returns
void

Definition at line 528 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::toggleRfidReaderVisualizationStatus ( std::string  frame_id)

Toggles the rfid reader visibility status.

Parameters
frame_id[std::string] The rfid reader frame id
Returns
void

Definition at line 577 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::toggleShowCircles ( void  )

Toggles the show_circles_ flag.

Returns
void

Definition at line 360 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::toggleShowLabel ( void  )

Toggles the show_label_ flag.

Gets the show_label_ flag.

Returns
void
bool : show_label_

Definition at line 351 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::toggleSonarVisualizationStatus ( std::string  frame_id)

Toggles the sonar visibility status.

Parameters
frame_id[std::string] The sonar frame id
Returns
void

Definition at line 561 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.

Parameters
frame_id[std::string] The rfid reader frame id
Returns
void
Parameters
frame_id[std::string] The sound sensor frame id
Returns
void

Definition at line 622 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.

Parameters
frame_id[std::string] The rfid reader frame id
Returns
void
Parameters
frame_id[std::string] The thermal sensor frame id
Returns
void

Definition at line 607 of file stdr_gui_robot.cpp.

void stdr_gui::CGuiRobot::toggleVisualizationStatus ( void  )

Toggles the visibility status.

Returns
void

Definition at line 646 of file stdr_gui_robot.cpp.

Member Data Documentation

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 80 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 87 of file stdr_gui_robot.h.

geometry_msgs::Pose2D stdr_gui::CGuiRobot::initial_pose_
private

Current robot pose.

Definition at line 89 of file stdr_gui_robot.h.

std::vector<CGuiLaser*> stdr_gui::CGuiRobot::lasers_
private

Robot sonar sensors.

Definition at line 74 of file stdr_gui_robot.h.

float stdr_gui::CGuiRobot::linear_speed_
private

Robot current linear speed by Y.

Definition at line 62 of file stdr_gui_robot.h.

float stdr_gui::CGuiRobot::linear_speed_y_
private

Robot current angular speed.

Definition at line 64 of file stdr_gui_robot.h.

float stdr_gui::CGuiRobot::radius_
private

Map resolution.

Definition at line 69 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 78 of file stdr_gui_robot.h.

bool stdr_gui::CGuiRobot::robot_initialized_
private

Check for start.

Definition at line 53 of file stdr_gui_robot.h.

bool stdr_gui::CGuiRobot::show_circles_
private

True when robot is initialized.

Definition at line 51 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 49 of file stdr_gui_robot.h.

std::vector<CGuiSonar*> stdr_gui::CGuiRobot::sonars_
private

Robot Rfid antenna sensors.

Definition at line 76 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.

ros::Subscriber stdr_gui::CGuiRobot::speeds_subscriber_
private

Robot current linear speed.

Definition at line 59 of file stdr_gui_robot.h.

bool stdr_gui::CGuiRobot::started_
private

Subscriber for the speeds twist message.

Definition at line 56 of file stdr_gui_robot.h.

std::vector<CGuiThermal*> stdr_gui::CGuiRobot::thermal_sensors_
private

Robot Rfid antenna sensors.

Definition at line 82 of file stdr_gui_robot.h.

QImage stdr_gui::CGuiRobot::visualization
private

Definition at line 97 of file stdr_gui_robot.h.

char stdr_gui::CGuiRobot::visualization_status_
private

Definition at line 107 of file stdr_gui_robot.h.


The documentation for this class was generated from the following files:


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