gazebo_ros_block_laser.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2013 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 /*
18  * Desc: Ros Block Laser controller.
19  * Author: Nathan Koenig
20  * Date: 01 Feb 2007
21  */
22 
23 #include <algorithm>
24 #include <assert.h>
25 #include <limits>
26 
29 
30 #include <gazebo/physics/World.hh>
31 #include <gazebo/physics/HingeJoint.hh>
32 #include <gazebo/sensors/Sensor.hh>
33 #include <sdf/sdf.hh>
34 #include <sdf/Param.hh>
35 #include <gazebo/common/Exception.hh>
36 #include <gazebo/sensors/RaySensor.hh>
37 #include <gazebo/sensors/SensorTypes.hh>
38 #include <gazebo/transport/Node.hh>
39 
40 #ifdef ENABLE_PROFILER
41 #include <ignition/common/Profiler.hh>
42 #endif
43 
44 #include <geometry_msgs/Point32.h>
45 #include <sensor_msgs/ChannelFloat32.h>
46 
47 #include <tf/tf.h>
48 
49 #define EPSILON_DIFF 0.000001
50 
51 namespace gazebo
52 {
53 // Register this plugin with the simulator
54 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosBlockLaser)
55 
56 // Constructor
59 {
60 }
61 
63 // Destructor
65 {
67  // Finalize the controller / Custom Callback Queue
68  this->laser_queue_.clear();
69  this->laser_queue_.disable();
70  this->rosnode_->shutdown();
71  this->callback_laser_queue_thread_.join();
72 
73  delete this->rosnode_;
74 }
75 
77 // Load the controller
78 void GazeboRosBlockLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
79 {
80  // load plugin
81  RayPlugin::Load(_parent, _sdf);
82 
83  // Get then name of the parent sensor
84  this->parent_sensor_ = _parent;
85 
86  // Get the world name.
87  std::string worldName = _parent->WorldName();
88  this->world_ = physics::get_world(worldName);
89 
90 #if GAZEBO_MAJOR_VERSION >= 8
91  last_update_time_ = this->world_->SimTime();
92 #else
93  last_update_time_ = this->world_->GetSimTime();
94 #endif
95 
96  this->node_ = transport::NodePtr(new transport::Node());
97  this->node_->Init(worldName);
98 
100  this->parent_ray_sensor_ = dynamic_pointer_cast<sensors::RaySensor>(this->parent_sensor_);
101 
102  if (!this->parent_ray_sensor_)
103  gzthrow("GazeboRosBlockLaser controller requires a Ray Sensor as its parent");
104 
105  this->robot_namespace_ = "";
106  if (_sdf->HasElement("robotNamespace"))
107  this->robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
108 
109  if (!_sdf->HasElement("frameName"))
110  {
111  ROS_INFO_NAMED("block_laser", "Block laser plugin missing <frameName>, defaults to /world");
112  this->frame_name_ = "/world";
113  }
114  else
115  this->frame_name_ = _sdf->GetElement("frameName")->Get<std::string>();
116 
117  if (!_sdf->HasElement("topicName"))
118  {
119  ROS_INFO_NAMED("block_laser", "Block laser plugin missing <topicName>, defaults to /world");
120  this->topic_name_ = "/world";
121  }
122  else
123  this->topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
124 
125  if (!_sdf->HasElement("gaussianNoise"))
126  {
127  ROS_INFO_NAMED("block_laser", "Block laser plugin missing <gaussianNoise>, defaults to 0.0");
128  this->gaussian_noise_ = 0;
129  }
130  else
131  this->gaussian_noise_ = _sdf->GetElement("gaussianNoise")->Get<double>();
132 
133  if (!_sdf->HasElement("hokuyoMinIntensity"))
134  {
135  ROS_INFO_NAMED("block_laser", "Block laser plugin missing <hokuyoMinIntensity>, defaults to 101");
136  this->hokuyo_min_intensity_ = 101;
137  }
138  else
139  this->hokuyo_min_intensity_ = _sdf->GetElement("hokuyoMinIntensity")->Get<double>();
140 
141  ROS_DEBUG_NAMED("block_laser", "gazebo_ros_laser plugin should set minimum intensity to %f due to cutoff in hokuyo filters." , this->hokuyo_min_intensity_);
142 
143  if (!_sdf->HasElement("updateRate"))
144  {
145  ROS_INFO_NAMED("block_laser", "Block laser plugin missing <updateRate>, defaults to 0");
146  this->update_rate_ = 0;
147  }
148  else
149  this->update_rate_ = _sdf->GetElement("updateRate")->Get<double>();
150  // FIXME: update the update_rate_
151 
152 
153  this->laser_connect_count_ = 0;
154 
155  // Make sure the ROS node for Gazebo has already been initialized
156  if (!ros::isInitialized())
157  {
158  ROS_FATAL_STREAM_NAMED("block_laser", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
159  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
160  return;
161  }
162 
163  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
164 
165  // resolve tf prefix
166  std::string prefix;
167  this->rosnode_->getParam(std::string("tf_prefix"), prefix);
168  this->frame_name_ = tf::resolve(prefix, this->frame_name_);
169 
170  // set size of cloud message, starts at 0!! FIXME: not necessary
171  this->cloud_msg_.points.clear();
172  this->cloud_msg_.channels.clear();
173  this->cloud_msg_.channels.push_back(sensor_msgs::ChannelFloat32());
174 
175  if (this->topic_name_ != "")
176  {
177  // Custom Callback Queue
178  ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::PointCloud>(
179  this->topic_name_,1,
180  boost::bind( &GazeboRosBlockLaser::LaserConnect,this),
181  boost::bind( &GazeboRosBlockLaser::LaserDisconnect,this), ros::VoidPtr(), &this->laser_queue_);
182  this->pub_ = this->rosnode_->advertise(ao);
183  }
184 
185 
186  // Initialize the controller
187 
188  // sensor generation off by default
189  this->parent_ray_sensor_->SetActive(false);
190  // start custom queue for laser
191  this->callback_laser_queue_thread_ = boost::thread( boost::bind( &GazeboRosBlockLaser::LaserQueueThread,this ) );
192 
193 }
194 
196 // Increment count
198 {
199  this->laser_connect_count_++;
200  this->parent_ray_sensor_->SetActive(true);
201 }
203 // Decrement count
205 {
206  this->laser_connect_count_--;
207 
208  if (this->laser_connect_count_ == 0)
209  this->parent_ray_sensor_->SetActive(false);
210 }
211 
213 // Update the controller
215 {
216 #ifdef ENABLE_PROFILER
217  IGN_PROFILE("GazeboRosBlockLaser::OnNewLaserScans");
218 #endif
219  if (this->topic_name_ != "")
220  {
221  common::Time sensor_update_time = this->parent_sensor_->LastUpdateTime();
222  if (sensor_update_time < last_update_time_)
223  {
224  ROS_WARN_NAMED("block_laser", "Negative sensor update time difference detected.");
225  last_update_time_ = sensor_update_time;
226  }
227 
228  if (last_update_time_ < sensor_update_time)
229  {
230 #ifdef ENABLE_PROFILER
231  IGN_PROFILE_BEGIN("PutLaserData");
232 #endif
233  this->PutLaserData(sensor_update_time);
234 #ifdef ENABLE_PROFILER
235  IGN_PROFILE_END();
236 #endif
237  last_update_time_ = sensor_update_time;
238  }
239  }
240  else
241  {
242  ROS_INFO_NAMED("block_laser", "gazebo_ros_block_laser topic name not set");
243  }
244 }
245 
247 // Put laser data to the interface
248 void GazeboRosBlockLaser::PutLaserData(common::Time &_updateTime)
249 {
250  int i, hja, hjb;
251  int j, vja, vjb;
252  double vb, hb;
253  int j1, j2, j3, j4; // four corners indices
254  double r1, r2, r3, r4, r; // four corner values + interpolated range
255  double intensity;
256 
257  this->parent_ray_sensor_->SetActive(false);
258 
259  auto maxAngle = this->parent_ray_sensor_->AngleMax();
260  auto minAngle = this->parent_ray_sensor_->AngleMin();
261 
262  double maxRange = this->parent_ray_sensor_->RangeMax();
263  double minRange = this->parent_ray_sensor_->RangeMin();
264  int rayCount = this->parent_ray_sensor_->RayCount();
265  int rangeCount = this->parent_ray_sensor_->RangeCount();
266 
267  int verticalRayCount = this->parent_ray_sensor_->VerticalRayCount();
268  int verticalRangeCount = this->parent_ray_sensor_->VerticalRangeCount();
269  auto verticalMaxAngle = this->parent_ray_sensor_->VerticalAngleMax();
270  auto verticalMinAngle = this->parent_ray_sensor_->VerticalAngleMin();
271 
272  double yDiff = maxAngle.Radian() - minAngle.Radian();
273  double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
274 
275 
276  // set size of cloud message everytime!
277  //int r_size = rangeCount * verticalRangeCount;
278  this->cloud_msg_.points.clear();
279  this->cloud_msg_.channels.clear();
280  this->cloud_msg_.channels.push_back(sensor_msgs::ChannelFloat32());
281 
282  /***************************************************************/
283  /* */
284  /* point scan from laser */
285  /* */
286  /***************************************************************/
287  boost::mutex::scoped_lock sclock(this->lock);
288  // Add Frame Name
289  this->cloud_msg_.header.frame_id = this->frame_name_;
290  this->cloud_msg_.header.stamp.sec = _updateTime.sec;
291  this->cloud_msg_.header.stamp.nsec = _updateTime.nsec;
292 
293  for (j = 0; j<verticalRangeCount; j++)
294  {
295  // interpolating in vertical direction
296  vb = (verticalRangeCount == 1) ? 0 : (double) j * (verticalRayCount - 1) / (verticalRangeCount - 1);
297  vja = (int) floor(vb);
298  vjb = std::min(vja + 1, verticalRayCount - 1);
299  vb = vb - floor(vb); // fraction from min
300 
301  assert(vja >= 0 && vja < verticalRayCount);
302  assert(vjb >= 0 && vjb < verticalRayCount);
303 
304  for (i = 0; i<rangeCount; i++)
305  {
306  // Interpolate the range readings from the rays in horizontal direction
307  hb = (rangeCount == 1)? 0 : (double) i * (rayCount - 1) / (rangeCount - 1);
308  hja = (int) floor(hb);
309  hjb = std::min(hja + 1, rayCount - 1);
310  hb = hb - floor(hb); // fraction from min
311 
312  assert(hja >= 0 && hja < rayCount);
313  assert(hjb >= 0 && hjb < rayCount);
314 
315  // indices of 4 corners
316  j1 = hja + vja * rayCount;
317  j2 = hjb + vja * rayCount;
318  j3 = hja + vjb * rayCount;
319  j4 = hjb + vjb * rayCount;
320  // range readings of 4 corners
321  r1 = this->parent_ray_sensor_->LaserShape()->GetRange(j1);
322  r2 = this->parent_ray_sensor_->LaserShape()->GetRange(j2);
323  r3 = this->parent_ray_sensor_->LaserShape()->GetRange(j3);
324  r4 = this->parent_ray_sensor_->LaserShape()->GetRange(j4);
325 
326  // Range is linear interpolation if values are close,
327  // and min if they are very different
328  r = (1-vb)*((1 - hb) * r1 + hb * r2)
329  + vb *((1 - hb) * r3 + hb * r4);
330 
331  // REP 117 says readings too close to the sensor become -inf, and too far away +inf
332  if (r < minRange)
333  {
334  r = -std::numeric_limits<double>::infinity();
335  }
336  else if ( r > maxRange)
337  {
338  r = std::numeric_limits<double>::infinity();
339  }
340 
341  // Intensity is averaged
342  intensity = 0.25*(this->parent_ray_sensor_->LaserShape()->GetRetro(j1) +
343  this->parent_ray_sensor_->LaserShape()->GetRetro(j2) +
344  this->parent_ray_sensor_->LaserShape()->GetRetro(j3) +
345  this->parent_ray_sensor_->LaserShape()->GetRetro(j4));
346 
347  // std::cout << " block debug "
348  // << " ij("<<i<<","<<j<<")"
349  // << " j1234("<<j1<<","<<j2<<","<<j3<<","<<j4<<")"
350  // << " r1234("<<r1<<","<<r2<<","<<r3<<","<<r4<<")"
351  // << std::endl;
352 
353  // get angles of ray to get xyz for point
354  double yAngle = 0.5*(hja+hjb) * yDiff / (rayCount -1) + minAngle.Radian();
355  double pAngle = 0.5*(vja+vjb) * pDiff / (verticalRayCount -1) + verticalMinAngle.Radian();
356 
357  /***************************************************************/
358  /* */
359  /* point scan from laser */
360  /* */
361  /***************************************************************/
362  geometry_msgs::Point32 point;
363  //pAngle is rotated by yAngle:
364  point.x = r * cos(pAngle) * cos(yAngle);
365  point.y = r * cos(pAngle) * sin(yAngle);
366  point.z = r * sin(pAngle);
367 
368  if (fabs(maxRange - r) > EPSILON_DIFF)
369  {
370  // add noise to range only if not at max range
371  point.x += this->GaussianKernel(0, this->gaussian_noise_);
372  point.y += this->GaussianKernel(0, this->gaussian_noise_);
373  point.z += this->GaussianKernel(0, this->gaussian_noise_);
374  }
375  this->cloud_msg_.points.push_back(point);
376 
377  this->cloud_msg_.channels[0].values.push_back(intensity + this->GaussianKernel(0,this->gaussian_noise_)) ;
378  }
379  }
380  this->parent_ray_sensor_->SetActive(true);
381 
382  // send data out via ros message
383  this->pub_.publish(this->cloud_msg_);
384 
385 
386 
387 }
388 
389 
391 // Utility for adding noise
392 double GazeboRosBlockLaser::GaussianKernel(double mu,double sigma)
393 {
394  // using Box-Muller transform to generate two independent standard normally disbributed normal variables
395  // see wikipedia
396  double U = (double)rand()/(double)RAND_MAX; // normalized uniform random variable
397  double V = (double)rand()/(double)RAND_MAX; // normalized uniform random variable
398  double X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V);
399  //double Y = sqrt(-2.0 * ::log(U)) * sin( 2.0*M_PI * V); // the other indep. normal variable
400  // we'll just use X
401  // scale to our mu and sigma
402  X = sigma * X + mu;
403  return X;
404 }
405 
406 // Custom Callback Queue
408 // custom callback queue thread
410 {
411  static const double timeout = 0.01;
412 
413  while (this->rosnode_->ok())
414  {
416  }
417 }
418 
420 {
421  this->sim_time_ = msgs::Convert( _msg->sim_time() );
422 
423  ignition::math::Pose3d pose;
424  pose.Pos().X() = 0.5*sin(0.01*this->sim_time_.Double());
425  gzdbg << "plugin simTime [" << this->sim_time_.Double() << "] update pose [" << pose.Pos().X() << "]\n";
426 }
427 
428 
429 }
EPSILON_DIFF
#define EPSILON_DIFF
Definition: gazebo_ros_block_laser.cpp:49
gazebo::GazeboRosBlockLaser::laser_connect_count_
int laser_connect_count_
Keep track of number of connctions.
Definition: gazebo_ros_block_laser.h:71
boost::shared_ptr< void >
gazebo
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
gazebo::GazeboRosBlockLaser::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_block_laser.h:82
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosBlockLaser::OnStats
void OnStats(const boost::shared_ptr< msgs::WorldStatistics const > &_msg)
Definition: gazebo_ros_block_laser.cpp:419
gazebo::GazeboRosBlockLaser::callback_laser_queue_thread_
boost::thread callback_laser_queue_thread_
Definition: gazebo_ros_block_laser.h:116
gazebo::GazeboRosBlockLaser
Definition: gazebo_ros_block_laser.h:49
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
gazebo::GazeboRosBlockLaser::laser_queue_
ros::CallbackQueue laser_queue_
Definition: gazebo_ros_block_laser.h:114
gazebo::GazeboRosBlockLaser::hokuyo_min_intensity_
double hokuyo_min_intensity_
hack to mimic hokuyo intensity cutoff of 100
Definition: gazebo_ros_block_laser.h:105
gazebo::GazeboRosBlockLaser::world_
physics::WorldPtr world_
Definition: gazebo_ros_block_laser.h:76
gazebo_ros_block_laser.h
gazebo::GazeboRosBlockLaser::LaserConnect
void LaserConnect()
Definition: gazebo_ros_block_laser.cpp:197
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
gazebo::GazeboRosBlockLaser::lock
boost::mutex lock
A mutex to lock access to fields that are used in message callbacks.
Definition: gazebo_ros_block_laser.h:101
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::AdvertiseOptions
gazebo::GazeboRosBlockLaser::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_block_laser.h:111
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
gazebo::GazeboRosBlockLaser::topic_name_
std::string topic_name_
topic name
Definition: gazebo_ros_block_laser.h:89
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosBlockLaser::frame_name_
std::string frame_name_
frame transform name, should match link name
Definition: gazebo_ros_block_laser.h:92
gazebo::GazeboRosBlockLaser::~GazeboRosBlockLaser
~GazeboRosBlockLaser()
Destructor.
Definition: gazebo_ros_block_laser.cpp:64
gazebo::GazeboRosBlockLaser::GaussianKernel
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
Definition: gazebo_ros_block_laser.cpp:392
gazebo::GazeboRosBlockLaser::LaserDisconnect
void LaserDisconnect()
Definition: gazebo_ros_block_laser.cpp:204
gazebo::GazeboRosBlockLaser::parent_ray_sensor_
sensors::RaySensorPtr parent_ray_sensor_
Definition: gazebo_ros_block_laser.h:79
tf.h
ros::NodeHandle::ok
bool ok() const
gazebo::GazeboRosBlockLaser::parent_sensor_
sensors::SensorPtr parent_sensor_
The parent sensor.
Definition: gazebo_ros_block_laser.h:78
gazebo::GazeboRosBlockLaser::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_block_laser.h:68
gazebo::GazeboRosBlockLaser::pub_
ros::Publisher pub_
Definition: gazebo_ros_block_laser.h:83
gazebo::GazeboRosBlockLaser::LaserQueueThread
void LaserQueueThread()
Definition: gazebo_ros_block_laser.cpp:409
gazebo::GazeboRosBlockLaser::gaussian_noise_
double gaussian_noise_
Gaussian noise.
Definition: gazebo_ros_block_laser.h:95
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosBlockLaser::OnNewLaserScans
virtual void OnNewLaserScans()
Update the controller.
Definition: gazebo_ros_block_laser.cpp:214
gazebo::GazeboRosBlockLaser::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_block_laser.cpp:78
gazebo_ros_utils.h
gazebo::GazeboRosBlockLaser::node_
transport::NodePtr node_
Definition: gazebo_ros_block_laser.h:119
ros::WallDuration
assert.h
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosBlockLaser::sim_time_
common::Time sim_time_
Definition: gazebo_ros_block_laser.h:120
gazebo::GazeboRosBlockLaser::update_rate_
double update_rate_
update rate of this sensor
Definition: gazebo_ros_block_laser.h:108
gazebo::GazeboRosBlockLaser::cloud_msg_
sensor_msgs::PointCloud cloud_msg_
ros message
Definition: gazebo_ros_block_laser.h:86
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
ros::NodeHandle
gazebo::GazeboRosBlockLaser::PutLaserData
void PutLaserData(common::Time &_updateTime)
Put laser data to the ROS topic.
Definition: gazebo_ros_block_laser.cpp:248


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