GazeboRosVelodyneLaser.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-2021, 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 static_assert(GAZEBO_MAJOR_VERSION > 2, "Gazebo version is too old");
58 
59 #if GAZEBO_GPU_RAY
60 #define RaySensor GpuRaySensor
61 #define STR_Gpu "Gpu"
62 #define STR_GPU_ "GPU "
63 #else
64 #define STR_Gpu ""
65 #define STR_GPU_ ""
66 #endif
67 
68 namespace gazebo
69 {
70 // Register this plugin with the simulator
71 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosVelodyneLaser)
72 
73 // Constructor
75 GazeboRosVelodyneLaser::GazeboRosVelodyneLaser() : nh_(NULL), gaussian_noise_(0), min_range_(0), max_range_(0)
76 {
77 }
78 
80 // Destructor
82 {
84  // Finalize the controller / Custom Callback Queue
87  if (nh_) {
88  nh_->shutdown();
89  delete nh_;
90  nh_ = NULL;
91  }
93 }
94 
96 // Load the controller
97 void GazeboRosVelodyneLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
98 {
99  // Load plugin
100  RayPlugin::Load(_parent, _sdf);
101 
102  // Initialize Gazebo node
103  gazebo_node_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
104  gazebo_node_->Init();
105 
106  // Get the parent ray sensor
107 #if GAZEBO_MAJOR_VERSION >= 7
108  parent_ray_sensor_ = std::dynamic_pointer_cast<sensors::RaySensor>(_parent);
109 #else
110  parent_ray_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(_parent);
111 #endif
112  if (!parent_ray_sensor_) {
113  gzthrow("GazeboRosVelodyne" << STR_Gpu << "Laser controller requires a " << STR_Gpu << "Ray Sensor as its parent");
114  }
115 
116  robot_namespace_ = "/";
117  if (_sdf->HasElement("robotNamespace")) {
118  robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>();
119  }
120 
121  if (!_sdf->HasElement("frameName")) {
122  ROS_INFO("Velodyne laser plugin missing <frameName>, defaults to /world");
123  frame_name_ = "/world";
124  } else {
125  frame_name_ = _sdf->GetElement("frameName")->Get<std::string>();
126  }
127 
128  if (!_sdf->HasElement("organize_cloud")) {
129  ROS_INFO("Velodyne laser plugin missing <organize_cloud>, defaults to false");
130  organize_cloud_ = false;
131  } else {
132  organize_cloud_ = _sdf->GetElement("organize_cloud")->Get<bool>();
133  }
134 
135  if (!_sdf->HasElement("min_range")) {
136  ROS_INFO("Velodyne laser plugin missing <min_range>, defaults to 0");
137  min_range_ = 0;
138  } else {
139  min_range_ = _sdf->GetElement("min_range")->Get<double>();
140  }
141 
142  if (!_sdf->HasElement("max_range")) {
143  ROS_INFO("Velodyne laser plugin missing <max_range>, defaults to infinity");
144  max_range_ = INFINITY;
145  } else {
146  max_range_ = _sdf->GetElement("max_range")->Get<double>();
147  }
148 
149  min_intensity_ = std::numeric_limits<double>::lowest();
150  if (!_sdf->HasElement("min_intensity")) {
151  ROS_INFO("Velodyne laser plugin missing <min_intensity>, defaults to no clipping");
152  } else {
153  min_intensity_ = _sdf->GetElement("min_intensity")->Get<double>();
154  }
155 
156  if (!_sdf->HasElement("topicName")) {
157  ROS_INFO("Velodyne laser plugin missing <topicName>, defaults to /points");
158  topic_name_ = "/points";
159  } else {
160  topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
161  }
162 
163  if (!_sdf->HasElement("gaussianNoise")) {
164  ROS_INFO("Velodyne laser plugin missing <gaussianNoise>, defaults to 0.0");
165  gaussian_noise_ = 0;
166  } else {
167  gaussian_noise_ = _sdf->GetElement("gaussianNoise")->Get<double>();
168  }
169 
170  // Make sure the ROS node for Gazebo has already been initialized
171  if (!ros::isInitialized()) {
172  ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
173  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
174  return;
175  }
176 
177  // Create node handle
179 
180  // Resolve tf prefix
181  std::string prefix;
182  nh_->getParam(std::string("tf_prefix"), prefix);
183  if (robot_namespace_ != "/") {
184  prefix = robot_namespace_;
185  }
186  boost::trim_right_if(prefix, boost::is_any_of("/"));
188 
189  // Advertise publisher with a custom callback queue
190  if (topic_name_ != "") {
191  ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::PointCloud2>(
192  topic_name_, 1,
193  boost::bind(&GazeboRosVelodyneLaser::ConnectCb, this),
194  boost::bind(&GazeboRosVelodyneLaser::ConnectCb, this),
196  pub_ = nh_->advertise(ao);
197  }
198 
199  // Sensor generation off by default
200  parent_ray_sensor_->SetActive(false);
201 
202  // Start custom queue for laser
203  callback_laser_queue_thread_ = boost::thread( boost::bind( &GazeboRosVelodyneLaser::laserQueueThread,this ) );
204 
205 #if GAZEBO_MAJOR_VERSION >= 7
206  ROS_INFO("Velodyne %slaser plugin ready, %i lasers", STR_GPU_, parent_ray_sensor_->VerticalRangeCount());
207 #else
208  ROS_INFO("Velodyne %slaser plugin ready, %i lasers", STR_GPU_, parent_ray_sensor_->GetVerticalRangeCount());
209 #endif
210 }
211 
213 // Subscribe on-demand
215 {
216  boost::lock_guard<boost::mutex> lock(lock_);
217  if (pub_.getNumSubscribers()) {
218  if (!sub_) {
219 #if GAZEBO_MAJOR_VERSION >= 7
220  sub_ = gazebo_node_->Subscribe(this->parent_ray_sensor_->Topic(), &GazeboRosVelodyneLaser::OnScan, this);
221 #else
222  sub_ = gazebo_node_->Subscribe(this->parent_ray_sensor_->GetTopic(), &GazeboRosVelodyneLaser::OnScan, this);
223 #endif
224  }
225  parent_ray_sensor_->SetActive(true);
226  } else {
227 #if GAZEBO_MAJOR_VERSION >= 7
228  if (sub_) {
229  sub_->Unsubscribe();
230  sub_.reset();
231  }
232 #endif
233  parent_ray_sensor_->SetActive(false);
234  }
235 }
236 
237 void GazeboRosVelodyneLaser::OnScan(ConstLaserScanStampedPtr& _msg)
238 {
239 #if GAZEBO_MAJOR_VERSION >= 7
240  const ignition::math::Angle maxAngle = parent_ray_sensor_->AngleMax();
241  const ignition::math::Angle minAngle = parent_ray_sensor_->AngleMin();
242 
243  const double maxRange = parent_ray_sensor_->RangeMax();
244  const double minRange = parent_ray_sensor_->RangeMin();
245 
246  const int rayCount = parent_ray_sensor_->RayCount();
247  const int rangeCount = parent_ray_sensor_->RangeCount();
248 
249  const int verticalRayCount = parent_ray_sensor_->VerticalRayCount();
250  const int verticalRangeCount = parent_ray_sensor_->VerticalRangeCount();
251 
252  const ignition::math::Angle verticalMaxAngle = parent_ray_sensor_->VerticalAngleMax();
253  const ignition::math::Angle verticalMinAngle = parent_ray_sensor_->VerticalAngleMin();
254 #else
255  math::Angle maxAngle = parent_ray_sensor_->GetAngleMax();
256  math::Angle minAngle = parent_ray_sensor_->GetAngleMin();
257 
258  const double maxRange = parent_ray_sensor_->GetRangeMax();
259  const double minRange = parent_ray_sensor_->GetRangeMin();
260 
261  const int rayCount = parent_ray_sensor_->GetRayCount();
262  const int rangeCount = parent_ray_sensor_->GetRangeCount();
263 
264  const int verticalRayCount = parent_ray_sensor_->GetVerticalRayCount();
265  const int verticalRangeCount = parent_ray_sensor_->GetVerticalRangeCount();
266 
267  const math::Angle verticalMaxAngle = parent_ray_sensor_->GetVerticalAngleMax();
268  const math::Angle verticalMinAngle = parent_ray_sensor_->GetVerticalAngleMin();
269 #endif
270 
271  const double yDiff = maxAngle.Radian() - minAngle.Radian();
272  const double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
273 
274  const double MIN_RANGE = std::max(min_range_, minRange);
275  const double MAX_RANGE = std::min(max_range_, maxRange);
276  const double MIN_INTENSITY = min_intensity_;
277 
278  // Populate message fields
279  const uint32_t POINT_STEP = 22;
280  sensor_msgs::PointCloud2 msg;
281  msg.header.frame_id = frame_name_;
282  msg.header.stamp = ros::Time(_msg->time().sec(), _msg->time().nsec());
283  msg.fields.resize(6);
284  msg.fields[0].name = "x";
285  msg.fields[0].offset = 0;
286  msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
287  msg.fields[0].count = 1;
288  msg.fields[1].name = "y";
289  msg.fields[1].offset = 4;
290  msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
291  msg.fields[1].count = 1;
292  msg.fields[2].name = "z";
293  msg.fields[2].offset = 8;
294  msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
295  msg.fields[2].count = 1;
296  msg.fields[3].name = "intensity";
297  msg.fields[3].offset = 12;
298  msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
299  msg.fields[3].count = 1;
300  msg.fields[4].name = "ring";
301  msg.fields[4].offset = 16;
302  msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
303  msg.fields[4].count = 1;
304  msg.fields[5].name = "time";
305  msg.fields[5].offset = 18;
306  msg.fields[5].datatype = sensor_msgs::PointField::FLOAT32;
307  msg.fields[5].count = 1;
308  msg.data.resize(verticalRangeCount * rangeCount * POINT_STEP);
309 
310  int i, j;
311  uint8_t *ptr = msg.data.data();
312  for (i = 0; i < rangeCount; i++) {
313  for (j = 0; j < verticalRangeCount; j++) {
314 
315  // Range
316  double r = _msg->scan().ranges(i + j * rangeCount);
317  // Intensity
318  double intensity = _msg->scan().intensities(i + j * rangeCount);
319  // Ignore points that lay outside range bands or optionally, beneath a
320  // minimum intensity level.
321  if ((MIN_RANGE >= r) || (r >= MAX_RANGE) || (intensity < MIN_INTENSITY) ) {
322  if (!organize_cloud_) {
323  continue;
324  }
325  }
326 
327  // Noise
328  if (gaussian_noise_ != 0.0) {
330  }
331 
332  // Get angles of ray to get xyz for point
333  double yAngle;
334  double pAngle;
335 
336  if (rangeCount > 1) {
337  yAngle = i * yDiff / (rangeCount -1) + minAngle.Radian();
338  } else {
339  yAngle = minAngle.Radian();
340  }
341 
342  if (verticalRayCount > 1) {
343  pAngle = j * pDiff / (verticalRangeCount -1) + verticalMinAngle.Radian();
344  } else {
345  pAngle = verticalMinAngle.Radian();
346  }
347 
348  // pAngle is rotated by yAngle:
349  if ((MIN_RANGE < r) && (r < MAX_RANGE)) {
350  *((float*)(ptr + 0)) = r * cos(pAngle) * cos(yAngle); // x
351  *((float*)(ptr + 4)) = r * cos(pAngle) * sin(yAngle); // y
352  *((float*)(ptr + 8)) = r * sin(pAngle); // z
353  *((float*)(ptr + 12)) = intensity; // intensity
354  *((uint16_t*)(ptr + 16)) = j; // ring
355  *((float*)(ptr + 18)) = 0.0; // time
356  ptr += POINT_STEP;
357  } else if (organize_cloud_) {
358  *((float*)(ptr + 0)) = nanf(""); // x
359  *((float*)(ptr + 4)) = nanf(""); // y
360  *((float*)(ptr + 8)) = nanf(""); // x
361  *((float*)(ptr + 12)) = nanf(""); // intensity
362  *((uint16_t*)(ptr + 16)) = j; // ring
363  *((float*)(ptr + 18)) = 0.0; // time
364  ptr += POINT_STEP;
365  }
366  }
367  }
368 
369  // Populate message with number of valid points
370  msg.data.resize(ptr - msg.data.data()); // Shrink to actual size
371  msg.point_step = POINT_STEP;
372  msg.is_bigendian = false;
373  if (organize_cloud_) {
374  msg.width = verticalRangeCount;
375  msg.height = msg.data.size() / POINT_STEP / msg.width;
376  msg.row_step = POINT_STEP * msg.width;
377  msg.is_dense = false;
378  } else {
379  msg.width = msg.data.size() / POINT_STEP;
380  msg.height = 1;
381  msg.row_step = msg.data.size();
382  msg.is_dense = true;
383  }
384 
385  // Publish output
386  pub_.publish(msg);
387 }
388 
389 // Custom Callback Queue
391 // Custom callback queue thread
393 {
394  while (nh_->ok()) {
396  }
397 }
398 
399 } // namespace gazebo
400 
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 Fri Apr 2 2021 02:51:11