22 #ifndef STDR_SONAR_VISUALIZATION 23 #define STDR_SONAR_VISUALIZATION 26 #include "ui_sonarVisualization.h" 27 #include "sensor_msgs/Range.h" 41 public Ui_sonarVisualization
54 stdr_msgs::SonarSensorMsg
msg_;
84 void setSonar(stdr_msgs::SonarSensorMsg msg);
104 void callback(
const sensor_msgs::Range& msg);
Implements the functionalities of the sonar visualization widget. Inherits form QWidget and Ui_sonarV...
void closeEvent(QCloseEvent *event)
Called when the close event is triggered.
CSonarVisualisation(QString name, float resolution)
Default contructor.
~CSonarVisualisation(void)
Default destructor.
void callback(const sensor_msgs::Range &msg)
Called when new laser data are available.
void destruct(void)
Destroys the visualizer.
void paint(void)
Paints the visualizer.
sensor_msgs::Range range_
Subscriber for getting the sonar ranges.
stdr_msgs::SonarSensorMsg msg_
The laser frame id.
The main namespace for STDR GUI.
void setSonar(stdr_msgs::SonarSensorMsg msg)
Sets the sonar description message.
ros::Subscriber subscriber_
Description of the sonar sensor.
float resolution_
The latest sonar range.
bool getActive(void)
Returns true if the visualizer is active.
bool active_
< True if the visualizer is active