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 
35 
36 #include <tf/tf.h>
37 
38 namespace gazebo
39 {
40 // Register this plugin with the simulator
41 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosDepthCamera)
42 
43 // Constructor
46 {
47  this->point_cloud_connect_count_ = 0;
48  this->depth_image_connect_count_ = 0;
49  this->depth_info_connect_count_ = 0;
50  this->last_depth_image_camera_info_update_time_ = common::Time(0);
51 }
52 
54 // Destructor
56 {
57 }
58 
60 // Load the controller
61 void GazeboRosDepthCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
62 {
63  DepthCameraPlugin::Load(_parent, _sdf);
64 
65  // Make sure the ROS node for Gazebo has already been initialized
66  if (!ros::isInitialized())
67  {
68  ROS_FATAL_STREAM_NAMED("depth_camera", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
69  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
70  return;
71  }
72 
73  // copying from DepthCameraPlugin into GazeboRosCameraUtils
74  this->parentSensor_ = this->parentSensor;
75  this->width_ = this->width;
76  this->height_ = this->height;
77  this->depth_ = this->depth;
78  this->format_ = this->format;
79  this->camera_ = this->depthCamera;
80 
81  // using a different default
82  if (!_sdf->HasElement("imageTopicName"))
83  this->image_topic_name_ = "ir/image_raw";
84  if (!_sdf->HasElement("cameraInfoTopicName"))
85  this->camera_info_topic_name_ = "ir/camera_info";
86 
87  // point cloud stuff
88  if (!_sdf->HasElement("pointCloudTopicName"))
89  this->point_cloud_topic_name_ = "points";
90  else
91  this->point_cloud_topic_name_ = _sdf->GetElement("pointCloudTopicName")->Get<std::string>();
92 
93  // depth image stuff
94  if (!_sdf->HasElement("depthImageTopicName"))
95  this->depth_image_topic_name_ = "depth/image_raw";
96  else
97  this->depth_image_topic_name_ = _sdf->GetElement("depthImageTopicName")->Get<std::string>();
98 
99  if (!_sdf->HasElement("depthImageCameraInfoTopicName"))
100  this->depth_image_camera_info_topic_name_ = "depth/camera_info";
101  else
102  this->depth_image_camera_info_topic_name_ = _sdf->GetElement("depthImageCameraInfoTopicName")->Get<std::string>();
103 
104  if (!_sdf->HasElement("pointCloudCutoff"))
105  this->point_cloud_cutoff_ = 0.4;
106  else
107  this->point_cloud_cutoff_ = _sdf->GetElement("pointCloudCutoff")->Get<double>();
108 
110  GazeboRosCameraUtils::Load(_parent, _sdf);
111 }
112 
114 {
115  ros::AdvertiseOptions point_cloud_ao =
116  ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
117  this->point_cloud_topic_name_,1,
118  boost::bind( &GazeboRosDepthCamera::PointCloudConnect,this),
119  boost::bind( &GazeboRosDepthCamera::PointCloudDisconnect,this),
120  ros::VoidPtr(), &this->camera_queue_);
121  this->point_cloud_pub_ = this->rosnode_->advertise(point_cloud_ao);
122 
123  ros::AdvertiseOptions depth_image_ao =
124  ros::AdvertiseOptions::create< sensor_msgs::Image >(
125  this->depth_image_topic_name_,1,
126  boost::bind( &GazeboRosDepthCamera::DepthImageConnect,this),
127  boost::bind( &GazeboRosDepthCamera::DepthImageDisconnect,this),
128  ros::VoidPtr(), &this->camera_queue_);
129  this->depth_image_pub_ = this->rosnode_->advertise(depth_image_ao);
130 
131  ros::AdvertiseOptions depth_image_camera_info_ao =
132  ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
134  boost::bind( &GazeboRosDepthCamera::DepthInfoConnect,this),
135  boost::bind( &GazeboRosDepthCamera::DepthInfoDisconnect,this),
136  ros::VoidPtr(), &this->camera_queue_);
137  this->depth_image_camera_info_pub_ = this->rosnode_->advertise(depth_image_camera_info_ao);
138 }
139 
140 
142 // Increment count
144 {
146  (*this->image_connect_count_)++;
147  this->parentSensor->SetActive(true);
148 }
150 // Decrement count
152 {
154  (*this->image_connect_count_)--;
155  if (this->point_cloud_connect_count_ <= 0)
156  this->parentSensor->SetActive(false);
157 }
158 
160 // Increment count
162 {
164  this->parentSensor->SetActive(true);
165 }
167 // Decrement count
169 {
171 }
172 
174 // Increment count
176 {
178 }
180 // Decrement count
182 {
184 }
185 
187 // Update the controller
188 void GazeboRosDepthCamera::OnNewDepthFrame(const float *_image,
189  unsigned int _width, unsigned int _height, unsigned int _depth,
190  const std::string &_format)
191 {
192  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
193  return;
194 
195 # if GAZEBO_MAJOR_VERSION >= 7
196  this->depth_sensor_update_time_ = this->parentSensor->LastMeasurementTime();
197 # else
198  this->depth_sensor_update_time_ = this->parentSensor->GetLastMeasurementTime();
199 # endif
200 
201  if (this->parentSensor->IsActive())
202  {
203  if (this->point_cloud_connect_count_ <= 0 &&
204  this->depth_image_connect_count_ <= 0 &&
205  (*this->image_connect_count_) <= 0)
206  {
207  this->parentSensor->SetActive(false);
208  }
209  else
210  {
211  if (this->point_cloud_connect_count_ > 0)
212  this->FillPointdCloud(_image);
213 
214  if (this->depth_image_connect_count_ > 0)
215  this->FillDepthImage(_image);
216  }
217  }
218  else
219  {
220  if (this->point_cloud_connect_count_ > 0 ||
221  this->depth_image_connect_count_ <= 0)
222  // do this first so there's chance for sensor to run 1 frame after activate
223  this->parentSensor->SetActive(true);
224  }
225 }
226 
228 // Update the controller
230  unsigned int _width, unsigned int _height, unsigned int _depth,
231  const std::string &_format)
232 {
233  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
234  return;
235 
236 # if GAZEBO_MAJOR_VERSION >= 7
237  this->depth_sensor_update_time_ = this->parentSensor->LastMeasurementTime();
238 # else
239  this->depth_sensor_update_time_ = this->parentSensor->GetLastMeasurementTime();
240 # endif
241 
242  if (!this->parentSensor->IsActive())
243  {
244  if (this->point_cloud_connect_count_ > 0)
245  // do this first so there's chance for sensor to run 1 frame after activate
246  this->parentSensor->SetActive(true);
247  }
248  else
249  {
250  if (this->point_cloud_connect_count_ > 0)
251  {
252  this->lock_.lock();
253  this->point_cloud_msg_.header.frame_id = this->frame_name_;
254  this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
255  this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
256  this->point_cloud_msg_.width = this->width;
257  this->point_cloud_msg_.height = this->height;
258  this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
259 
261  pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
262  pcd_modifier.resize(_width*_height);
263 
264  point_cloud_msg_.is_dense = true;
265 
270 
271  for (unsigned int i = 0; i < _width; i++)
272  {
273  for (unsigned int j = 0; j < _height; j++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
274  {
275  unsigned int index = (j * _width) + i;
276  *iter_x = _pcd[4 * index];
277  *iter_y = _pcd[4 * index + 1];
278  *iter_z = _pcd[4 * index + 2];
279  *iter_rgb = _pcd[4 * index + 3];
280  if (i == _width /2 && j == _height / 2)
281  {
282  uint32_t rgb = *reinterpret_cast<int*>(&(*iter_rgb));
283  uint8_t r = (rgb >> 16) & 0x0000ff;
284  uint8_t g = (rgb >> 8) & 0x0000ff;
285  uint8_t b = (rgb) & 0x0000ff;
286  std::cerr << (int)r << " " << (int)g << " " << (int)b << "\n";
287  }
288  }
289  }
290 
292  this->lock_.unlock();
293  }
294  }
295 }
296 
298 // Update the controller
299 void GazeboRosDepthCamera::OnNewImageFrame(const unsigned char *_image,
300  unsigned int _width, unsigned int _height, unsigned int _depth,
301  const std::string &_format)
302 {
303  if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
304  return;
305 
306  //ROS_ERROR_NAMED("depth_camera", "camera_ new frame %s %s",this->parentSensor_->GetName().c_str(),this->frame_name_.c_str());
307 # if GAZEBO_MAJOR_VERSION >= 7
308  this->sensor_update_time_ = this->parentSensor->LastMeasurementTime();
309 # else
310  this->sensor_update_time_ = this->parentSensor->GetLastMeasurementTime();
311 # endif
312 
313  if (!this->parentSensor->IsActive())
314  {
315  if ((*this->image_connect_count_) > 0)
316  // do this first so there's chance for sensor to run 1 frame after activate
317  this->parentSensor->SetActive(true);
318  }
319  else
320  {
321  if ((*this->image_connect_count_) > 0)
322  {
323  this->PutCameraData(_image);
324  // TODO(lucasw) publish camera info with depth image
325  // this->PublishCameraInfo(sensor_update_time);
326  }
327  }
328 }
329 
331 // Put camera data to the interface
333 {
334  this->lock_.lock();
335 
336  this->point_cloud_msg_.header.frame_id = this->frame_name_;
337  this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
338  this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
339  this->point_cloud_msg_.width = this->width;
340  this->point_cloud_msg_.height = this->height;
341  this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
342 
345  this->height,
346  this->width,
347  this->skip_,
348  (void*)_src );
349 
351 
352  this->lock_.unlock();
353 }
354 
356 // Put depth image data to the interface
358 {
359  this->lock_.lock();
360  // copy data into image
361  this->depth_image_msg_.header.frame_id = this->frame_name_;
362  this->depth_image_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
363  this->depth_image_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
364 
367  this->height,
368  this->width,
369  this->skip_,
370  (void*)_src );
371 
373 
374  this->lock_.unlock();
375 }
376 
377 
378 // Fill depth information
380  sensor_msgs::PointCloud2 &point_cloud_msg,
381  uint32_t rows_arg, uint32_t cols_arg,
382  uint32_t step_arg, void* data_arg)
383 {
384  sensor_msgs::PointCloud2Modifier pcd_modifier(point_cloud_msg);
385  pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
386  pcd_modifier.resize(rows_arg*cols_arg);
387 
392 
393  point_cloud_msg.is_dense = true;
394 
395  float* toCopyFrom = (float*)data_arg;
396  int index = 0;
397 
398  double hfov = this->parentSensor->DepthCamera()->HFOV().Radian();
399  double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
400 
401  // convert depth to point cloud
402  for (uint32_t j=0; j<rows_arg; j++)
403  {
404  double pAngle;
405  if (rows_arg>1) pAngle = atan2( (double)j - 0.5*(double)(rows_arg-1), fl);
406  else pAngle = 0.0;
407 
408  for (uint32_t i=0; i<cols_arg; i++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
409  {
410  double yAngle;
411  if (cols_arg>1) yAngle = atan2( (double)i - 0.5*(double)(cols_arg-1), fl);
412  else yAngle = 0.0;
413 
414  double depth = toCopyFrom[index++];
415 
416  // in optical frame
417  // hardcoded rotation rpy(-M_PI/2, 0, -M_PI/2) is built-in
418  // to urdf, where the *_optical_frame should have above relative
419  // rotation from the physical camera *_frame
420  *iter_x = depth * tan(yAngle);
421  *iter_y = depth * tan(pAngle);
422  if(depth > this->point_cloud_cutoff_)
423  {
424  *iter_z = depth;
425  }
426  else //point in the unseeable range
427  {
428  *iter_x = *iter_y = *iter_z = std::numeric_limits<float>::quiet_NaN ();
429  point_cloud_msg.is_dense = false;
430  }
431 
432  // put image color data for each point
433  uint8_t* image_src = (uint8_t*)(&(this->image_msg_.data[0]));
434  if (this->image_msg_.data.size() == rows_arg*cols_arg*3)
435  {
436  // color
437  iter_rgb[0] = image_src[i*3+j*cols_arg*3+0];
438  iter_rgb[1] = image_src[i*3+j*cols_arg*3+1];
439  iter_rgb[2] = image_src[i*3+j*cols_arg*3+2];
440  }
441  else if (this->image_msg_.data.size() == rows_arg*cols_arg)
442  {
443  // mono (or bayer? @todo; fix for bayer)
444  iter_rgb[0] = image_src[i+j*cols_arg];
445  iter_rgb[1] = image_src[i+j*cols_arg];
446  iter_rgb[2] = image_src[i+j*cols_arg];
447  }
448  else
449  {
450  // no image
451  iter_rgb[0] = 0;
452  iter_rgb[1] = 0;
453  iter_rgb[2] = 0;
454  }
455  }
456  }
457 
458  return true;
459 }
460 
461 // Fill depth information
463  sensor_msgs::Image& image_msg,
464  uint32_t rows_arg, uint32_t cols_arg,
465  uint32_t step_arg, void* data_arg)
466 {
467  image_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
468  image_msg.height = rows_arg;
469  image_msg.width = cols_arg;
470  image_msg.step = sizeof(float) * cols_arg;
471  image_msg.data.resize(rows_arg * cols_arg * sizeof(float));
472  image_msg.is_bigendian = 0;
473 
474  const float bad_point = std::numeric_limits<float>::quiet_NaN();
475 
476  float* dest = (float*)(&(image_msg.data[0]));
477  float* toCopyFrom = (float*)data_arg;
478  int index = 0;
479 
480  // convert depth to point cloud
481  for (uint32_t j = 0; j < rows_arg; j++)
482  {
483  for (uint32_t i = 0; i < cols_arg; i++)
484  {
485  float depth = toCopyFrom[index++];
486 
487  if (depth > this->point_cloud_cutoff_)
488  {
489  dest[i + j * cols_arg] = depth;
490  }
491  else //point in the unseeable range
492  {
493  dest[i + j * cols_arg] = bad_point;
494  }
495  }
496  }
497  return true;
498 }
499 
501 {
502  ROS_DEBUG_NAMED("depth_camera", "publishing default camera info, then depth camera info");
504 
505  if (this->depth_info_connect_count_ > 0)
506  {
507 # if GAZEBO_MAJOR_VERSION >= 7
508  common::Time sensor_update_time = this->parentSensor_->LastMeasurementTime();
509 # else
510  common::Time sensor_update_time = this->parentSensor_->GetLastMeasurementTime();
511 # endif
512  this->sensor_update_time_ = sensor_update_time;
513  if (sensor_update_time - this->last_depth_image_camera_info_update_time_ >= this->update_period_)
514  {
515  this->PublishCameraInfo(this->depth_image_camera_info_pub_); // , sensor_update_time);
516  this->last_depth_image_camera_info_update_time_ = sensor_update_time;
517  }
518  }
519 }
520 
521 //@todo: publish disparity similar to openni_camera_deprecated/src/nodelets/openni_nodelet.cpp.
522 /*
523 #include <stereo_msgs/DisparityImage.h>
524 pub_disparity_ = comm_nh.advertise<stereo_msgs::DisparityImage > ("depth/disparity", 5, subscriberChanged2, subscriberChanged2);
525 
526 void GazeboRosDepthCamera::PublishDisparityImage(const DepthImage& depth, ros::Time time)
527 {
528  stereo_msgs::DisparityImagePtr disp_msg = boost::make_shared<stereo_msgs::DisparityImage > ();
529  disp_msg->header.stamp = time;
530  disp_msg->header.frame_id = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_;
531  disp_msg->image.header = disp_msg->header;
532  disp_msg->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
533  disp_msg->image.height = depth_height_;
534  disp_msg->image.width = depth_width_;
535  disp_msg->image.step = disp_msg->image.width * sizeof (float);
536  disp_msg->image.data.resize (disp_msg->image.height * disp_msg->image.step);
537  disp_msg->T = depth.getBaseline ();
538  disp_msg->f = depth.getFocalLength () * depth_width_ / depth.getWidth ();
539 
541  disp_msg->min_disparity = 0.0;
542  disp_msg->max_disparity = disp_msg->T * disp_msg->f / 0.3;
543  disp_msg->delta_d = 0.125;
544 
545  depth.fillDisparityImage (depth_width_, depth_height_, reinterpret_cast<float*>(&disp_msg->image.data[0]), disp_msg->image.step);
546 
547  pub_disparity_.publish (disp_msg);
548 }
549 */
550 
551 
552 }
virtual void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
std::string image_topic_name_
ROS image topic name.
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
std::string depth_image_topic_name_
image where each pixel contains the depth information
ROSCPP_DECL bool isInitialized()
std::string point_cloud_topic_name_
ROS image topic name.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
Load the plugin.
boost::shared_ptr< int > image_connect_count_
Keep track of number of image connections.
sensor_msgs::Image image_msg_
ROS image message.
#define ROS_DEBUG_NAMED(name,...)
void publish(const boost::shared_ptr< M > &message) const
event::ConnectionPtr OnLoad(const boost::function< void()> &)
#define ROS_FATAL_STREAM_NAMED(name, args)
const std::string TYPE_32FC1
bool initialized_
True if camera util is initialized.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string frame_name_
ROS frame transform name to use in the image message header. This should typically match the link nam...
bool FillDepthImageHelper(sensor_msgs::Image &image_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
sensor_msgs::PointCloud2 point_cloud_msg_
PointCloud2 point cloud message.
ros::Publisher point_cloud_pub_
A pointer to the ROS node. A node will be instantiated if it does not exist.
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
int point_cloud_connect_count_
Keep track of number of connctions for point clouds.
virtual void OnNewDepthFrame(const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
void FillPointdCloud(const float *_src)
Put camera data to the ROS topic.
int depth_image_connect_count_
Keep track of number of connctions for point clouds.
void FillDepthImage(const float *_src)
push depth image data into ros topic
virtual void Advertise()
Advertise point cloud and depth image.
void setPointCloud2FieldsByString(int n_fields,...)
virtual void OnNewRGBPointCloud(const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
boost::shared_ptr< void > VoidPtr
virtual void OnNewImageFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
bool FillPointCloudHelper(sensor_msgs::PointCloud2 &point_cloud_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)


gazebo_plugins
Author(s): John Hsu
autogenerated on Wed Aug 24 2022 02:47:52