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>
51 #ifdef ENABLE_PROFILER
52 #include <ignition/common/Profiler.hh>
56 #include <sdf/Param.hh>
59 #include <ignition/math/Rand.hh>
64 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosRange)
89 RayPlugin::Load(_parent, this->
sdf);
93 std::string worldName = _parent->WorldName();
94 this->
world_ = physics::get_world(worldName);
105 gzthrow(
"GazeboRosRange controller requires a Ray Sensor as its parent");
108 if (this->
sdf->HasElement(
"robotNamespace"))
111 if (!this->
sdf->HasElement(
"frameName"))
113 ROS_INFO_NAMED(
"range",
"Range plugin missing <frameName>, defaults to /world");
119 if (!this->
sdf->HasElement(
"topicName"))
121 ROS_INFO_NAMED(
"range",
"Range plugin missing <topicName>, defaults to /range");
127 if (!this->
sdf->HasElement(
"radiation"))
129 ROS_WARN_NAMED(
"range",
"Range plugin missing <radiation>, defaults to ultrasound");
134 this->
radiation_ = _sdf->GetElement(
"radiation")->Get<std::string>();
136 if (!this->
sdf->HasElement(
"fov"))
138 ROS_WARN_NAMED(
"range",
"Range plugin missing <fov>, defaults to 0.05");
142 this->
fov_ = _sdf->GetElement(
"fov")->Get<
double>();
143 if (!this->
sdf->HasElement(
"gaussianNoise"))
145 ROS_INFO_NAMED(
"range",
"Range plugin missing <gaussianNoise>, defaults to 0.0");
151 if (!this->
sdf->HasElement(
"updateRate"))
153 ROS_INFO_NAMED(
"range",
"Range plugin missing <updateRate>, defaults to 0");
170 if (this->
radiation_==std::string(
"ultrasound"))
171 this->
range_msg_.radiation_type = sensor_msgs::Range::ULTRASOUND;
173 this->range_msg_.radiation_type = sensor_msgs::Range::INFRARED;
175 this->range_msg_.field_of_view =
fov_;
176 this->range_msg_.max_range = this->parent_ray_sensor_->RangeMax();
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";
208 ros::AdvertiseOptions::create<sensor_msgs::Range>(
248 #ifdef ENABLE_PROFILER
249 IGN_PROFILE(
"GazeboRosRange::OnNewLaserScans");
253 #if GAZEBO_MAJOR_VERSION >= 8
254 common::Time cur_time = this->
world_->SimTime();
256 common::Time cur_time = this->
world_->GetSimTime();
260 ROS_WARN_NAMED(
"range",
"Negative sensor update time difference detected.");
261 this->last_update_time_ = cur_time;
266 common::Time sensor_update_time =
268 #ifdef ENABLE_PROFILER
269 IGN_PROFILE_BEGIN(
"PutRangeData");
272 #ifdef ENABLE_PROFILER
275 this->last_update_time_ = cur_time;
296 boost::mutex::scoped_lock lock(this->
lock_);
299 this->
range_msg_.header.stamp.sec = _updateTime.sec;
300 this->
range_msg_.header.stamp.nsec = _updateTime.nsec;
303 range_msg_.range = std::numeric_limits<sensor_msgs::Range::_range_type>::max();
307 for(
int i = 0; i < num_ranges; ++i)
334 double U = ignition::math::Rand::DblUniform();
337 double V = ignition::math::Rand::DblUniform();
339 double X = sqrt(-2.0 * ::log(U)) * cos(2.0*M_PI * V);
352 static const double timeout = 0.01;