23 #ifndef STDR_GUI_SONAR_CONTAINER 24 #define STDR_GUI_SONAR_CONTAINER 27 #include "stdr_msgs/SonarSensorMsg.h" 28 #include "sensor_msgs/Range.h" 52 stdr_msgs::SonarSensorMsg
msg_;
69 CGuiSonar(stdr_msgs::SonarSensorMsg msg,std::string baseTopic);
82 void callback(
const sensor_msgs::Range& msg);
~CGuiSonar(void)
Default destructor.
stdr_msgs::SonarSensorMsg msg_
Subscriber for the ros sensor msg.
char getVisualizationStatus(void)
Returns the visibility status of the specific sonar sensor.
void toggleVisualizationStatus(void)
Toggles the visibility status of the specific sonar sensor.
std::string topic_
The ROS tf frame.
char visualization_status_
void callback(const sensor_msgs::Range &msg)
Callback for the ros sonar message.
sensor_msgs::Range range_
Visualization status of the specific sonar.
Implements the functionalities for a sonar sensor.
bool lock_
< Used to avoid drawing when a new sonar message arives
CGuiSonar(stdr_msgs::SonarSensorMsg msg, std::string baseTopic)
Default contructor.
std::string tf_frame_
A sonar sensor message : Depscription of a sonar sensor.
std::string getFrameId(void)
Returns the frame id of the specific sonar sensor.
void paint(QImage *m, float ocgd, tf::TransformListener *listener)
Paints the sonar range in the map image.
The main namespace for STDR GUI.
float getMaxRange(void)
Returns the max range of the specific sonar sensor.
void setVisualizationStatus(char vs)
Sets 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.
ros::Subscriber subscriber_
The ros sonar range msg.