Implements the functionalities of the laser visualization widget. Inherits form QWidget and Ui_laserVisualization (auto created from ui file) More...
#include <stdr_laser_visualization.h>

Public Member Functions | |
| void | callback (const sensor_msgs::LaserScan &msg) |
| Called when new laser data are available. More... | |
| CLaserVisualisation (QString name, float resolution) | |
| Default contructor. More... | |
| void | closeEvent (QCloseEvent *event) |
| Called when the close event is triggered. More... | |
| void | destruct (void) |
| Destroys the visualizer. More... | |
| bool | getActive (void) |
| Returns true if the visualizer is active. More... | |
| void | paint (void) |
| Paints the visualizer. More... | |
| void | setLaser (stdr_msgs::LaserSensorMsg msg) |
| Sets the laser description message. More... | |
| ~CLaserVisualisation (void) | |
| Default destructor. More... | |
Private Attributes | |
| bool | active_ |
| < True if the visualizer is active More... | |
| QImage | internal_image_ |
| A void image. More... | |
| stdr_msgs::LaserSensorMsg | msg_ |
| The image to draw into. More... | |
| QString | name_ |
| float | resolution_ |
| The latest laser scan. More... | |
| sensor_msgs::LaserScan | scan_ |
| Subscriber for getting the laser scans. More... | |
| ros::Subscriber | subscriber_ |
| Description of the laser sensor. More... | |
| QImage | void_image_ |
| The laser frame id. More... | |
Implements the functionalities of the laser visualization widget. Inherits form QWidget and Ui_laserVisualization (auto created from ui file)
Definition at line 38 of file stdr_laser_visualization.h.
| stdr_gui::CLaserVisualisation::CLaserVisualisation | ( | QString | name, |
| float | resolution | ||
| ) |
Default contructor.
| name | [QString] Laser frame id |
| resolution | [float] Map resolution |
Definition at line 33 of file stdr_laser_visualization.cpp.
| stdr_gui::CLaserVisualisation::~CLaserVisualisation | ( | void | ) |
| void stdr_gui::CLaserVisualisation::callback | ( | const sensor_msgs::LaserScan & | msg | ) |
Called when new laser data are available.
| msg | [const sensor_msgs::LaserScan&] The new laser data |
Definition at line 119 of file stdr_laser_visualization.cpp.
| void stdr_gui::CLaserVisualisation::closeEvent | ( | QCloseEvent * | event | ) |
Called when the close event is triggered.
| event | [QCloseEvent*] The close event |
Definition at line 86 of file stdr_laser_visualization.cpp.
| void stdr_gui::CLaserVisualisation::destruct | ( | void | ) |
| bool stdr_gui::CLaserVisualisation::getActive | ( | void | ) |
Returns true if the visualizer is active.
Definition at line 97 of file stdr_laser_visualization.cpp.
| void stdr_gui::CLaserVisualisation::paint | ( | void | ) |
| void stdr_gui::CLaserVisualisation::setLaser | ( | stdr_msgs::LaserSensorMsg | msg | ) |
Sets the laser description message.
| msg | [stdr_msgs::LaserSensorMsg] The laser description |
Definition at line 107 of file stdr_laser_visualization.cpp.
|
private |
< True if the visualizer is active
The map resolution
Definition at line 46 of file stdr_laser_visualization.h.
|
private |
A void image.
Definition at line 59 of file stdr_laser_visualization.h.
|
private |
The image to draw into.
Definition at line 56 of file stdr_laser_visualization.h.
|
private |
Definition at line 63 of file stdr_laser_visualization.h.
|
private |
The latest laser scan.
Definition at line 48 of file stdr_laser_visualization.h.
|
private |
Subscriber for getting the laser scans.
Definition at line 51 of file stdr_laser_visualization.h.
|
private |
Description of the laser sensor.
Definition at line 53 of file stdr_laser_visualization.h.
|
private |
The laser frame id.
Definition at line 61 of file stdr_laser_visualization.h.