Implements the functionalities for a sonar sensor. More...
#include <stdr_gui_sonar.h>
Public Member Functions | |
void | callback (const sensor_msgs::Range &msg) |
Callback for the ros sonar message. | |
CGuiSonar (stdr_msgs::SonarSensorMsg msg, std::string baseTopic) | |
Default contructor. | |
std::string | getFrameId (void) |
Returns the frame id of the specific sonar sensor. | |
float | getMaxRange (void) |
Returns the max range of the specific sonar sensor. | |
char | getVisualizationStatus (void) |
Returns the visibility status of the specific sonar sensor. | |
void | paint (QImage *m, float ocgd, tf::TransformListener *listener) |
Paints the sonar range in the map image. | |
void | setVisualizationStatus (char vs) |
Sets the visibility status of the specific sonar sensor. | |
void | toggleVisualizationStatus (void) |
Toggles the visibility status of the specific sonar sensor. | |
void | visualizerPaint (QImage *m, float ocgd, float maxRange) |
Paints the sonar range in it's own visualizer. | |
~CGuiSonar (void) | |
Default destructor. | |
Private Attributes | |
bool | lock_ |
< Used to avoid drawing when a new sonar message arives | |
stdr_msgs::SonarSensorMsg | msg_ |
Subscriber for the ros sensor msg. | |
sensor_msgs::Range | range_ |
Visualization status of the specific sonar. | |
ros::Subscriber | subscriber_ |
The ros sonar range msg. | |
std::string | tf_frame_ |
A sonar sensor message : Depscription of a sonar sensor. | |
std::string | topic_ |
The ROS tf frame. | |
char | visualization_status_ |
Implements the functionalities for a sonar sensor.
Definition at line 41 of file stdr_gui_sonar.h.
stdr_gui::CGuiSonar::CGuiSonar | ( | stdr_msgs::SonarSensorMsg | msg, |
std::string | baseTopic | ||
) |
Default contructor.
msg | [stdr_msgs::SonarSensorMsg] The sonar description msg |
baseTopic | [std::string] The ros topic for subscription |
Definition at line 32 of file stdr_gui_sonar.cpp.
stdr_gui::CGuiSonar::~CGuiSonar | ( | void | ) |
void stdr_gui::CGuiSonar::callback | ( | const sensor_msgs::Range & | msg | ) |
Callback for the ros sonar message.
msg | [const sensor_msgs::Range&] The new sonar range message |
Definition at line 57 of file stdr_gui_sonar.cpp.
std::string stdr_gui::CGuiSonar::getFrameId | ( | void | ) |
Returns the frame id of the specific sonar sensor.
Definition at line 227 of file stdr_gui_sonar.cpp.
float stdr_gui::CGuiSonar::getMaxRange | ( | void | ) |
Returns the max range of the specific sonar sensor.
Definition at line 200 of file stdr_gui_sonar.cpp.
char stdr_gui::CGuiSonar::getVisualizationStatus | ( | void | ) |
Returns the visibility status of the specific sonar sensor.
Definition at line 209 of file stdr_gui_sonar.cpp.
void stdr_gui::CGuiSonar::paint | ( | QImage * | m, |
float | ocgd, | ||
tf::TransformListener * | listener | ||
) |
Paints the sonar range in the map image.
m | [QImage*] The image to be drawn |
ocgd | [float] The map's resolution |
listener | [tf::TransformListener *] ROS tf transform listener |
< Find transformation
< Draw laser stuff
Definition at line 73 of file stdr_gui_sonar.cpp.
void stdr_gui::CGuiSonar::setVisualizationStatus | ( | char | vs | ) |
Sets the visibility status of the specific sonar sensor.
vs | [char] The new visibility status |
Definition at line 237 of file stdr_gui_sonar.cpp.
void stdr_gui::CGuiSonar::toggleVisualizationStatus | ( | void | ) |
Toggles the visibility status of the specific sonar sensor.
Definition at line 218 of file stdr_gui_sonar.cpp.
void stdr_gui::CGuiSonar::visualizerPaint | ( | QImage * | m, |
float | ocgd, | ||
float | maxRange | ||
) |
Paints the sonar range in it's own visualizer.
m | [QImage*] The image to be drawn |
ocgd | [float] The map's resolution |
maxRange | [float] The maximum range of all the robot sensors. Used for the visualizer proportions |
Definition at line 153 of file stdr_gui_sonar.cpp.
bool stdr_gui::CGuiSonar::lock_ [private] |
< Used to avoid drawing when a new sonar message arives
The ROS topic to which the subscription must be made for the new values to be taken
Definition at line 47 of file stdr_gui_sonar.h.
stdr_msgs::SonarSensorMsg stdr_gui::CGuiSonar::msg_ [private] |
Subscriber for the ros sensor msg.
Definition at line 53 of file stdr_gui_sonar.h.
sensor_msgs::Range stdr_gui::CGuiSonar::range_ [private] |
Visualization status of the specific sonar.
Definition at line 57 of file stdr_gui_sonar.h.
The ros sonar range msg.
Definition at line 55 of file stdr_gui_sonar.h.
std::string stdr_gui::CGuiSonar::tf_frame_ [private] |
A sonar sensor message : Depscription of a sonar sensor.
Definition at line 51 of file stdr_gui_sonar.h.
std::string stdr_gui::CGuiSonar::topic_ [private] |
The ROS tf frame.
Definition at line 49 of file stdr_gui_sonar.h.
char stdr_gui::CGuiSonar::visualization_status_ [private] |
Definition at line 58 of file stdr_gui_sonar.h.