41 #include <gazebo/physics/World.hh>
42 #include <gazebo/sensors/Sensor.hh>
44 #include <sdf/Param.hh>
45 #include <gazebo/common/Exception.hh>
46 #include <gazebo/sensors/RaySensor.hh>
47 #include <gazebo/sensors/SensorTypes.hh>
48 #include <gazebo/transport/Node.hh>
50 #include <sensor_msgs/PointCloud2.h>
57 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosVelodyneLaser)
67 GazeboRosVelodyneLaser::~GazeboRosVelodyneLaser()
72 laser_queue_.disable();
78 callback_laser_queue_thread_.join();
83 void GazeboRosVelodyneLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
86 RayPlugin::Load(_parent, _sdf);
89 parent_sensor_ = _parent;
92 #if GAZEBO_MAJOR_VERSION >= 7
93 std::string worldName = _parent->WorldName();
95 std::string worldName = _parent->GetWorldName();
97 world_ = physics::get_world(worldName);
99 last_update_time_ = world_->GetSimTime();
101 node_ = transport::NodePtr(
new transport::Node());
102 node_->Init(worldName);
104 #if GAZEBO_MAJOR_VERSION >= 7
105 parent_ray_sensor_ = std::dynamic_pointer_cast<sensors::RaySensor>(parent_sensor_);
107 parent_ray_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(parent_sensor_);
110 if (!parent_ray_sensor_) {
111 gzthrow(
"GazeboRosVelodyneLaser controller requires a Ray Sensor as its parent");
114 robot_namespace_ =
"";
115 if (_sdf->HasElement(
"robotNamespace")) {
116 robot_namespace_ = _sdf->GetElement(
"robotNamespace")->Get<std::string>() +
"/";
119 if (!_sdf->HasElement(
"frameName")) {
120 ROS_INFO(
"Velodyne laser plugin missing <frameName>, defaults to /world");
121 frame_name_ =
"/world";
123 frame_name_ = _sdf->GetElement(
"frameName")->Get<std::string>();
126 if (!_sdf->HasElement(
"min_range")) {
127 ROS_INFO(
"Velodyne laser plugin missing <min_range>, defaults to 0");
130 min_range_ = _sdf->GetElement(
"min_range")->Get<
double>();
133 if (!_sdf->HasElement(
"max_range")) {
134 ROS_INFO(
"Velodyne laser plugin missing <max_range>, defaults to infinity");
135 max_range_ = INFINITY;
137 max_range_ = _sdf->GetElement(
"max_range")->Get<
double>();
140 if (!_sdf->HasElement(
"topicName")) {
141 ROS_INFO(
"Velodyne laser plugin missing <topicName>, defaults to /world");
142 topic_name_ =
"/world";
144 topic_name_ = _sdf->GetElement(
"topicName")->Get<std::string>();
147 if (!_sdf->HasElement(
"gaussianNoise")) {
148 ROS_INFO(
"Velodyne laser plugin missing <gaussianNoise>, defaults to 0.0");
151 gaussian_noise_ = _sdf->GetElement(
"gaussianNoise")->Get<
double>();
156 ROS_FATAL_STREAM(
"A ROS node for Gazebo has not been initialized, unable to load plugin. "
157 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
165 rosnode_->getParam(std::string(
"tf_prefix"), prefix);
168 if (topic_name_ !=
"") {
172 boost::bind( &GazeboRosVelodyneLaser::laserConnect,
this),
173 boost::bind( &GazeboRosVelodyneLaser::laserDisconnect,
this),
ros::VoidPtr(), &laser_queue_);
174 pub_ = rosnode_->advertise(ao);
178 parent_ray_sensor_->SetActive(
false);
180 callback_laser_queue_thread_ = boost::thread( boost::bind( &GazeboRosVelodyneLaser::laserQueueThread,
this ) );
182 #if GAZEBO_MAJOR_VERSION >= 7
183 ROS_INFO(
"Velodyne laser plugin ready, %i lasers", parent_ray_sensor_->VerticalRangeCount());
185 ROS_INFO(
"Velodyne laser plugin ready, %i lasers", parent_ray_sensor_->GetVerticalRangeCount());
191 void GazeboRosVelodyneLaser::laserConnect()
193 laser_connect_count_++;
194 parent_ray_sensor_->SetActive(
true);
198 void GazeboRosVelodyneLaser::laserDisconnect()
200 laser_connect_count_--;
201 if (laser_connect_count_ == 0) {
202 parent_ray_sensor_->SetActive(
false);
208 void GazeboRosVelodyneLaser::OnNewLaserScans()
210 if (topic_name_ !=
"") {
211 #if GAZEBO_MAJOR_VERSION >= 7
212 common::Time sensor_update_time = parent_sensor_->LastUpdateTime();
214 common::Time sensor_update_time = parent_sensor_->GetLastUpdateTime();
216 if (last_update_time_ < sensor_update_time) {
217 putLaserData(sensor_update_time);
218 last_update_time_ = sensor_update_time;
221 ROS_INFO(
"gazebo_ros_velodyne_laser topic name not set");
227 void GazeboRosVelodyneLaser::putLaserData(common::Time &_updateTime)
233 double r1, r2, r3, r4, r;
236 parent_ray_sensor_->SetActive(
false);
238 #if GAZEBO_MAJOR_VERSION >= 7
239 math::Angle maxAngle = parent_ray_sensor_->AngleMax();
240 math::Angle minAngle = parent_ray_sensor_->AngleMin();
242 double maxRange = parent_ray_sensor_->RangeMax();
243 double minRange = parent_ray_sensor_->RangeMin();
245 int rayCount = parent_ray_sensor_->RayCount();
246 int rangeCount = parent_ray_sensor_->RangeCount();
248 int verticalRayCount = parent_ray_sensor_->VerticalRayCount();
249 int verticalRangeCount = parent_ray_sensor_->VerticalRangeCount();
250 math::Angle verticalMaxAngle = parent_ray_sensor_->VerticalAngleMax();
251 math::Angle verticalMinAngle = parent_ray_sensor_->VerticalAngleMin();
253 math::Angle maxAngle = parent_ray_sensor_->GetAngleMax();
254 math::Angle minAngle = parent_ray_sensor_->GetAngleMin();
256 double maxRange = parent_ray_sensor_->GetRangeMax();
257 double minRange = parent_ray_sensor_->GetRangeMin();
259 int rayCount = parent_ray_sensor_->GetRayCount();
260 int rangeCount = parent_ray_sensor_->GetRangeCount();
262 int verticalRayCount = parent_ray_sensor_->GetVerticalRayCount();
263 int verticalRangeCount = parent_ray_sensor_->GetVerticalRangeCount();
264 math::Angle verticalMaxAngle = parent_ray_sensor_->GetVerticalAngleMax();
265 math::Angle verticalMinAngle = parent_ray_sensor_->GetVerticalAngleMin();
268 double yDiff = maxAngle.Radian() - minAngle.Radian();
269 double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
276 boost::mutex::scoped_lock lock(lock_);
279 const uint32_t POINT_STEP = 32;
280 sensor_msgs::PointCloud2
msg;
281 msg.header.frame_id = frame_name_;
282 msg.header.stamp.sec = _updateTime.sec;
283 msg.header.stamp.nsec = _updateTime.nsec;
284 msg.fields.resize(5);
285 msg.fields[0].name =
"x";
286 msg.fields[0].offset = 0;
287 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
288 msg.fields[0].count = 1;
289 msg.fields[1].name =
"y";
290 msg.fields[1].offset = 4;
291 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
292 msg.fields[1].count = 1;
293 msg.fields[2].name =
"z";
294 msg.fields[2].offset = 8;
295 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
296 msg.fields[2].count = 1;
297 msg.fields[3].name =
"intensity";
298 msg.fields[3].offset = 16;
299 msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
300 msg.fields[3].count = 1;
301 msg.fields[4].name =
"ring";
302 msg.fields[4].offset = 20;
303 msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
304 msg.fields[4].count = 1;
305 msg.data.resize(verticalRangeCount * rangeCount * POINT_STEP);
307 const double MIN_RANGE = std::max(min_range_, minRange);
308 const double MAX_RANGE = std::min(max_range_, maxRange - minRange - 0.01);
310 uint8_t *ptr =
msg.data.data();
311 for (j = 0; j<verticalRangeCount; j++) {
313 vb = (verticalRangeCount == 1) ? 0 : (
double) j * (verticalRayCount - 1) / (verticalRangeCount - 1);
314 vja = (int) floor(vb);
315 vjb = std::min(vja + 1, verticalRayCount - 1);
318 assert(vja >= 0 && vja < verticalRayCount);
319 assert(vjb >= 0 && vjb < verticalRayCount);
321 for (i = 0; i<rangeCount; i++) {
323 hb = (rangeCount == 1)? 0 : (
double) i * (rayCount - 1) / (rangeCount - 1);
324 hja = (int) floor(hb);
325 hjb = std::min(hja + 1, rayCount - 1);
328 assert(hja >= 0 && hja < rayCount);
329 assert(hjb >= 0 && hjb < rayCount);
332 j1 = hja + vja * rayCount;
333 j2 = hjb + vja * rayCount;
334 j3 = hja + vjb * rayCount;
335 j4 = hjb + vjb * rayCount;
337 #if GAZEBO_MAJOR_VERSION >= 7
338 r1 = std::min(parent_ray_sensor_->LaserShape()->GetRange(j1) , maxRange-minRange);
339 r2 = std::min(parent_ray_sensor_->LaserShape()->GetRange(j2) , maxRange-minRange);
340 r3 = std::min(parent_ray_sensor_->LaserShape()->GetRange(j3) , maxRange-minRange);
341 r4 = std::min(parent_ray_sensor_->LaserShape()->GetRange(j4) , maxRange-minRange);
343 r1 = std::min(parent_ray_sensor_->GetLaserShape()->GetRange(j1) , maxRange-minRange);
344 r2 = std::min(parent_ray_sensor_->GetLaserShape()->GetRange(j2) , maxRange-minRange);
345 r3 = std::min(parent_ray_sensor_->GetLaserShape()->GetRange(j3) , maxRange-minRange);
346 r4 = std::min(parent_ray_sensor_->GetLaserShape()->GetRange(j4) , maxRange-minRange);
351 r = (1 - vb) * ((1 - hb) * r1 + hb * r2)
352 + vb * ((1 - hb) * r3 + hb * r4);
353 if (gaussian_noise_ != 0.0) {
354 r += gaussianKernel(0,gaussian_noise_);
358 #if GAZEBO_MAJOR_VERSION >= 7
359 intensity = 0.25*(parent_ray_sensor_->LaserShape()->GetRetro(j1) +
360 parent_ray_sensor_->LaserShape()->GetRetro(j2) +
361 parent_ray_sensor_->LaserShape()->GetRetro(j3) +
362 parent_ray_sensor_->LaserShape()->GetRetro(j4));
364 intensity = 0.25*(parent_ray_sensor_->GetLaserShape()->GetRetro(j1) +
365 parent_ray_sensor_->GetLaserShape()->GetRetro(j2) +
366 parent_ray_sensor_->GetLaserShape()->GetRetro(j3) +
367 parent_ray_sensor_->GetLaserShape()->GetRetro(j4));
371 double yAngle = 0.5*(hja+hjb) * yDiff / (rayCount -1) + minAngle.Radian();
372 double pAngle = j * pDiff / (verticalRayCount -1) + verticalMinAngle.Radian();
375 if ((MIN_RANGE < r) && (r < MAX_RANGE)) {
376 *((
float*)(ptr + 0)) = r * cos(pAngle) * cos(yAngle);
377 *((
float*)(ptr + 4)) = r * cos(pAngle) * sin(yAngle);
378 #if GAZEBO_MAJOR_VERSION > 2
379 *((
float*)(ptr + 8)) = r * sin(pAngle);
381 *((
float*)(ptr + 8)) = -r * sin(pAngle);
383 *((
float*)(ptr + 16)) = intensity;
384 #if GAZEBO_MAJOR_VERSION > 2
385 *((uint16_t*)(ptr + 20)) = j;
387 *((uint16_t*)(ptr + 20)) = verticalRangeCount - 1 - j;
393 parent_ray_sensor_->SetActive(
true);
396 msg.point_step = POINT_STEP;
397 msg.row_step = ptr -
msg.data.data();
399 msg.width =
msg.row_step / POINT_STEP;
400 msg.is_bigendian =
false;
402 msg.data.resize(
msg.row_step);
411 void GazeboRosVelodyneLaser::laserQueueThread()
413 static const double TIMEOUT = 0.01;
415 while (rosnode_->ok()) {
422 sim_time_ = msgs::Convert( _msg->sim_time() );
425 pose.pos.x = 0.5*sin(0.01*sim_time_.Double());
426 gzdbg <<
"plugin simTime [" << sim_time_.Double() <<
"] update pose [" << pose.pos.x <<
"]\n";