Public Member Functions | Private Attributes | List of all members
stdr_gui::CGuiLaser Class Reference

Implements the functionalities for a laser sensor. More...

#include <stdr_gui_laser.h>

Public Member Functions

void callback (const sensor_msgs::LaserScan &msg)
 Callback for the ros laser message. More...
 
 CGuiLaser (stdr_msgs::LaserSensorMsg msg, std::string baseTopic)
 Default contructor. More...
 
std::string getFrameId (void)
 Returns the frame id of the specific laser sensor. More...
 
float getMaxRange (void)
 Returns the max range of the specific laser sensor. More...
 
char getVisualizationStatus (void)
 Returns the visibility status of the specific laser sensor. More...
 
void paint (QImage *m, float ocgd, tf::TransformListener *listener)
 Paints the laser scan in the map image. More...
 
void setVisualizationStatus (char vs)
 Sets the visibility status of the specific laser sensor. More...
 
void toggleVisualizationStatus (void)
 Toggles the visibility status of the specific laser sensor. More...
 
void visualizerPaint (QImage *m, float ocgd, float maxRange)
 Paints the laser scan in it's own visualizer. More...
 
 ~CGuiLaser (void)
 Default destructor. More...
 

Private Attributes

bool lock_
 < Used to avoid drawing when a new laser message arives More...
 
stdr_msgs::LaserSensorMsg msg_
 Subscriber for the ros laser msg. More...
 
sensor_msgs::LaserScan scan_
 Visualization status of the specific laser. More...
 
ros::Subscriber subscriber_
 The ros laser scan msg. More...
 
std::string tf_frame_
 A laser sensor message : Depscription of a laser sensor. More...
 
std::string topic_
 The ROS tf frame. More...
 
char visualization_status_
 

Detailed Description

Implements the functionalities for a laser sensor.

Definition at line 39 of file stdr_gui_laser.h.

Constructor & Destructor Documentation

stdr_gui::CGuiLaser::CGuiLaser ( stdr_msgs::LaserSensorMsg  msg,
std::string  baseTopic 
)

Default contructor.

Parameters
msg[stdr_msgs::LaserSensorMsg] The laser description msg
baseTopic[std::string] The ros topic for subscription
Returns
void

Definition at line 32 of file stdr_gui_laser.cpp.

stdr_gui::CGuiLaser::~CGuiLaser ( void  )

Default destructor.

Returns
void

Definition at line 47 of file stdr_gui_laser.cpp.

Member Function Documentation

void stdr_gui::CGuiLaser::callback ( const sensor_msgs::LaserScan &  msg)

Callback for the ros laser message.

Parameters
msg[const sensor_msgs::LaserScan&] The new laser scan message
Returns
void

Definition at line 74 of file stdr_gui_laser.cpp.

std::string stdr_gui::CGuiLaser::getFrameId ( void  )

Returns the frame id of the specific laser sensor.

Returns
std::string : The laser frame id

Definition at line 221 of file stdr_gui_laser.cpp.

float stdr_gui::CGuiLaser::getMaxRange ( void  )

Returns the max range of the specific laser sensor.

Returns
void

Definition at line 212 of file stdr_gui_laser.cpp.

char stdr_gui::CGuiLaser::getVisualizationStatus ( void  )

Returns the visibility status of the specific laser sensor.

Returns
void

Definition at line 55 of file stdr_gui_laser.cpp.

void stdr_gui::CGuiLaser::paint ( QImage *  m,
float  ocgd,
tf::TransformListener listener 
)

Paints the laser scan in the map image.

Parameters
m[QImage*] The image to be drawn
ocgd[float] The map's resolution
listener[tf::TransformListener *] ROS tf transform listener
Returns
void

< Find transformation

< Draw laser stuff

Definition at line 90 of file stdr_gui_laser.cpp.

void stdr_gui::CGuiLaser::setVisualizationStatus ( char  vs)

Sets the visibility status of the specific laser sensor.

Parameters
vs[char] The new visibility status
Returns
void

Definition at line 231 of file stdr_gui_laser.cpp.

void stdr_gui::CGuiLaser::toggleVisualizationStatus ( void  )

Toggles the visibility status of the specific laser sensor.

Returns
void

Definition at line 64 of file stdr_gui_laser.cpp.

void stdr_gui::CGuiLaser::visualizerPaint ( QImage *  m,
float  ocgd,
float  maxRange 
)

Paints the laser scan in it's own visualizer.

Parameters
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
Returns
void

Definition at line 165 of file stdr_gui_laser.cpp.

Member Data Documentation

bool stdr_gui::CGuiLaser::lock_
private

< Used to avoid drawing when a new laser message arives

The ROS topic to which the subscription must be made for the new values to be taken

Definition at line 45 of file stdr_gui_laser.h.

stdr_msgs::LaserSensorMsg stdr_gui::CGuiLaser::msg_
private

Subscriber for the ros laser msg.

Definition at line 53 of file stdr_gui_laser.h.

sensor_msgs::LaserScan stdr_gui::CGuiLaser::scan_
private

Visualization status of the specific laser.

Definition at line 59 of file stdr_gui_laser.h.

ros::Subscriber stdr_gui::CGuiLaser::subscriber_
private

The ros laser scan msg.

Definition at line 56 of file stdr_gui_laser.h.

std::string stdr_gui::CGuiLaser::tf_frame_
private

A laser sensor message : Depscription of a laser sensor.

Definition at line 50 of file stdr_gui_laser.h.

std::string stdr_gui::CGuiLaser::topic_
private

The ROS tf frame.

Definition at line 47 of file stdr_gui_laser.h.

char stdr_gui::CGuiLaser::visualization_status_
private

Definition at line 62 of file stdr_gui_laser.h.


The documentation for this class was generated from the following files:


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Mon Jun 10 2019 15:15:17