stdr_gui_laser.cpp
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 
23 
24 namespace stdr_gui
25 {
32  CGuiLaser::CGuiLaser(stdr_msgs::LaserSensorMsg msg,std::string baseTopic):
33  msg_(msg)
34  {
35  topic_ = baseTopic + "/" + msg_.frame_id;
36  tf_frame_ = baseTopic + "_" + msg_.frame_id;
38  lock_ = false;
39  subscriber_ = n.subscribe(topic_.c_str(), 1, &CGuiLaser::callback,this);
41  }
42 
48  {
49  }
50 
56  {
57  return visualization_status_;
58  }
59 
65  {
67  }
68 
74  void CGuiLaser::callback(const sensor_msgs::LaserScan& msg)
75  {
76  if(lock_)
77  {
78  return;
79  }
80  scan_ = msg;
81  }
82 
91  QImage *m,
92  float ocgd,
93  tf::TransformListener *listener)
94  {
95  lock_ = true;
96  QPainter painter(m);
97  //~ painter.setRenderHint(QPainter::Antialiasing, true);
98 
100  tf::StampedTransform transform;
101 
102  try
103  {
104  listener->waitForTransform("map_static",
105  tf_frame_.c_str(),
106  ros::Time(0),
107  ros::Duration(0.2));
108  listener->lookupTransform("map_static",
109  tf_frame_.c_str(), ros::Time(0), transform);
110  }
111  catch (tf::TransformException ex)
112  {
113  ROS_DEBUG("%s",ex.what());
114  }
115  tfScalar roll,pitch,yaw;
116  float pose_x = transform.getOrigin().x();
117  float pose_y = transform.getOrigin().y();
118  transform.getBasis().getRPY(roll,pitch,yaw);
119  float pose_theta = yaw;
120 
122 
123  for(unsigned int i = 0 ; i < scan_.ranges.size() ; i++)
124  {
125  float real_dist = scan_.ranges[i];
126  if(real_dist > msg_.maxRange)
127  {
128  real_dist = msg_.maxRange;
129  painter.setPen(QColor(255,0,0,75 * (2 - visualization_status_)));
130  }
131  else if(real_dist < msg_.minRange)
132  {
133  real_dist = msg_.minRange;
134  painter.setPen(QColor(100,100,100,
135  75 * (2 - visualization_status_)));
136  }
137  else
138  {
139  painter.setPen(QColor(255,0,0,75 * (2 - visualization_status_)));
140  }
141  painter.drawLine(
142  pose_x / ocgd,
143 
144  pose_y / ocgd,
145 
146  pose_x / ocgd + real_dist *
147  cos(pose_theta + scan_.angle_min + i * scan_.angle_increment)
148  / ocgd,
149 
150  pose_y / ocgd + real_dist *
151  sin(pose_theta + scan_.angle_min + i * scan_.angle_increment)
152  / ocgd
153  );
154  }
155  lock_ = false;
156  }
157 
166  QImage *m,
167  float ocgd,
168  float maxRange)
169  {
170  lock_ = true;
171  QPainter painter(m);
172  float size = m->width();
173  float climax = size / maxRange * ocgd / 2.1;
174 
175  for(unsigned int i = 0 ; i < scan_.ranges.size() ; i++)
176  {
177  float real_dist = scan_.ranges[i];
178  if(real_dist > msg_.maxRange)
179  {
180  real_dist = msg_.maxRange;
181  painter.setPen(QColor(255,0,0,100));
182  }
183  else if(real_dist < msg_.minRange)
184  {
185  real_dist = msg_.minRange;
186  painter.setPen(QColor(100,100,100,100));
187  }
188  else
189  {
190  painter.setPen(QColor(255,0,0,100));
191  }
192 
193  painter.drawLine(
194  size / 2 + (msg_.pose.x / ocgd) * climax,
195  size / 2 + (msg_.pose.y / ocgd) * climax,
196 
197  size / 2 + ((msg_.pose.x / ocgd) + real_dist *
198  cos(scan_.angle_min + i * scan_.angle_increment + msg_.pose.theta)
199  / ocgd) * climax,
200  size / 2 + ((msg_.pose.y / ocgd) + real_dist *
201  sin(scan_.angle_min + i * scan_.angle_increment + msg_.pose.theta)
202  / ocgd) * climax
203  );
204  }
205  lock_ = false;
206  }
207 
213  {
214  return msg_.maxRange;
215  }
216 
221  std::string CGuiLaser::getFrameId(void)
222  {
223  return msg_.frame_id;
224  }
225 
232  {
234  }
235 }
236 
float getMaxRange(void)
Returns the max range of the specific laser sensor.
char getVisualizationStatus(void)
Returns the visibility status of the specific laser sensor.
double tfScalar
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setVisualizationStatus(char vs)
Sets the visibility status of the specific laser sensor.
CGuiLaser(stdr_msgs::LaserSensorMsg msg, std::string baseTopic)
Default contructor.
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
~CGuiLaser(void)
Default destructor.
ros::Subscriber subscriber_
The ros laser scan msg.
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
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&#39;s own visualizer.
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
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.
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
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
std::string tf_frame_
A laser sensor message : Depscription of a laser sensor.
#define ROS_DEBUG(...)


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