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