stdr_gui_sonar.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 
23 #ifndef STDR_GUI_SONAR_CONTAINER
24 #define STDR_GUI_SONAR_CONTAINER
25 
26 #include "stdr_gui/stdr_tools.h"
27 #include "stdr_msgs/SonarSensorMsg.h"
28 #include "sensor_msgs/Range.h"
29 
34 namespace stdr_gui
35 {
36 
41  class CGuiSonar
42  {
43  //------------------------------------------------------------------------//
44  private:
46  bool lock_;
48  std::string topic_;
50  std::string tf_frame_;
52  stdr_msgs::SonarSensorMsg msg_;
56  sensor_msgs::Range range_;
59 
60  //------------------------------------------------------------------------//
61  public:
62 
69  CGuiSonar(stdr_msgs::SonarSensorMsg msg,std::string baseTopic);
70 
75  ~CGuiSonar(void);
76 
82  void callback(const sensor_msgs::Range& msg);
83 
91  void paint(QImage *m,float ocgd,tf::TransformListener *listener);
92 
100  void visualizerPaint(QImage *m,float ocgd,float maxRange);
101 
106  float getMaxRange(void);
107 
112  std::string getFrameId(void);
113 
118  char getVisualizationStatus(void);
119 
124  void toggleVisualizationStatus(void);
125 
131  void setVisualizationStatus(char vs);
132  };
133 }
134 
135 #endif
~CGuiSonar(void)
Default destructor.
stdr_msgs::SonarSensorMsg msg_
Subscriber for the ros sensor msg.
char getVisualizationStatus(void)
Returns the visibility status of the specific sonar sensor.
void toggleVisualizationStatus(void)
Toggles the visibility status of the specific sonar sensor.
std::string topic_
The ROS tf frame.
void callback(const sensor_msgs::Range &msg)
Callback for the ros sonar message.
sensor_msgs::Range range_
Visualization status of the specific sonar.
Implements the functionalities for a sonar sensor.
bool lock_
< Used to avoid drawing when a new sonar message arives
CGuiSonar(stdr_msgs::SonarSensorMsg msg, std::string baseTopic)
Default contructor.
std::string tf_frame_
A sonar sensor message : Depscription of a sonar sensor.
std::string getFrameId(void)
Returns the frame id of the specific sonar sensor.
void paint(QImage *m, float ocgd, tf::TransformListener *listener)
Paints the sonar range in the map image.
The main namespace for STDR GUI.
float getMaxRange(void)
Returns the max range of the specific sonar sensor.
void setVisualizationStatus(char vs)
Sets the visibility status of the specific sonar sensor.
void visualizerPaint(QImage *m, float ocgd, float maxRange)
Paints the sonar range in it&#39;s own visualizer.
ros::Subscriber subscriber_
The ros sonar range msg.


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