stdr_gui_laser.h
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16  Authors :
17  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
21 
22 #ifndef STDR_GUI_LASER_CONTAINER
23 #define STDR_GUI_LASER_CONTAINER
24 
25 #include "stdr_gui/stdr_tools.h"
26 #include "stdr_msgs/LaserSensorMsg.h"
27 #include "sensor_msgs/LaserScan.h"
28 
33 namespace stdr_gui
34 {
39  class CGuiLaser
40  {
41  //------------------------------------------------------------------------//
42  private:
43 
45  bool lock_;
47  std::string topic_;
48 
50  std::string tf_frame_;
51 
53  stdr_msgs::LaserSensorMsg msg_;
54 
57 
59  sensor_msgs::LaserScan scan_;
60 
63 
64  //------------------------------------------------------------------------//
65  public:
66 
73  CGuiLaser(stdr_msgs::LaserSensorMsg msg,std::string baseTopic);
74 
79  ~CGuiLaser(void);
80 
86  void callback(const sensor_msgs::LaserScan& msg);
87 
95  void paint(QImage *m,float ocgd,tf::TransformListener *listener);
96 
104  void visualizerPaint(QImage *m,float ocgd,float maxRange);
105 
110  float getMaxRange(void);
111 
116  char getVisualizationStatus(void);
117 
122  void toggleVisualizationStatus(void);
123 
129  void setVisualizationStatus(char vs);
130 
135  std::string getFrameId(void);
136  };
137 }
138 
139 #endif
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 setVisualizationStatus(char vs)
Sets the visibility status of the specific laser sensor.
CGuiLaser(stdr_msgs::LaserSensorMsg msg, std::string baseTopic)
Default contructor.
~CGuiLaser(void)
Default destructor.
ros::Subscriber subscriber_
The ros laser scan msg.
sensor_msgs::LaserScan scan_
Visualization status of the specific laser.
void callback(const sensor_msgs::LaserScan &msg)
Callback for the ros laser message.
void visualizerPaint(QImage *m, float ocgd, float maxRange)
Paints the laser scan in it's own visualizer.
std::string topic_
The ROS tf frame.
stdr_msgs::LaserSensorMsg msg_
Subscriber for the ros laser msg.
void toggleVisualizationStatus(void)
Toggles the visibility status of the specific laser sensor.
The main namespace for STDR GUI.
void paint(QImage *m, float ocgd, tf::TransformListener *listener)
Paints the laser scan in the map image.
std::string getFrameId(void)
Returns the frame id of the specific laser sensor.
bool lock_
< Used to avoid drawing when a new laser message arives
Implements the functionalities for a laser sensor.
std::string tf_frame_
A laser sensor message : Depscription of a laser sensor.


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