Implements the functionalities of the sonar visualization widget. Inherits form QWidget and Ui_sonarVisualization (auto created from ui file) More...
#include <stdr_sonar_visualization.h>
Public Member Functions | |
void | callback (const sensor_msgs::Range &msg) |
Called when new laser data are available. | |
void | closeEvent (QCloseEvent *event) |
Called when the close event is triggered. | |
CSonarVisualisation (QString name, float resolution) | |
Default contructor. | |
void | destruct (void) |
Destroys the visualizer. | |
bool | getActive (void) |
Returns true if the visualizer is active. | |
void | paint (void) |
Paints the visualizer. | |
void | setSonar (stdr_msgs::SonarSensorMsg msg) |
Sets the sonar description message. | |
~CSonarVisualisation (void) | |
Default destructor. | |
Private Attributes | |
bool | active_ |
< True if the visualizer is active | |
stdr_msgs::SonarSensorMsg | msg_ |
The laser frame id. | |
QString | name_ |
sensor_msgs::Range | range_ |
Subscriber for getting the sonar ranges. | |
float | resolution_ |
The latest sonar range. | |
ros::Subscriber | subscriber_ |
Description of the sonar sensor. |
Implements the functionalities of the sonar visualization widget. Inherits form QWidget and Ui_sonarVisualization (auto created from ui file)
Definition at line 39 of file stdr_sonar_visualization.h.
stdr_gui::CSonarVisualisation::CSonarVisualisation | ( | QString | name, |
float | resolution | ||
) |
Default contructor.
name | [QString] Sonar frame id |
resolution | [float] Map resolution |
Definition at line 32 of file stdr_sonar_visualization.cpp.
void stdr_gui::CSonarVisualisation::callback | ( | const sensor_msgs::Range & | msg | ) |
Called when new laser data are available.
msg | [const sensor_msgs::Range&] The new sonar data |
Definition at line 111 of file stdr_sonar_visualization.cpp.
void stdr_gui::CSonarVisualisation::closeEvent | ( | QCloseEvent * | event | ) |
Called when the close event is triggered.
event | [QCloseEvent*] The close event |
Definition at line 78 of file stdr_sonar_visualization.cpp.
void stdr_gui::CSonarVisualisation::destruct | ( | void | ) |
bool stdr_gui::CSonarVisualisation::getActive | ( | void | ) |
Returns true if the visualizer is active.
Definition at line 89 of file stdr_sonar_visualization.cpp.
void stdr_gui::CSonarVisualisation::paint | ( | void | ) |
void stdr_gui::CSonarVisualisation::setSonar | ( | stdr_msgs::SonarSensorMsg | msg | ) |
Sets the sonar description message.
msg | [stdr_msgs::SonarSensorMsg] The sonar description |
Definition at line 99 of file stdr_sonar_visualization.cpp.
bool stdr_gui::CSonarVisualisation::active_ [private] |
< True if the visualizer is active
The map resolution
Definition at line 47 of file stdr_sonar_visualization.h.
stdr_msgs::SonarSensorMsg stdr_gui::CSonarVisualisation::msg_ [private] |
The laser frame id.
Definition at line 55 of file stdr_sonar_visualization.h.
QString stdr_gui::CSonarVisualisation::name_ [private] |
Definition at line 56 of file stdr_sonar_visualization.h.
sensor_msgs::Range stdr_gui::CSonarVisualisation::range_ [private] |
Subscriber for getting the sonar ranges.
Definition at line 51 of file stdr_sonar_visualization.h.
float stdr_gui::CSonarVisualisation::resolution_ [private] |
The latest sonar range.
Definition at line 49 of file stdr_sonar_visualization.h.
Description of the sonar sensor.
Definition at line 53 of file stdr_sonar_visualization.h.