GazeboRosVelodyneLaser.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-2018, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 
37 #include <algorithm>
38 #include <assert.h>
39 
40 #include <gazebo/physics/World.hh>
41 #include <gazebo/sensors/Sensor.hh>
42 #include <sdf/sdf.hh>
43 #include <sdf/Param.hh>
44 #include <gazebo/common/Exception.hh>
45 #if GAZEBO_GPU_RAY
46 #include <gazebo/sensors/GpuRaySensor.hh>
47 #else
48 #include <gazebo/sensors/RaySensor.hh>
49 #endif
50 #include <gazebo/sensors/SensorTypes.hh>
51 #include <gazebo/transport/Node.hh>
52 
53 #include <sensor_msgs/PointCloud2.h>
54 
55 #include <tf/tf.h>
56 
57 #if GAZEBO_GPU_RAY
58 #define RaySensor GpuRaySensor
59 #define STR_Gpu "Gpu"
60 #define STR_GPU_ "GPU "
61 #else
62 #define STR_Gpu ""
63 #define STR_GPU_ ""
64 #endif
65 
66 namespace gazebo
67 {
68 // Register this plugin with the simulator
69 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosVelodyneLaser)
70 
71 // Constructor
73 GazeboRosVelodyneLaser::GazeboRosVelodyneLaser() : nh_(NULL), gaussian_noise_(0), min_range_(0), max_range_(0)
74 {
75 }
76 
78 // Destructor
80 {
82  // Finalize the controller / Custom Callback Queue
85  if (nh_) {
86  nh_->shutdown();
87  delete nh_;
88  nh_ = NULL;
89  }
91 }
92 
94 // Load the controller
95 void GazeboRosVelodyneLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
96 {
97  // Load plugin
98  RayPlugin::Load(_parent, _sdf);
99 
100  // Initialize Gazebo node
101  gazebo_node_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
102  gazebo_node_->Init();
103 
104  // Get the parent ray sensor
105 #if GAZEBO_MAJOR_VERSION >= 7
106  parent_ray_sensor_ = std::dynamic_pointer_cast<sensors::RaySensor>(_parent);
107 #else
108  parent_ray_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(_parent);
109 #endif
110  if (!parent_ray_sensor_) {
111  gzthrow("GazeboRosVelodyne" << STR_Gpu << "Laser controller requires a " << STR_Gpu << "Ray Sensor as its parent");
112  }
113 
114  robot_namespace_ = "/";
115  if (_sdf->HasElement("robotNamespace")) {
116  robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>();
117  }
118 
119  if (!_sdf->HasElement("frameName")) {
120  ROS_INFO("Velodyne laser plugin missing <frameName>, defaults to /world");
121  frame_name_ = "/world";
122  } else {
123  frame_name_ = _sdf->GetElement("frameName")->Get<std::string>();
124  }
125 
126  if (!_sdf->HasElement("min_range")) {
127  ROS_INFO("Velodyne laser plugin missing <min_range>, defaults to 0");
128  min_range_ = 0;
129  } else {
130  min_range_ = _sdf->GetElement("min_range")->Get<double>();
131  }
132 
133  if (!_sdf->HasElement("max_range")) {
134  ROS_INFO("Velodyne laser plugin missing <max_range>, defaults to infinity");
135  max_range_ = INFINITY;
136  } else {
137  max_range_ = _sdf->GetElement("max_range")->Get<double>();
138  }
139 
140  min_intensity_ = std::numeric_limits<double>::lowest();
141  if (!_sdf->HasElement("min_intensity")) {
142  ROS_INFO("Velodyne laser plugin missing <min_intensity>, defaults to no clipping");
143  } else {
144  min_intensity_ = _sdf->GetElement("min_intensity")->Get<double>();
145  }
146 
147  if (!_sdf->HasElement("topicName")) {
148  ROS_INFO("Velodyne laser plugin missing <topicName>, defaults to /points");
149  topic_name_ = "/points";
150  } else {
151  topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
152  }
153 
154  if (!_sdf->HasElement("gaussianNoise")) {
155  ROS_INFO("Velodyne laser plugin missing <gaussianNoise>, defaults to 0.0");
156  gaussian_noise_ = 0;
157  } else {
158  gaussian_noise_ = _sdf->GetElement("gaussianNoise")->Get<double>();
159  }
160 
161  // Make sure the ROS node for Gazebo has already been initialized
162  if (!ros::isInitialized()) {
163  ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
164  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
165  return;
166  }
167 
168  // Create node handle
170 
171  // Resolve tf prefix
172  std::string prefix;
173  nh_->getParam(std::string("tf_prefix"), prefix);
174  if (robot_namespace_ != "/") {
175  prefix = robot_namespace_;
176  }
177  boost::trim_right_if(prefix, boost::is_any_of("/"));
179 
180  // Advertise publisher with a custom callback queue
181  if (topic_name_ != "") {
182  ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::PointCloud2>(
183  topic_name_, 1,
184  boost::bind(&GazeboRosVelodyneLaser::ConnectCb, this),
185  boost::bind(&GazeboRosVelodyneLaser::ConnectCb, this),
187  pub_ = nh_->advertise(ao);
188  }
189 
190  // Sensor generation off by default
191  parent_ray_sensor_->SetActive(false);
192 
193  // Start custom queue for laser
194  callback_laser_queue_thread_ = boost::thread( boost::bind( &GazeboRosVelodyneLaser::laserQueueThread,this ) );
195 
196 #if GAZEBO_MAJOR_VERSION >= 7
197  ROS_INFO("Velodyne %slaser plugin ready, %i lasers", STR_GPU_, parent_ray_sensor_->VerticalRangeCount());
198 #else
199  ROS_INFO("Velodyne %slaser plugin ready, %i lasers", STR_GPU_, parent_ray_sensor_->GetVerticalRangeCount());
200 #endif
201 }
202 
204 // Subscribe on-demand
206 {
207  boost::lock_guard<boost::mutex> lock(lock_);
208  if (pub_.getNumSubscribers()) {
209  if (!sub_) {
210 #if GAZEBO_MAJOR_VERSION >= 7
211  sub_ = gazebo_node_->Subscribe(this->parent_ray_sensor_->Topic(), &GazeboRosVelodyneLaser::OnScan, this);
212 #else
213  sub_ = gazebo_node_->Subscribe(this->parent_ray_sensor_->GetTopic(), &GazeboRosVelodyneLaser::OnScan, this);
214 #endif
215  }
216  parent_ray_sensor_->SetActive(true);
217  } else {
218 #if GAZEBO_MAJOR_VERSION >= 7
219  if (sub_) {
220  sub_->Unsubscribe();
221  sub_.reset();
222  }
223 #endif
224  parent_ray_sensor_->SetActive(false);
225  }
226 }
227 
228 void GazeboRosVelodyneLaser::OnScan(ConstLaserScanStampedPtr& _msg)
229 {
230 #if GAZEBO_MAJOR_VERSION >= 7
231  const ignition::math::Angle maxAngle = parent_ray_sensor_->AngleMax();
232  const ignition::math::Angle minAngle = parent_ray_sensor_->AngleMin();
233 
234  const double maxRange = parent_ray_sensor_->RangeMax();
235  const double minRange = parent_ray_sensor_->RangeMin();
236 
237  const int rayCount = parent_ray_sensor_->RayCount();
238  const int rangeCount = parent_ray_sensor_->RangeCount();
239 
240  const int verticalRayCount = parent_ray_sensor_->VerticalRayCount();
241  const int verticalRangeCount = parent_ray_sensor_->VerticalRangeCount();
242 
243  const ignition::math::Angle verticalMaxAngle = parent_ray_sensor_->VerticalAngleMax();
244  const ignition::math::Angle verticalMinAngle = parent_ray_sensor_->VerticalAngleMin();
245 #else
246  math::Angle maxAngle = parent_ray_sensor_->GetAngleMax();
247  math::Angle minAngle = parent_ray_sensor_->GetAngleMin();
248 
249  const double maxRange = parent_ray_sensor_->GetRangeMax();
250  const double minRange = parent_ray_sensor_->GetRangeMin();
251 
252  const int rayCount = parent_ray_sensor_->GetRayCount();
253  const int rangeCount = parent_ray_sensor_->GetRangeCount();
254 
255  const int verticalRayCount = parent_ray_sensor_->GetVerticalRayCount();
256  const int verticalRangeCount = parent_ray_sensor_->GetVerticalRangeCount();
257 
258  const math::Angle verticalMaxAngle = parent_ray_sensor_->GetVerticalAngleMax();
259  const math::Angle verticalMinAngle = parent_ray_sensor_->GetVerticalAngleMin();
260 #endif
261 
262  const double yDiff = maxAngle.Radian() - minAngle.Radian();
263  const double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
264 
265  const double MIN_RANGE = std::max(min_range_, minRange);
266  const double MAX_RANGE = std::min(max_range_, maxRange);
267  const double MIN_INTENSITY = min_intensity_;
268 
269  // Populate message fields
270  const uint32_t POINT_STEP = 32;
271  sensor_msgs::PointCloud2 msg;
272  msg.header.frame_id = frame_name_;
273  msg.header.stamp = ros::Time(_msg->time().sec(), _msg->time().nsec());
274  msg.fields.resize(5);
275  msg.fields[0].name = "x";
276  msg.fields[0].offset = 0;
277  msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
278  msg.fields[0].count = 1;
279  msg.fields[1].name = "y";
280  msg.fields[1].offset = 4;
281  msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
282  msg.fields[1].count = 1;
283  msg.fields[2].name = "z";
284  msg.fields[2].offset = 8;
285  msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
286  msg.fields[2].count = 1;
287  msg.fields[3].name = "intensity";
288  msg.fields[3].offset = 16;
289  msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
290  msg.fields[3].count = 1;
291  msg.fields[4].name = "ring";
292  msg.fields[4].offset = 20;
293  msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
294  msg.fields[4].count = 1;
295  msg.data.resize(verticalRangeCount * rangeCount * POINT_STEP);
296 
297  int i, j;
298  uint8_t *ptr = msg.data.data();
299  for (i = 0; i < rangeCount; i++) {
300  for (j = 0; j < verticalRangeCount; j++) {
301 
302  // Range
303  double r = _msg->scan().ranges(i + j * rangeCount);
304  // Intensity
305  double intensity = _msg->scan().intensities(i + j * rangeCount);
306  // Ignore points that lay outside range bands or optionally, beneath a
307  // minimum intensity level.
308  if ((MIN_RANGE >= r) || (r >= MAX_RANGE) || (intensity < MIN_INTENSITY) ) {
309  continue;
310  }
311 
312  // Noise
313  if (gaussian_noise_ != 0.0) {
315  }
316 
317  // Get angles of ray to get xyz for point
318  double yAngle;
319  double pAngle;
320 
321  if (rangeCount > 1) {
322  yAngle = i * yDiff / (rangeCount -1) + minAngle.Radian();
323  } else {
324  yAngle = minAngle.Radian();
325  }
326 
327  if (verticalRayCount > 1) {
328  pAngle = j * pDiff / (verticalRangeCount -1) + verticalMinAngle.Radian();
329  } else {
330  pAngle = verticalMinAngle.Radian();
331  }
332 
333  // pAngle is rotated by yAngle:
334  if ((MIN_RANGE < r) && (r < MAX_RANGE)) {
335  *((float*)(ptr + 0)) = r * cos(pAngle) * cos(yAngle);
336  *((float*)(ptr + 4)) = r * cos(pAngle) * sin(yAngle);
337 #if GAZEBO_MAJOR_VERSION > 2
338  *((float*)(ptr + 8)) = r * sin(pAngle);
339 #else
340  *((float*)(ptr + 8)) = -r * sin(pAngle);
341 #endif
342  *((float*)(ptr + 16)) = intensity;
343 #if GAZEBO_MAJOR_VERSION > 2
344  *((uint16_t*)(ptr + 20)) = j; // ring
345 #else
346  *((uint16_t*)(ptr + 20)) = verticalRangeCount - 1 - j; // ring
347 #endif
348  ptr += POINT_STEP;
349  }
350  }
351  }
352 
353  // Populate message with number of valid points
354  msg.point_step = POINT_STEP;
355  msg.row_step = ptr - msg.data.data();
356  msg.height = 1;
357  msg.width = msg.row_step / POINT_STEP;
358  msg.is_bigendian = false;
359  msg.is_dense = true;
360  msg.data.resize(msg.row_step); // Shrink to actual size
361 
362  // Publish output
363  pub_.publish(msg);
364 }
365 
366 // Custom Callback Queue
368 // Custom callback queue thread
370 {
371  while (nh_->ok()) {
373  }
374 }
375 
376 } // namespace gazebo
377 
void publish(const boost::shared_ptr< M > &message) const
void OnScan(const ConstLaserScanStampedPtr &_msg)
ros::NodeHandle * nh_
Pointer to ROS node.
sensors::RaySensorPtr parent_ray_sensor_
The parent ray sensor.
gazebo::transport::NodePtr gazebo_node_
ROSCPP_DECL bool isInitialized()
static double gaussianKernel(double mu, double sigma)
Gaussian noise generator.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
void ConnectCb()
Subscribe on-demand.
ros::Publisher pub_
ROS publisher.
std::string resolve(const std::string &prefix, const std::string &frame_name)
#define ROS_FATAL_STREAM(args)
#define STR_Gpu
#define ROS_INFO(...)
double gaussian_noise_
Gaussian noise.
gazebo::transport::SubscriberPtr sub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double min_range_
Minimum range to publish.
uint32_t getNumSubscribers() const
std::string robot_namespace_
For setting ROS name space.
bool getParam(const std::string &key, std::string &s) const
double max_range_
Maximum range to publish.
std::string frame_name_
frame transform name, should match link name
double min_intensity_
the intensity beneath which points will be filtered
bool ok() const
boost::mutex lock_
A mutex to lock access.
#define STR_GPU_
boost::shared_ptr< void > VoidPtr


velodyne_gazebo_plugins
Author(s): Kevin Hallenbeck
autogenerated on Mon Mar 11 2019 02:27:05