gazebo_ros_depth_camera.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: GazeboRosDepthCamera plugin for simulating cameras in Gazebo
19  Author: John Hsu
20  Date: 24 Sept 2008
21  */
22 
23 #include <algorithm>
24 #include <assert.h>
25 #include <boost/thread/thread.hpp>
26 #include <boost/bind.hpp>
27 
29 
30 #include <gazebo/sensors/Sensor.hh>
31 #include <sdf/sdf.hh>
32 #include <gazebo/sensors/SensorTypes.hh>
33 
34 #ifdef ENABLE_PROFILER
35 #include <ignition/common/Profiler.hh>
36 #endif
37 
39 
40 #include <tf/tf.h>
41 
42 namespace gazebo
43 {
44 // Register this plugin with the simulator
45 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosDepthCamera)
46 
47 // Constructor
50 {
51  this->point_cloud_connect_count_ = 0;
52  this->normals_connect_count_ = 0;
53  this->depth_image_connect_count_ = 0;
54  this->depth_info_connect_count_ = 0;
55  this->reflectance_connect_count_ = 0;
56  this->last_depth_image_camera_info_update_time_ = common::Time(0);
57 }
58 
60 // Destructor
62 {
63  if (pcd_ != nullptr)
64  {
65  delete [] pcd_;
66  }
67 }
68 
70 // Load the controller
71 void GazeboRosDepthCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
72 {
73  DepthCameraPlugin::Load(_parent, _sdf);
74 
75  // Make sure the ROS node for Gazebo has already been initialized
76  if (!ros::isInitialized())
77  {
78  ROS_FATAL_STREAM_NAMED("depth_camera", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
79  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
80  return;
81  }
82 
83  // copying from DepthCameraPlugin into GazeboRosCameraUtils
84  this->parentSensor_ = this->parentSensor;
85  this->width_ = this->width;
86  this->height_ = this->height;
87  this->depth_ = this->depth;
88  this->format_ = this->format;
89  this->camera_ = this->depthCamera;
90 
91  // using a different default
92  if (!_sdf->HasElement("imageTopicName"))
93  this->image_topic_name_ = "ir/image_raw";
94  if (!_sdf->HasElement("cameraInfoTopicName"))
95  this->camera_info_topic_name_ = "ir/camera_info";
96 
97  // point cloud stuff
98  if (!_sdf->HasElement("pointCloudTopicName"))
99  this->point_cloud_topic_name_ = "points";
100  else
101  this->point_cloud_topic_name_ = _sdf->GetElement("pointCloudTopicName")->Get<std::string>();
102 
103  // reflectance stuff
104  if (!_sdf->HasElement("reflectanceTopicName"))
105  this->reflectance_topic_name_ = "reflectance";
106  else
107  this->reflectance_topic_name_ = _sdf->GetElement("reflectanceTopicName")->Get<std::string>();
108 
109  // normals stuff
110  if (!_sdf->HasElement("normalsTopicName"))
111  this->normals_topic_name_ = "normals";
112  else
113  this->normals_topic_name_ = _sdf->GetElement("normalsTopicName")->Get<std::string>();
114 
115  // depth image stuff
116  if (!_sdf->HasElement("depthImageTopicName"))
117  this->depth_image_topic_name_ = "depth/image_raw";
118  else
119  this->depth_image_topic_name_ = _sdf->GetElement("depthImageTopicName")->Get<std::string>();
120 
121  if (!_sdf->HasElement("depthImageCameraInfoTopicName"))
122  this->depth_image_camera_info_topic_name_ = "depth/camera_info";
123  else
124  this->depth_image_camera_info_topic_name_ = _sdf->GetElement("depthImageCameraInfoTopicName")->Get<std::string>();
125 
126  if (!_sdf->HasElement("pointCloudCutoff"))
127  this->point_cloud_cutoff_ = 0.4;
128  else
129  this->point_cloud_cutoff_ = _sdf->GetElement("pointCloudCutoff")->Get<double>();
130 
131  if (!_sdf->HasElement("reduceNormals"))
132  this->reduce_normals_ = 50;
133  else
134  this->reduce_normals_ = _sdf->GetElement("reduceNormals")->Get<int>();
135 
136  // allow optional publication of depth images in 16UC1 instead of 32FC1
137  if (!_sdf->HasElement("useDepth16UC1Format"))
138  this->use_depth_image_16UC1_format_ = false;
139  else
140  this->use_depth_image_16UC1_format_ = _sdf->GetElement("useDepth16UC1Format")->Get<bool>();
141 
143  GazeboRosCameraUtils::Load(_parent, _sdf);
144 }
145 
147 {
148  ros::AdvertiseOptions point_cloud_ao =
149  ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
150  this->point_cloud_topic_name_,1,
151  boost::bind( &GazeboRosDepthCamera::PointCloudConnect,this),
152  boost::bind( &GazeboRosDepthCamera::PointCloudDisconnect,this),
153  ros::VoidPtr(), &this->camera_queue_);
154  this->point_cloud_pub_ = this->rosnode_->advertise(point_cloud_ao);
155 
156  ros::AdvertiseOptions depth_image_ao =
157  ros::AdvertiseOptions::create< sensor_msgs::Image >(
158  this->depth_image_topic_name_,1,
159  boost::bind( &GazeboRosDepthCamera::DepthImageConnect,this),
160  boost::bind( &GazeboRosDepthCamera::DepthImageDisconnect,this),
161  ros::VoidPtr(), &this->camera_queue_);
162  this->depth_image_pub_ = this->rosnode_->advertise(depth_image_ao);
163 
164  ros::AdvertiseOptions depth_image_camera_info_ao =
165  ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
167  boost::bind( &GazeboRosDepthCamera::DepthInfoConnect,this),
168  boost::bind( &GazeboRosDepthCamera::DepthInfoDisconnect,this),
169  ros::VoidPtr(), &this->camera_queue_);
170  this->depth_image_camera_info_pub_ = this->rosnode_->advertise(depth_image_camera_info_ao);
171 
172 #if GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 12
173  ros::AdvertiseOptions reflectance_ao =
174  ros::AdvertiseOptions::create<sensor_msgs::Image>(
176  boost::bind( &GazeboRosDepthCamera::ReflectanceConnect,this),
178  ros::VoidPtr(), &this->camera_queue_);
179  this->reflectance_pub_ = this->rosnode_->advertise(reflectance_ao);
180 
181  ros::AdvertiseOptions normals_ao =
182  ros::AdvertiseOptions::create<visualization_msgs::MarkerArray >(
184  boost::bind( &GazeboRosDepthCamera::NormalsConnect,this),
185  boost::bind( &GazeboRosDepthCamera::NormalsDisconnect,this),
186  ros::VoidPtr(), &this->camera_queue_);
187  this->normal_pub_ = this->rosnode_->advertise(normals_ao);
188 #endif
189 }
190 
192 // Increment count
194 {
196  (*this->image_connect_count_)++;
197  this->parentSensor->SetActive(true);
198 }
199 
201 // Decrement count
203 {
205  (*this->image_connect_count_)--;
206  if (this->point_cloud_connect_count_ <= 0)
207  this->parentSensor->SetActive(false);
208 }
209 
211 // Increment count
213 {
215  (*this->image_connect_count_)++;
216  this->parentSensor->SetActive(true);
217 }
218 
220 // Increment count
222 {
223  this->normals_connect_count_++;
224  (*this->image_connect_count_)++;
225  this->parentSensor->SetActive(true);
226 }
227 
229 // Decrement count
231 {
233  (*this->image_connect_count_)--;
234  if (this->reflectance_connect_count_ <= 0)
235  this->parentSensor->SetActive(false);
236 }
237 
239 // Decrement count
241 {
242  this->normals_connect_count_--;
243  (*this->image_connect_count_)--;
244  if (this->reflectance_connect_count_ <= 0)
245  this->parentSensor->SetActive(false);
246 }
247 
249 // Increment count
251 {
253  this->parentSensor->SetActive(true);
254 }
255 
257 // Decrement count
259 {
261 }
262 
264 // Increment count
266 {
268 }
270 // Decrement count
272 {
274 }
275 
277 // Update the controller
278 void GazeboRosDepthCamera::OnNewDepthFrame(const float *_image,
279  unsigned int _width, unsigned int _height, unsigned int _depth,
280  const std::string &_format)
281 {
282 #ifdef ENABLE_PROFILER
283  IGN_PROFILE("GazeboRosDepthCamera::OnNewDepthFrame");
284 #endif
285  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
286  return;
287 #ifdef ENABLE_PROFILER
288  IGN_PROFILE_BEGIN("fill ROS message");
289 #endif
290 # if GAZEBO_MAJOR_VERSION >= 7
291  this->depth_sensor_update_time_ = this->parentSensor->LastMeasurementTime();
292 # else
293  this->depth_sensor_update_time_ = this->parentSensor->GetLastMeasurementTime();
294 # endif
295 
296  if (this->parentSensor->IsActive())
297  {
298  if (this->point_cloud_connect_count_ <= 0 &&
299  this->depth_image_connect_count_ <= 0 &&
300  (*this->image_connect_count_) <= 0 &&
301  this->normals_connect_count_ <= 0)
302  {
303  this->parentSensor->SetActive(false);
304  }
305  else
306  {
307  if (this->point_cloud_connect_count_ > 0 ||
308  this->normals_connect_count_ > 0)
309  {
310  this->FillPointdCloud(_image);
311  }
312 
313  if (this->depth_image_connect_count_ > 0)
314  this->FillDepthImage(_image);
315  }
316  }
317  else
318  {
319  if (this->point_cloud_connect_count_ > 0 ||
320  this->depth_image_connect_count_ <= 0)
321  // do this first so there's chance for sensor to run 1 frame after activate
322  this->parentSensor->SetActive(true);
323  }
324 #ifdef ENABLE_PROFILER
325  IGN_PROFILE_END();
326 #endif
327 }
328 
330 // Update the controller
332  unsigned int _width, unsigned int _height, unsigned int _depth,
333  const std::string &_format)
334 {
335 #ifdef ENABLE_PROFILER
336  IGN_PROFILE("GazeboRosDepthCamera::OnNewRGBPointCloud");
337 #endif
338  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
339  return;
340 #ifdef ENABLE_PROFILER
341  IGN_PROFILE_BEGIN("fill ROS message");
342 #endif
343 # if GAZEBO_MAJOR_VERSION >= 7
344  this->depth_sensor_update_time_ = this->parentSensor->LastMeasurementTime();
345 # else
346  this->depth_sensor_update_time_ = this->parentSensor->GetLastMeasurementTime();
347 # endif
348 
349  if (!this->parentSensor->IsActive())
350  {
351  if (this->point_cloud_connect_count_ > 0)
352  // do this first so there's chance for sensor to run 1 frame after activate
353  this->parentSensor->SetActive(true);
354  }
355  else
356  {
357  if (this->point_cloud_connect_count_ > 0 || this->normals_connect_count_ > 0)
358  {
359  this->lock_.lock();
360 
361  if (pcd_ == nullptr)
362  pcd_ = new float[_width * _height * 4];
363 
364  memcpy(pcd_, _pcd, sizeof(float)* _width * _height * 4);
365 
366  this->point_cloud_msg_.header.frame_id = this->frame_name_;
367  this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
368  this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
369  this->point_cloud_msg_.width = this->width;
370  this->point_cloud_msg_.height = this->height;
371  this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
372 
374  pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
375  pcd_modifier.resize(_width*_height);
376 
377  point_cloud_msg_.is_dense = true;
378 
383 
384  for (unsigned int i = 0; i < _width; i++)
385  {
386  for (unsigned int j = 0; j < _height; j++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
387  {
388  unsigned int index = (j * _width) + i;
389  *iter_x = _pcd[4 * index];
390  *iter_y = _pcd[4 * index + 1];
391  *iter_z = _pcd[4 * index + 2];
392  *iter_rgb = _pcd[4 * index + 3];
393  }
394  }
395 
397  this->lock_.unlock();
398  }
399  }
400 #ifdef ENABLE_PROFILER
401  IGN_PROFILE_END();
402 #endif
403 }
404 
405 #if GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 12
406 // Update the controller
408 void GazeboRosDepthCamera::OnNewReflectanceFrame(const float *_image,
409  unsigned int _width, unsigned int _height, unsigned int _depth,
410  const std::string &_format)
411 {
412 #ifdef ENABLE_PROFILER
413  IGN_PROFILE("GazeboRosDepthCamera::OnNewReflectanceFrame");
414 #endif
415  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
416  return;
417 
418 #ifdef ENABLE_PROFILER
419  IGN_PROFILE_BEGIN("fill ROS message");
420 #endif
421  if (this->reflectance_connect_count_ > 0)
423  {
424  boost::mutex::scoped_lock lock(this->lock_);
425 
426  // copy data into image
427  this->reflectance_msg_.header.frame_id = this->frame_name_;
428  this->reflectance_msg_.header.stamp.sec = this->sensor_update_time_.sec;
429  this->reflectance_msg_.header.stamp.nsec = this->sensor_update_time_.nsec;
430 
431  // copy from src to image_msg_
432  fillImage(this->reflectance_msg_, sensor_msgs::image_encodings::TYPE_32FC1, _height, _width,
433  4*_width, reinterpret_cast<const void*>(_image));
434 
435  // publish to ros
437  }
438 #ifdef ENABLE_PROFILER
439  IGN_PROFILE_END();
440 #endif
441 }
442 #endif
443 
445 // Update the controller
446 void GazeboRosDepthCamera::OnNewImageFrame(const unsigned char *_image,
447  unsigned int _width, unsigned int _height, unsigned int _depth,
448  const std::string &_format)
449 {
450 #ifdef ENABLE_PROFILER
451  IGN_PROFILE("GazeboRosDepthCamera::OnNewImageFrame");
452 #endif
453  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
454  return;
455 #ifdef ENABLE_PROFILER
456  IGN_PROFILE_BEGIN("fill ROS message");
457 #endif
458  //ROS_ERROR_NAMED("depth_camera", "camera_ new frame %s %s",this->parentSensor_->GetName().c_str(),this->frame_name_.c_str());
459 # if GAZEBO_MAJOR_VERSION >= 7
460  this->sensor_update_time_ = this->parentSensor->LastMeasurementTime();
461 # else
462  this->sensor_update_time_ = this->parentSensor->GetLastMeasurementTime();
463 # endif
464 
465  if (!this->parentSensor->IsActive())
466  {
467  if ((*this->image_connect_count_) > 0)
468  // do this first so there's chance for sensor to run 1 frame after activate
469  this->parentSensor->SetActive(true);
470  }
471  else
472  {
473  if ((*this->image_connect_count_) > 0)
474  {
475  this->PutCameraData(_image);
476  // TODO(lucasw) publish camera info with depth image
477  // this->PublishCameraInfo(sensor_update_time);
478  }
479  }
480 #ifdef ENABLE_PROFILER
481  IGN_PROFILE_END();
482 #endif
483 }
484 
485 #if GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 12
486 void GazeboRosDepthCamera::OnNewNormalsFrame(const float * _normals,
487  unsigned int _width, unsigned int _height,
488  unsigned int _depth, const std::string &_format)
489 {
490 #ifdef ENABLE_PROFILER
491  IGN_PROFILE("GazeboRosDepthCamera::OnNewNormalsFrame");
492 #endif
493  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
494  return;
495 #ifdef ENABLE_PROFILER
496  IGN_PROFILE_BEGIN("fill ROS message");
497 #endif
498  visualization_msgs::MarkerArray m_array;
499 
500  if (!this->parentSensor->IsActive())
501  {
502  if (this->normals_connect_count_ > 0)
503  // do this first so there's chance for sensor to run 1 frame after activate
504  this->parentSensor->SetActive(true);
505  }
506  else
507  {
508  if (this->normals_connect_count_ > 0)
509  {
510  boost::mutex::scoped_lock lock(this->lock_);
511  if (pcd_ != nullptr)
512  {
513  for (unsigned int i = 0; i < _width; i++)
514  {
515  for (unsigned int j = 0; j < _height; j++)
516  {
517  // plotting some of the normals, otherwise rviz will block it
518  unsigned int index = (j * _width) + i;
519  if (index % this->reduce_normals_ == 0)
520  {
521  visualization_msgs::Marker m;
522  m.type = visualization_msgs::Marker::ARROW;
523  m.header.frame_id = this->frame_name_;
524  m.header.stamp.sec = this->depth_sensor_update_time_.sec;
525  m.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
526  m.action = visualization_msgs::Marker::ADD;
527 
528  m.color.r = 1.0;
529  m.color.g = 0.0;
530  m.color.b = 0.0;
531  m.color.a = 1.0;
532  m.scale.x = 1;
533  m.scale.y = 0.01;
534  m.scale.z = 0.01;
535  m.lifetime.sec = 1;
536  m.lifetime.nsec = 0;
537 
538  m.id = index;
539  float x = _normals[4 * index];
540  float y = _normals[4 * index + 1];
541  float z = _normals[4 * index + 2];
542 
543  m.pose.position.x = pcd_[4 * index];
544  m.pose.position.y = pcd_[4 * index + 1];
545  m.pose.position.z = pcd_[4 * index + 2];
546 
547  // calculating the angle of the normal with the world
548  tf::Vector3 axis_vector(x, y, z);
550  if (!axis_vector.isZero())
551  {
552  tf::Vector3 vector(1.0, 0.0, 0.0);
553  tf::Vector3 right_vector = axis_vector.cross(vector);
554  right_vector.normalized();
555  q.setRotation(right_vector, -1.0*acos(axis_vector.dot(vector)));
556  q.normalize();
557  }
558 
559  m.pose.orientation.x = q.x();
560  m.pose.orientation.y = q.y();
561  m.pose.orientation.z = q.z();
562  m.pose.orientation.w = q.w();
563 
564  m_array.markers.push_back(m);
565  }
566  }
567  }
568  }
569  this->normal_pub_.publish(m_array);
570  }
571  }
572 #ifdef ENABLE_PROFILER
573  IGN_PROFILE_END();
574 #endif
575 }
576 #endif
577 
579 // Put camera data to the interface
581 {
582  this->lock_.lock();
583 
584  this->point_cloud_msg_.header.frame_id = this->frame_name_;
585  this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
586  this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
587  this->point_cloud_msg_.width = this->width;
588  this->point_cloud_msg_.height = this->height;
589  this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
590 
593  this->height,
594  this->width,
595  this->skip_,
596  (void*)_src );
597 
599 
600  this->lock_.unlock();
601 }
602 
604 // Put depth image data to the interface
606 {
607  this->lock_.lock();
608  // copy data into image
609  this->depth_image_msg_.header.frame_id = this->frame_name_;
610  this->depth_image_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
611  this->depth_image_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
612 
615  this->height,
616  this->width,
617  this->skip_,
618  (void*)_src );
619 
621 
622  this->lock_.unlock();
623 }
624 
625 
626 // Fill depth information
628  sensor_msgs::PointCloud2 &point_cloud_msg,
629  uint32_t rows_arg, uint32_t cols_arg,
630  uint32_t step_arg, void* data_arg)
631 {
632  sensor_msgs::PointCloud2Modifier pcd_modifier(point_cloud_msg);
633  pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
634  pcd_modifier.resize(rows_arg*cols_arg);
635 
640 
641  point_cloud_msg.is_dense = true;
642 
643  float* toCopyFrom = (float*)data_arg;
644  int index = 0;
645 
646  double hfov = this->parentSensor->DepthCamera()->HFOV().Radian();
647  double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
648 
649  if (pcd_ == nullptr){
650  pcd_ = new float[rows_arg * cols_arg * 4];
651  }
652 
653  // convert depth to point cloud
654  for (uint32_t j=0; j<rows_arg; j++)
655  {
656  double pAngle;
657  if (rows_arg>1) pAngle = atan2( (double)j - 0.5*(double)(rows_arg-1), fl);
658  else pAngle = 0.0;
659 
660  for (uint32_t i=0; i<cols_arg; i++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
661  {
662  double yAngle;
663  if (cols_arg>1) yAngle = atan2( (double)i - 0.5*(double)(cols_arg-1), fl);
664  else yAngle = 0.0;
665 
666  double depth = toCopyFrom[index++];
667 
668  // in optical frame
669  // hardcoded rotation rpy(-M_PI/2, 0, -M_PI/2) is built-in
670  // to urdf, where the *_optical_frame should have above relative
671  // rotation from the physical camera *_frame
672  unsigned int index = (j * cols_arg) + i;
673  *iter_x = depth * tan(yAngle);
674  *iter_y = depth * tan(pAngle);
675  if(depth > this->point_cloud_cutoff_)
676  {
677  *iter_z = depth;
678  pcd_[4 * index + 2] = *iter_z;
679  }
680  else //point in the unseeable range
681  {
682  *iter_x = *iter_y = *iter_z = std::numeric_limits<float>::quiet_NaN ();
683  pcd_[4 * index + 2] = 0;
684  point_cloud_msg.is_dense = false;
685  }
686 
687  pcd_[4 * index] = *iter_x;
688  pcd_[4 * index + 1] = *iter_y;
689  pcd_[4 * index + 3] = 0;
690 
691  // put image color data for each point
692  uint8_t* image_src = (uint8_t*)(&(this->image_msg_.data[0]));
693  if (this->image_msg_.data.size() == rows_arg*cols_arg*3)
694  {
695  // color
696  iter_rgb[0] = image_src[i*3+j*cols_arg*3+0];
697  iter_rgb[1] = image_src[i*3+j*cols_arg*3+1];
698  iter_rgb[2] = image_src[i*3+j*cols_arg*3+2];
699  }
700  else if (this->image_msg_.data.size() == rows_arg*cols_arg)
701  {
702  // mono (or bayer? @todo; fix for bayer)
703  iter_rgb[0] = image_src[i+j*cols_arg];
704  iter_rgb[1] = image_src[i+j*cols_arg];
705  iter_rgb[2] = image_src[i+j*cols_arg];
706  }
707  else
708  {
709  // no image
710  iter_rgb[0] = 0;
711  iter_rgb[1] = 0;
712  iter_rgb[2] = 0;
713  }
714  }
715  }
716 
717  return true;
718 }
719 
720 // Fill depth information
722  sensor_msgs::Image& image_msg,
723  uint32_t rows_arg, uint32_t cols_arg,
724  uint32_t step_arg, void* data_arg)
725 {
726  image_msg.height = rows_arg;
727  image_msg.width = cols_arg;
728  image_msg.is_bigendian = 0;
729  // deal with the differences in between 32FC1 & 16UC1
730  // http://www.ros.org/reps/rep-0118.html#id4
731  union uint16_or_float
732  {
733  uint16_t* dest_uint16;
734  float* dest_float;
735  };
736  uint16_or_float dest;
738  {
739  image_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
740  image_msg.step = sizeof(float) * cols_arg;
741  image_msg.data.resize(rows_arg * cols_arg * sizeof(float));
742  dest.dest_float = (float*)(&(image_msg.data[0]));
743  }
744  else
745  {
746  image_msg.encoding = sensor_msgs::image_encodings::TYPE_16UC1;
747  image_msg.step = sizeof(uint16_t) * cols_arg;
748  image_msg.data.resize(rows_arg * cols_arg * sizeof(uint16_t));
749  dest.dest_uint16 = (uint16_t*)(&(image_msg.data[0]));
750  }
751 
752  float* toCopyFrom = (float*)data_arg;
753  int index = 0;
754 
755  // convert depth to point cloud
756  for (uint32_t j = 0; j < rows_arg; j++)
757  {
758  for (uint32_t i = 0; i < cols_arg; i++)
759  {
760  float depth = toCopyFrom[index++];
761 
762  if (depth > this->point_cloud_cutoff_)
763  {
765  dest.dest_float[i + j * cols_arg] = depth;
766  else
767  dest.dest_uint16[i + j * cols_arg] = depth * 1000.0;
768  }
769  else //point in the unseeable range
770  {
772  dest.dest_float[i + j * cols_arg] = std::numeric_limits<float>::quiet_NaN();
773  else
774  dest.dest_uint16[i + j * cols_arg] = 0;
775  }
776  }
777  }
778  return true;
779 }
780 
782 {
783  ROS_DEBUG_NAMED("depth_camera", "publishing default camera info, then depth camera info");
785 
786  if (this->depth_info_connect_count_ > 0)
787  {
788 # if GAZEBO_MAJOR_VERSION >= 7
789  common::Time sensor_update_time = this->parentSensor_->LastMeasurementTime();
790 # else
791  common::Time sensor_update_time = this->parentSensor_->GetLastMeasurementTime();
792 # endif
793  this->sensor_update_time_ = sensor_update_time;
794  if (sensor_update_time - this->last_depth_image_camera_info_update_time_ >= this->update_period_)
795  {
796  this->PublishCameraInfo(this->depth_image_camera_info_pub_); // , sensor_update_time);
797  this->last_depth_image_camera_info_update_time_ = sensor_update_time;
798  }
799  }
800 }
801 
802 //@todo: publish disparity similar to openni_camera_deprecated/src/nodelets/openni_nodelet.cpp.
803 /*
804 #include <stereo_msgs/DisparityImage.h>
805 pub_disparity_ = comm_nh.advertise<stereo_msgs::DisparityImage > ("depth/disparity", 5, subscriberChanged2, subscriberChanged2);
806 
807 void GazeboRosDepthCamera::PublishDisparityImage(const DepthImage& depth, ros::Time time)
808 {
809  stereo_msgs::DisparityImagePtr disp_msg = boost::make_shared<stereo_msgs::DisparityImage > ();
810  disp_msg->header.stamp = time;
811  disp_msg->header.frame_id = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_;
812  disp_msg->image.header = disp_msg->header;
813  disp_msg->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
814  disp_msg->image.height = depth_height_;
815  disp_msg->image.width = depth_width_;
816  disp_msg->image.step = disp_msg->image.width * sizeof (float);
817  disp_msg->image.data.resize (disp_msg->image.height * disp_msg->image.step);
818  disp_msg->T = depth.getBaseline ();
819  disp_msg->f = depth.getFocalLength () * depth_width_ / depth.getWidth ();
820 
822  disp_msg->min_disparity = 0.0;
823  disp_msg->max_disparity = disp_msg->T * disp_msg->f / 0.3;
824  disp_msg->delta_d = 0.125;
825 
826  depth.fillDisparityImage (depth_width_, depth_height_, reinterpret_cast<float*>(&disp_msg->image.data[0]), disp_msg->image.step);
827 
828  pub_disparity_.publish (disp_msg);
829 }
830 */
831 
832 
833 }
gazebo::GazeboRosDepthCamera::PointCloudConnect
void PointCloudConnect()
Definition: gazebo_ros_depth_camera.cpp:193
gazebo::GazeboRosCameraUtils::initialized_
bool initialized_
True if camera util is initialized.
Definition: gazebo_ros_camera_utils.h:224
gazebo::GazeboRosDepthCamera::reflectance_pub_
ros::Publisher reflectance_pub_
Definition: gazebo_ros_depth_camera.h:147
gazebo::GazeboRosDepthCamera::depth_image_camera_info_topic_name_
std::string depth_image_camera_info_topic_name_
Definition: gazebo_ros_depth_camera.h:180
gazebo::GazeboRosDepthCamera::point_cloud_topic_name_
std::string point_cloud_topic_name_
ROS image topic name.
Definition: gazebo_ros_depth_camera.h:164
tf::Quaternion::normalize
Quaternion & normalize()
point_cloud2_iterator.h
gazebo::GazeboRosDepthCamera::depth_image_pub_
ros::Publisher depth_image_pub_
Definition: gazebo_ros_depth_camera.h:146
boost::shared_ptr< void >
gazebo::GazeboRosCameraUtils::parentSensor_
sensors::SensorPtr parentSensor_
Definition: gazebo_ros_camera_utils.h:193
gazebo::GazeboRosDepthCamera::use_depth_image_16UC1_format_
bool use_depth_image_16UC1_format_
Definition: gazebo_ros_depth_camera.h:184
gazebo
gazebo::GazeboRosDepthCamera::DepthImageConnect
void DepthImageConnect()
Definition: gazebo_ros_depth_camera.cpp:250
tf::Quaternion::getIdentity
static const Quaternion & getIdentity()
gazebo::GazeboRosDepthCamera::OnNewImageFrame
virtual void OnNewImageFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) override
Update the controller.
Definition: gazebo_ros_depth_camera.cpp:446
gazebo::GazeboRosDepthCamera::FillDepthImageHelper
bool FillDepthImageHelper(sensor_msgs::Image &image_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
Definition: gazebo_ros_depth_camera.cpp:721
gazebo::GazeboRosDepthCamera::DepthInfoConnect
void DepthInfoConnect()
Definition: gazebo_ros_depth_camera.cpp:265
gazebo::GazeboRosDepthCamera::~GazeboRosDepthCamera
~GazeboRosDepthCamera()
Destructor.
Definition: gazebo_ros_depth_camera.cpp:61
gazebo::GazeboRosDepthCamera::normals_topic_name_
std::string normals_topic_name_
ROS normals topic name.
Definition: gazebo_ros_depth_camera.h:170
gazebo::GazeboRosCameraUtils::PutCameraData
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
Definition: gazebo_ros_camera_utils.cpp:639
gazebo::GazeboRosDepthCamera::PointCloudDisconnect
void PointCloudDisconnect()
Definition: gazebo_ros_depth_camera.cpp:202
gazebo::GazeboRosDepthCamera::Load
virtual void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf) override
Load the plugin.
Definition: gazebo_ros_depth_camera.cpp:71
gazebo_ros_depth_camera.h
gazebo::GazeboRosDepthCamera::OnNewDepthFrame
virtual void OnNewDepthFrame(const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) override
Update the controller.
Definition: gazebo_ros_depth_camera.cpp:278
gazebo::GazeboRosDepthCamera::Advertise
virtual void Advertise()
Advertise point cloud, depth image, normals and reflectance.
Definition: gazebo_ros_depth_camera.cpp:146
gazebo::GazeboRosCameraUtils::image_topic_name_
std::string image_topic_name_
ROS image topic name.
Definition: gazebo_ros_camera_utils.h:126
gazebo::GazeboRosCameraUtils::width_
unsigned int width_
Definition: gazebo_ros_camera_utils.h:190
gazebo::GazeboRosDepthCamera::FillDepthImage
void FillDepthImage(const float *_src)
push depth image data into ros topic
Definition: gazebo_ros_depth_camera.cpp:605
gazebo::GazeboRosDepthCamera
Definition: gazebo_ros_depth_camera.h:62
gazebo::GazeboRosDepthCamera::depth_image_camera_info_pub_
ros::Publisher depth_image_camera_info_pub_
Definition: gazebo_ros_depth_camera.h:188
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
gazebo::GazeboRosDepthCamera::depth_image_msg_
sensor_msgs::Image depth_image_msg_
Definition: gazebo_ros_depth_camera.h:152
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
gazebo::GazeboRosCameraUtils::rosnode_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition: gazebo_ros_camera_utils.h:109
ros::AdvertiseOptions
gazebo::GazeboRosDepthCamera::depth_image_topic_name_
std::string depth_image_topic_name_
image where each pixel contains the depth information
Definition: gazebo_ros_depth_camera.h:179
gazebo::GazeboRosDepthCamera::DepthInfoDisconnect
void DepthInfoDisconnect()
Definition: gazebo_ros_depth_camera.cpp:271
tf::Quaternion::setRotation
void setRotation(const Vector3 &axis, const tfScalar &angle)
gazebo::GazeboRosDepthCamera::reflectance_topic_name_
std::string reflectance_topic_name_
ROS reflectance topic name.
Definition: gazebo_ros_depth_camera.h:167
sensor_msgs::image_encodings::TYPE_16UC1
const std::string TYPE_16UC1
gazebo::GazeboRosDepthCamera::ReflectanceDisconnect
void ReflectanceDisconnect()
Decrease the counter which count the subscribers are connected.
Definition: gazebo_ros_depth_camera.cpp:230
gazebo::GazeboRosDepthCamera::last_depth_image_camera_info_update_time_
common::Time last_depth_image_camera_info_update_time_
Definition: gazebo_ros_depth_camera.h:134
gazebo::GazeboRosCameraUtils::height_
unsigned int height_
Definition: gazebo_ros_camera_utils.h:190
gazebo::GazeboRosCameraUtils::PublishCameraInfo
void PublishCameraInfo()
Definition: gazebo_ros_camera_utils.cpp:674
sensor_msgs::PointCloud2Iterator
gazebo::GazeboRosDepthCamera::FillPointCloudHelper
bool FillPointCloudHelper(sensor_msgs::PointCloud2 &point_cloud_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
Definition: gazebo_ros_depth_camera.cpp:627
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
gazebo::GazeboRosDepthCamera::ReflectanceConnect
void ReflectanceConnect()
Increase the counter which count the subscribers are connected.
Definition: gazebo_ros_depth_camera.cpp:212
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
gazebo::GazeboRosCameraUtils::frame_name_
std::string frame_name_
ROS frame transform name to use in the image message header. This should typically match the link nam...
Definition: gazebo_ros_camera_utils.h:142
gazebo::GazeboRosDepthCamera::NormalsConnect
void NormalsConnect()
Increase the counter which count the subscribers are connected.
Definition: gazebo_ros_depth_camera.cpp:221
gazebo::GazeboRosDepthCamera::point_cloud_cutoff_
double point_cloud_cutoff_
Definition: gazebo_ros_depth_camera.h:158
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosDepthCamera::point_cloud_connect_count_
int point_cloud_connect_count_
Keep track of number of connctions for point clouds.
Definition: gazebo_ros_depth_camera.h:112
gazebo::GazeboRosCameraUtils::image_connect_count_
boost::shared_ptr< int > image_connect_count_
Keep track of number of image connections.
Definition: gazebo_ros_camera_utils.h:92
gazebo::GazeboRosCameraUtils::update_period_
double update_period_
Definition: gazebo_ros_camera_utils.h:145
gazebo::GazeboRosDepthCamera::PublishCameraInfo
virtual void PublishCameraInfo()
Definition: gazebo_ros_depth_camera.cpp:781
gazebo::GazeboRosCameraUtils::sensor_update_time_
common::Time sensor_update_time_
Definition: gazebo_ros_camera_utils.h:201
gazebo::GazeboRosDepthCamera::reflectance_msg_
sensor_msgs::Image reflectance_msg_
Definition: gazebo_ros_depth_camera.h:153
gazebo::GazeboRosDepthCamera::FillPointdCloud
void FillPointdCloud(const float *_src)
Put camera data to the ROS topic.
Definition: gazebo_ros_depth_camera.cpp:580
gazebo::GazeboRosCameraUtils::depth_
unsigned int depth_
Definition: gazebo_ros_camera_utils.h:190
gazebo::GazeboRosDepthCamera::reduce_normals_
int reduce_normals_
adding one value each reduce_normals_ to the array marker
Definition: gazebo_ros_depth_camera.h:161
gazebo::GazeboRosCameraUtils::lock_
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
Definition: gazebo_ros_camera_utils.h:167
gazebo::GazeboRosDepthCamera::depth_image_connect_count_
int depth_image_connect_count_
Keep track of number of connctions for point clouds.
Definition: gazebo_ros_depth_camera.h:131
gazebo::GazeboRosDepthCamera::reflectance_connect_count_
int reflectance_connect_count_
Keep track of number of connections for reflectance.
Definition: gazebo_ros_depth_camera.h:117
gazebo::GazeboRosCameraUtils::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
Load the plugin.
Definition: gazebo_ros_camera_utils.cpp:104
gazebo::GazeboRosDepthCamera::pcd_
float * pcd_
copy of the pointcloud data, used to place normals in the world
Definition: gazebo_ros_depth_camera.h:156
gazebo::GazeboRosDepthCamera::load_connection_
event::ConnectionPtr load_connection_
Definition: gazebo_ros_depth_camera.h:190
tf.h
sensor_msgs::PointCloud2Modifier::resize
void resize(size_t size)
gazebo::GazeboRosDepthCamera::normal_pub_
ros::Publisher normal_pub_
Definition: gazebo_ros_depth_camera.h:148
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
gazebo::GazeboRosDepthCamera::depth_info_connect_count_
int depth_info_connect_count_
Definition: gazebo_ros_depth_camera.h:181
gazebo::GazeboRosDepthCamera::DepthImageDisconnect
void DepthImageDisconnect()
Definition: gazebo_ros_depth_camera.cpp:258
sensor_msgs::PointCloud2Modifier
gazebo::GazeboRosCameraUtils::skip_
int skip_
Definition: gazebo_ros_camera_utils.h:171
gazebo::GazeboRosDepthCamera::depth_sensor_update_time_
common::Time depth_sensor_update_time_
Definition: gazebo_ros_depth_camera.h:187
gazebo::GazeboRosDepthCamera::OnNewRGBPointCloud
virtual void OnNewRGBPointCloud(const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) override
Update the controller.
Definition: gazebo_ros_depth_camera.cpp:331
gazebo::GazeboRosCameraUtils::format_
std::string format_
Definition: gazebo_ros_camera_utils.h:191
gazebo::GazeboRosCameraUtils::image_msg_
sensor_msgs::Image image_msg_
ROS image message.
Definition: gazebo_ros_camera_utils.h:114
gazebo::GazeboRosDepthCamera::NormalsDisconnect
void NormalsDisconnect()
Decrease the counter which count the subscribers are connected.
Definition: gazebo_ros_depth_camera.cpp:240
gazebo::GazeboRosDepthCamera::point_cloud_pub_
ros::Publisher point_cloud_pub_
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition: gazebo_ros_depth_camera.h:145
gazebo::GazeboRosDepthCamera::normals_connect_count_
int normals_connect_count_
Keep track of number of connections for normals.
Definition: gazebo_ros_depth_camera.h:124
assert.h
gazebo::GazeboRosCameraUtils::camera_info_topic_name_
std::string camera_info_topic_name_
Definition: gazebo_ros_camera_utils.h:137
gazebo::GazeboRosDepthCamera::point_cloud_msg_
sensor_msgs::PointCloud2 point_cloud_msg_
PointCloud2 point cloud message.
Definition: gazebo_ros_depth_camera.h:151
gazebo::GazeboRosCameraUtils::camera_queue_
ros::CallbackQueue camera_queue_
Definition: gazebo_ros_camera_utils.h:184
gazebo::GazeboRosCameraUtils::camera_
rendering::CameraPtr camera_
Definition: gazebo_ros_camera_utils.h:194
tf::Quaternion
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
gazebo::GazeboRosCameraUtils::OnLoad
event::ConnectionPtr OnLoad(const boost::function< void()> &)
Definition: gazebo_ros_camera_utils.cpp:266


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