Public Member Functions | Private Attributes
stdr_gui::CGuiLaser Class Reference

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

#include <stdr_gui_laser.h>

List of all members.

Public Member Functions

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

Private Attributes

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

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.

Returns the max range of the specific laser sensor.

Returns:
void

Definition at line 212 of file stdr_gui_laser.cpp.

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.

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.

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

< 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 46 of file stdr_gui_laser.h.

stdr_msgs::LaserSensorMsg stdr_gui::CGuiLaser::msg_ [private]

Subscriber for the ros laser msg.

Definition at line 55 of file stdr_gui_laser.h.

sensor_msgs::LaserScan stdr_gui::CGuiLaser::scan_ [private]

Visualization status of the specific laser.

Definition at line 61 of file stdr_gui_laser.h.

The ros laser scan msg.

Definition at line 58 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 52 of file stdr_gui_laser.h.

std::string stdr_gui::CGuiLaser::topic_ [private]

The ROS tf frame.

Definition at line 49 of file stdr_gui_laser.h.

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 Tue Feb 7 2017 03:46:43