gazebo_ros_range.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (Modified BSD License)
3  *
4  * Copyright (c) 2013-2015, PAL Robotics, S.L.
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 PAL Robotics, S.L. 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 
39 
40 #include <algorithm>
41 #include <string>
42 #include <assert.h>
43 
44 #include <gazebo/physics/World.hh>
45 #include <gazebo/physics/HingeJoint.hh>
46 #include <gazebo/sensors/Sensor.hh>
47 #include <gazebo/common/Exception.hh>
48 #include <gazebo/sensors/RaySensor.hh>
49 #include <gazebo/sensors/SensorTypes.hh>
50 
51 #ifdef ENABLE_PROFILER
52 #include <ignition/common/Profiler.hh>
53 #endif
54 
55 #include <sdf/sdf.hh>
56 #include <sdf/Param.hh>
57 
58 #include <tf/tf.h>
59 #include <ignition/math/Rand.hh>
60 
61 namespace gazebo
62 {
63 // Register this plugin with the simulator
64 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosRange)
65 
66 // Constructor
69 {
70 }
71 
73 // Destructor
75 {
76  this->range_queue_.clear();
77  this->range_queue_.disable();
78  this->rosnode_->shutdown();
79  this->callback_queue_thread_.join();
80 
81  delete this->rosnode_;
82 }
83 
85 // Load the controller
86 void GazeboRosRange::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
87 {
88  // load plugin
89  RayPlugin::Load(_parent, this->sdf);
90  // Get then name of the parent sensor
91  this->parent_sensor_ = _parent;
92  // Get the world name.
93  std::string worldName = _parent->WorldName();
94  this->world_ = physics::get_world(worldName);
95  // save pointers
96  this->sdf = _sdf;
97 
98  this->last_update_time_ = common::Time(0);
99 
101  this->parent_ray_sensor_ =
102  dynamic_pointer_cast<sensors::RaySensor>(this->parent_sensor_);
103 
104  if (!this->parent_ray_sensor_)
105  gzthrow("GazeboRosRange controller requires a Ray Sensor as its parent");
106 
107  this->robot_namespace_ = "";
108  if (this->sdf->HasElement("robotNamespace"))
109  this->robot_namespace_ = this->sdf->Get<std::string>("robotNamespace") + "/";
110 
111  if (!this->sdf->HasElement("frameName"))
112  {
113  ROS_INFO_NAMED("range", "Range plugin missing <frameName>, defaults to /world");
114  this->frame_name_ = "/world";
115  }
116  else
117  this->frame_name_ = this->sdf->Get<std::string>("frameName");
118 
119  if (!this->sdf->HasElement("topicName"))
120  {
121  ROS_INFO_NAMED("range", "Range plugin missing <topicName>, defaults to /range");
122  this->topic_name_ = "/range";
123  }
124  else
125  this->topic_name_ = this->sdf->Get<std::string>("topicName");
126 
127  if (!this->sdf->HasElement("radiation"))
128  {
129  ROS_WARN_NAMED("range", "Range plugin missing <radiation>, defaults to ultrasound");
130  this->radiation_ = "ultrasound";
131 
132  }
133  else
134  this->radiation_ = _sdf->GetElement("radiation")->Get<std::string>();
135 
136  if (!this->sdf->HasElement("fov"))
137  {
138  ROS_WARN_NAMED("range", "Range plugin missing <fov>, defaults to 0.05");
139  this->fov_ = 0.05;
140  }
141  else
142  this->fov_ = _sdf->GetElement("fov")->Get<double>();
143  if (!this->sdf->HasElement("gaussianNoise"))
144  {
145  ROS_INFO_NAMED("range", "Range plugin missing <gaussianNoise>, defaults to 0.0");
146  this->gaussian_noise_ = 0;
147  }
148  else
149  this->gaussian_noise_ = this->sdf->Get<double>("gaussianNoise");
150 
151  if (!this->sdf->HasElement("updateRate"))
152  {
153  ROS_INFO_NAMED("range", "Range plugin missing <updateRate>, defaults to 0");
154  this->update_rate_ = 0;
155  }
156  else
157  this->update_rate_ = this->sdf->Get<double>("updateRate");
158 
159  // prepare to throttle this plugin at the same rate
160  // ideally, we should invoke a plugin update when the sensor updates,
161  // have to think about how to do that properly later
162  if (this->update_rate_ > 0.0)
163  this->update_period_ = 1.0/this->update_rate_;
164  else
165  this->update_period_ = 0.0;
166 
167  this->range_connect_count_ = 0;
168 
169  this->range_msg_.header.frame_id = this->frame_name_;
170  if (this->radiation_==std::string("ultrasound"))
171  this->range_msg_.radiation_type = sensor_msgs::Range::ULTRASOUND;
172  else
173  this->range_msg_.radiation_type = sensor_msgs::Range::INFRARED;
174 
175  this->range_msg_.field_of_view = fov_;
176  this->range_msg_.max_range = this->parent_ray_sensor_->RangeMax();
177  this->range_msg_.min_range = this->parent_ray_sensor_->RangeMin();
178 
179  // Init ROS
180  if (ros::isInitialized())
181  {
182  // ros callback queue for processing subscription
183  this->deferred_load_thread_ = boost::thread(
184  boost::bind(&GazeboRosRange::LoadThread, this));
185  }
186  else
187  {
188  gzerr << "Not loading plugin since ROS hasn't been "
189  << "properly initialized. Try starting gazebo with ros plugin:\n"
190  << " gazebo -s libgazebo_ros_api_plugin.so\n";
191  }
192 }
193 
195 // Load the controller
197 {
198  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
199 
200  // resolve tf prefix
201  std::string prefix;
202  this->rosnode_->getParam(std::string("tf_prefix"), prefix);
203  this->frame_name_ = tf::resolve(prefix, this->frame_name_);
204 
205  if (this->topic_name_ != "")
206  {
208  ros::AdvertiseOptions::create<sensor_msgs::Range>(
209  this->topic_name_, 1,
210  boost::bind(&GazeboRosRange::RangeConnect, this),
211  boost::bind(&GazeboRosRange::RangeDisconnect, this),
212  ros::VoidPtr(), &this->range_queue_);
213  this->pub_ = this->rosnode_->advertise(ao);
214  }
215 
216 
217  // Initialize the controller
218 
219  // sensor generation off by default
220  this->parent_ray_sensor_->SetActive(false);
221  // start custom queue for range
222  this->callback_queue_thread_ =
223  boost::thread(boost::bind(&GazeboRosRange::RangeQueueThread, this));
224 }
225 
227 // Increment count
229 {
230  this->range_connect_count_++;
231  this->parent_ray_sensor_->SetActive(true);
232 }
234 // Decrement count
236 {
237  this->range_connect_count_--;
238 
239  if (this->range_connect_count_ == 0)
240  this->parent_ray_sensor_->SetActive(false);
241 }
242 
243 
245 // Update the plugin
247 {
248 #ifdef ENABLE_PROFILER
249  IGN_PROFILE("GazeboRosRange::OnNewLaserScans");
250 #endif
251  if (this->topic_name_ != "")
252  {
253 #if GAZEBO_MAJOR_VERSION >= 8
254  common::Time cur_time = this->world_->SimTime();
255 #else
256  common::Time cur_time = this->world_->GetSimTime();
257 #endif
258  if (cur_time < this->last_update_time_)
259  {
260  ROS_WARN_NAMED("range", "Negative sensor update time difference detected.");
261  this->last_update_time_ = cur_time;
262  }
263 
264  if (cur_time - this->last_update_time_ >= this->update_period_)
265  {
266  common::Time sensor_update_time =
267  this->parent_sensor_->LastUpdateTime();
268 #ifdef ENABLE_PROFILER
269  IGN_PROFILE_BEGIN("PutRangeData");
270 #endif
271  this->PutRangeData(sensor_update_time);
272 #ifdef ENABLE_PROFILER
273  IGN_PROFILE_END();
274 #endif
275  this->last_update_time_ = cur_time;
276  }
277  }
278  else
279  {
280  ROS_INFO_NAMED("range", "gazebo_ros_range topic name not set");
281  }
282 }
283 
285 // Put range data to the interface
286 void GazeboRosRange::PutRangeData(common::Time &_updateTime)
287 {
288  this->parent_ray_sensor_->SetActive(false);
289 
290  /***************************************************************/
291  /* */
292  /* point scan from ray sensor */
293  /* */
294  /***************************************************************/
295  {
296  boost::mutex::scoped_lock lock(this->lock_);
297  // Add Frame Name
298  this->range_msg_.header.frame_id = this->frame_name_;
299  this->range_msg_.header.stamp.sec = _updateTime.sec;
300  this->range_msg_.header.stamp.nsec = _updateTime.nsec;
301 
302  // find ray with minimal range
303  range_msg_.range = std::numeric_limits<sensor_msgs::Range::_range_type>::max();
304 
305  int num_ranges = parent_ray_sensor_->LaserShape()->GetSampleCount() * parent_ray_sensor_->LaserShape()->GetVerticalSampleCount();
306 
307  for(int i = 0; i < num_ranges; ++i)
308  {
309  double ray = parent_ray_sensor_->LaserShape()->GetRange(i);
310  if (ray < range_msg_.range)
311  range_msg_.range = ray;
312  }
313 
314  // add Gaussian noise and limit to min/max range
315  if (range_msg_.range < range_msg_.max_range)
316  range_msg_.range = std::min(range_msg_.range + this->GaussianKernel(0,gaussian_noise_), parent_ray_sensor_->RangeMax());
317 
318  this->parent_ray_sensor_->SetActive(true);
319 
320  // send data out via ros message
321  if (this->range_connect_count_ > 0 && this->topic_name_ != "")
322  this->pub_.publish(this->range_msg_);
323  }
324 }
325 
327 // Utility for adding noise
328 double GazeboRosRange::GaussianKernel(double mu, double sigma)
329 {
330  // using Box-Muller transform to generate two independent standard
331  // normally disbributed normal variables see wikipedia
332 
333  // normalized uniform random variable
334  double U = ignition::math::Rand::DblUniform();
335 
336  // normalized uniform random variable
337  double V = ignition::math::Rand::DblUniform();
338 
339  double X = sqrt(-2.0 * ::log(U)) * cos(2.0*M_PI * V);
340  // double Y = sqrt(-2.0 * ::log(U)) * sin(2.0*M_PI * V);
341 
342  // there are 2 indep. vars, we'll just use X
343  // scale to our mu and sigma
344  X = sigma * X + mu;
345  return X;
346 }
347 
349 // Put range data to the interface
351 {
352  static const double timeout = 0.01;
353 
354  while (this->rosnode_->ok())
355  {
357  }
358 }
359 }
gazebo::GazeboRosRange::parent_sensor_
sensors::SensorPtr parent_sensor_
The parent sensor.
Definition: gazebo_ros_range.h:93
gazebo::GazeboRosRange::pub_
ros::Publisher pub_
Definition: gazebo_ros_range.h:98
gazebo::GazeboRosRange::topic_name_
std::string topic_name_
topic name
Definition: gazebo_ros_range.h:104
boost::shared_ptr< void >
gazebo::GazeboRosRange::frame_name_
std::string frame_name_
frame transform name, should match link name
Definition: gazebo_ros_range.h:107
gazebo
gazebo::GazeboRosRange::PutRangeData
void PutRangeData(common::Time &_updateTime)
Put range data to the ROS topic.
Definition: gazebo_ros_range.cpp:286
gazebo::GazeboRosRange::range_connect_count_
int range_connect_count_
Keep track of number of connctions.
Definition: gazebo_ros_range.h:86
gazebo::GazeboRosRange::OnNewLaserScans
virtual void OnNewLaserScans()
Update the controller.
Definition: gazebo_ros_range.cpp:246
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
gazebo_ros_range.h
gazebo::GazeboRosRange::fov_
double fov_
sensor field of view
Definition: gazebo_ros_range.h:113
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosRange::range_msg_
sensor_msgs::Range range_msg_
ros message
Definition: gazebo_ros_range.h:101
gazebo::GazeboRosRange::RangeDisconnect
void RangeDisconnect()
Definition: gazebo_ros_range.cpp:235
gazebo::GazeboRosRange::GaussianKernel
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
Definition: gazebo_ros_range.cpp:328
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
gazebo::GazeboRosRange::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_range.h:97
gazebo::GazeboRosRange::radiation_
std::string radiation_
radiation type : ultrasound or infrared
Definition: gazebo_ros_range.h:110
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
gazebo::GazeboRosRange
Definition: gazebo_ros_range.h:66
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
gazebo::GazeboRosRange::LoadThread
void LoadThread()
Definition: gazebo_ros_range.cpp:196
ros::AdvertiseOptions
gazebo::GazeboRosRange::deferred_load_thread_
boost::thread deferred_load_thread_
Definition: gazebo_ros_range.h:141
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
gazebo::GazeboRosRange::lock_
boost::mutex lock_
mutex to lock access to fields that are used in message callbacks
Definition: gazebo_ros_range.h:121
gazebo::GazeboRosRange::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_range.h:136
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosRange::RangeConnect
void RangeConnect()
Definition: gazebo_ros_range.cpp:228
gazebo::GazeboRosRange::RangeQueueThread
void RangeQueueThread()
Definition: gazebo_ros_range.cpp:350
gazebo::GazeboRosRange::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_range.h:132
gazebo::GazeboRosRange::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_range.cpp:86
gazebo::GazeboRosRange::~GazeboRosRange
~GazeboRosRange()
Destructor.
Definition: gazebo_ros_range.cpp:74
gazebo::GazeboRosRange::range_queue_
ros::CallbackQueue range_queue_
Definition: gazebo_ros_range.h:134
tf.h
ros::NodeHandle::ok
bool ok() const
gazebo::GazeboRosRange::update_period_
double update_period_
Definition: gazebo_ros_range.h:128
gazebo::GazeboRosRange::update_rate_
double update_rate_
update rate of this sensor
Definition: gazebo_ros_range.h:127
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosRange::sdf
sdf::ElementPtr sdf
Definition: gazebo_ros_range.h:139
gazebo::GazeboRosRange::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_range.h:129
gazebo_ros_utils.h
ros::WallDuration
assert.h
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosRange::gaussian_noise_
double gaussian_noise_
Gaussian noise.
Definition: gazebo_ros_range.h:115
gazebo::GazeboRosRange::world_
physics::WorldPtr world_
Definition: gazebo_ros_range.h:91
ros::CallbackQueue::callAvailable
void callAvailable()
ros::CallbackQueue::disable
void disable()
GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
#define GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
Definition: gazebo_ros_utils.h:49
gazebo::GazeboRosRange::parent_ray_sensor_
sensors::RaySensorPtr parent_ray_sensor_
Definition: gazebo_ros_range.h:94
ros::NodeHandle


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28