28 #include <gazebo/physics/World.hh>
29 #include <gazebo/physics/HingeJoint.hh>
30 #include <gazebo/sensors/Sensor.hh>
32 #include <sdf/Param.hh>
33 #include <gazebo/common/Exception.hh>
34 #include <gazebo/sensors/RaySensor.hh>
35 #include <gazebo/sensors/SensorTypes.hh>
36 #include <gazebo/transport/transport.hh>
38 #ifdef ENABLE_PROFILER
39 #include <ignition/common/Profiler.hh>
46 #include <ignition/math/Rand.hh>
51 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosLaser)
72 RayPlugin::Load(_parent, this->
sdf);
74 std::string worldName = _parent->WorldName();
75 this->
world_ = physics::get_world(worldName);
81 dynamic_pointer_cast<sensors::RaySensor>(_parent);
84 gzthrow(
"GazeboRosLaser controller requires a Ray Sensor as its parent");
88 if (!this->
sdf->HasElement(
"frameName"))
90 ROS_INFO_NAMED(
"laser",
"Laser plugin missing <frameName>, defaults to /world");
97 if (!this->
sdf->HasElement(
"topicName"))
99 ROS_INFO_NAMED(
"laser",
"Laser plugin missing <topicName>, defaults to /world");
111 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
126 this->
gazebo_node_ = gazebo::transport::NodePtr(
new gazebo::transport::Node());
134 ROS_INFO_NAMED(
"laser",
"Laser Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
143 ros::AdvertiseOptions::create<sensor_msgs::LaserScan>(
162 this->laser_connect_count_++;
163 if (this->laser_connect_count_ == 1)
173 this->laser_connect_count_--;
174 if (this->laser_connect_count_ == 0)
182 #ifdef ENABLE_PROFILER
183 IGN_PROFILE(
"GazeboRosLaser::OnScan");
184 IGN_PROFILE_BEGIN(
"fill ROS message");
188 sensor_msgs::LaserScan laser_msg;
189 laser_msg.header.stamp =
ros::Time(_msg->time().sec(), _msg->time().nsec());
191 laser_msg.angle_min = _msg->scan().angle_min();
192 laser_msg.angle_max = _msg->scan().angle_max();
193 laser_msg.angle_increment = _msg->scan().angle_step();
194 laser_msg.time_increment = 0;
195 laser_msg.scan_time = 0;
196 laser_msg.range_min = _msg->scan().range_min();
197 laser_msg.range_max = _msg->scan().range_max();
198 laser_msg.ranges.resize(_msg->scan().ranges_size());
199 std::copy(_msg->scan().ranges().begin(),
200 _msg->scan().ranges().end(),
201 laser_msg.ranges.begin());
202 laser_msg.intensities.resize(_msg->scan().intensities_size());
203 std::copy(_msg->scan().intensities().begin(),
204 _msg->scan().intensities().end(),
205 laser_msg.intensities.begin());
207 #ifdef ENABLE_PROFILER