30 #include <gazebo/physics/World.hh>
31 #include <gazebo/physics/HingeJoint.hh>
32 #include <gazebo/sensors/Sensor.hh>
33 #include <gazebo/common/Exception.hh>
34 #include <gazebo/sensors/GpuRaySensor.hh>
35 #include <gazebo/sensors/SensorTypes.hh>
36 #include <gazebo/transport/transport.hh>
38 #ifdef ENABLE_PROFILER
39 #include <ignition/common/Profiler.hh>
47 #include <ignition/math/Rand.hh>
52 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosLaser)
75 GpuRayPlugin::Load(_parent, this->
sdf);
77 std::string worldName = _parent->WorldName();
78 this->
world_ = physics::get_world(worldName);
84 dynamic_pointer_cast<sensors::GpuRaySensor>(_parent);
87 gzthrow(
"GazeboRosLaser controller requires a Ray Sensor as its parent");
91 if (!this->
sdf->HasElement(
"frameName"))
93 ROS_INFO_NAMED(
"gpu_laser",
"GazeboRosLaser plugin missing <frameName>, defaults to /world");
99 if (!this->
sdf->HasElement(
"topicName"))
101 ROS_INFO_NAMED(
"gpu_laser",
"GazeboRosLaser plugin missing <topicName>, defaults to /world");
113 ROS_FATAL_STREAM_NAMED(
"gpu_laser",
"A ROS node for Gazebo has not been initialized, unable to load plugin. "
114 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
129 this->
gazebo_node_ = gazebo::transport::NodePtr(
new gazebo::transport::Node());
137 ROS_INFO_NAMED(
"gpu_laser",
"GPU Laser Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
146 ros::AdvertiseOptions::create<sensor_msgs::LaserScan>(
187 #ifdef ENABLE_PROFILER
188 IGN_PROFILE(
"GazeboRosLaser::OnScan");
189 IGN_PROFILE_BEGIN(
"fill ROS message");
193 sensor_msgs::LaserScan laser_msg;
194 laser_msg.header.stamp =
ros::Time(_msg->time().sec(), _msg->time().nsec());
196 laser_msg.angle_min = _msg->scan().angle_min();
197 laser_msg.angle_max = _msg->scan().angle_max();
198 laser_msg.angle_increment = _msg->scan().angle_step();
199 laser_msg.time_increment = 0;
200 laser_msg.scan_time = 0;
201 laser_msg.range_min = _msg->scan().range_min();
202 laser_msg.range_max = _msg->scan().range_max();
203 laser_msg.ranges.resize(_msg->scan().ranges_size());
204 std::copy(_msg->scan().ranges().begin(),
205 _msg->scan().ranges().end(),
206 laser_msg.ranges.begin());
207 laser_msg.intensities.resize(_msg->scan().intensities_size());
208 std::copy(_msg->scan().intensities().begin(),
209 _msg->scan().intensities().end(),
210 laser_msg.intensities.begin());
212 #ifdef ENABLE_PROFILER