Public Member Functions | Private Member Functions | Private Attributes
stdr_gui::CGuiRobot Class Reference

Implements the functionalities for a robot. More...

#include <stdr_gui_robot.h>

List of all members.

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::vector< 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 linear speed by Y.
float linear_speed_y_
 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_

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.

Default destructor.

Returns:
void

Definition at line 263 of file stdr_gui_robot.cpp.


Member Function Documentation

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.

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:
void The 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.

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.

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.

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.

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.

Gets the show_label_ flag.

Returns:
bool : show_label_

Definition at line 342 of file stdr_gui_robot.cpp.

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.

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.

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.

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.

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.

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.

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.

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.

Toggles the show_circles_ flag.

Returns:
void

Definition at line 360 of file stdr_gui_robot.cpp.

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.

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.

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.

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.

Toggles the visibility status.

Returns:
void

Definition at line 646 of file stdr_gui_robot.cpp.


Member Data Documentation

Radius of robot if shape is circular.

Definition at line 68 of file stdr_gui_robot.h.

std::vector<CGuiCO2*> stdr_gui::CGuiRobot::co2_sensors_ [private]

Robot Rfid antenna sensors.

Definition at line 81 of file stdr_gui_robot.h.

geometry_msgs::Pose2D stdr_gui::CGuiRobot::current_pose_ [private]

Robot footprint if not circular.

Definition at line 93 of file stdr_gui_robot.h.

stdr_msgs::FootprintMsg stdr_gui::CGuiRobot::footprint_ [private]

Visualization image.

Definition at line 96 of file stdr_gui_robot.h.

std::string stdr_gui::CGuiRobot::frame_id_ [private]

Initial robot pose.

Definition at line 88 of file stdr_gui_robot.h.

geometry_msgs::Pose2D stdr_gui::CGuiRobot::initial_pose_ [private]

Current robot pose.

Definition at line 90 of file stdr_gui_robot.h.

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

Robot sonar sensors.

Definition at line 75 of file stdr_gui_robot.h.

Robot current linear speed by Y.

Definition at line 63 of file stdr_gui_robot.h.

Robot current angular speed.

Definition at line 65 of file stdr_gui_robot.h.

Map resolution.

Definition at line 70 of file stdr_gui_robot.h.

Robot laser sensors.

Definition at line 73 of file stdr_gui_robot.h.

std::vector<CGuiRfid*> stdr_gui::CGuiRobot::rfids_ [private]

Robot Rfid antenna sensors.

Definition at line 79 of file stdr_gui_robot.h.

Check for start.

Definition at line 55 of file stdr_gui_robot.h.

True when robot is initialized.

Definition at line 52 of file stdr_gui_robot.h.

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

Robot frame id.

Definition at line 86 of file stdr_gui_robot.h.

Robot current linear speed.

Definition at line 61 of file stdr_gui_robot.h.

Subscriber for the speeds twist message.

Definition at line 58 of file stdr_gui_robot.h.

Robot Rfid antenna sensors.

Definition at line 83 of file stdr_gui_robot.h.

Definition at line 97 of file stdr_gui_robot.h.

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 Tue Feb 7 2017 03:46:43