gazebo_ros_depth_camera.cpp
Go to the documentation of this file.
00001 /*
00002  *  Gazebo - Outdoor Multi-Robot Simulator
00003  *  Copyright (C) 2003
00004  *     Nate Koenig & Andrew Howard
00005  *
00006  *  This program is free software; you can redistribute it and/or modify
00007  *  it under the terms of the GNU General Public License as published by
00008  *  the Free Software Foundation; either version 2 of the License, or
00009  *  (at your option) any later version.
00010  *
00011  *  This program is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  *  GNU General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU General Public License
00017  *  along with this program; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 /*
00022  @mainpage
00023    Desc: GazeboRosDepthCamera plugin for simulating cameras in Gazebo
00024    Author: John Hsu
00025    Date: 24 Sept 2008
00026    SVN info: $Id$
00027  @htmlinclude manifest.html
00028  @b GazeboRosDepthCamera plugin broadcasts ROS Image messages
00029  */
00030 
00031 #include <algorithm>
00032 #include <assert.h>
00033 #include <boost/thread/thread.hpp>
00034 #include <boost/bind.hpp>
00035 
00036 #include <gazebo_plugins/gazebo_ros_depth_camera.h>
00037 
00038 #include "sensors/Sensor.hh"
00039 #include "sdf/interface/SDF.hh"
00040 #include "sensors/SensorTypes.hh"
00041 
00042 // for creating PointCloud2 from pcl point cloud
00043 #include "pcl/ros/conversions.h"
00044 
00045 #include "tf/tf.h"
00046 
00047 namespace gazebo
00048 {
00049 
00051 // Constructor
00052 GazeboRosDepthCamera::GazeboRosDepthCamera()
00053 {
00054   this->point_cloud_connect_count_ = 0;
00055   this->depth_info_connect_count_ = 0;
00056   this->last_depth_image_camera_info_update_time_ = common::Time(0);
00057 }
00058 
00060 // Destructor
00061 GazeboRosDepthCamera::~GazeboRosDepthCamera()
00062 {
00063 }
00064 
00066 // Load the controller
00067 void GazeboRosDepthCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00068 {
00069   DepthCameraPlugin::Load(_parent, _sdf);
00070 
00071   // copying from DepthCameraPlugin into GazeboRosCameraUtils
00072   this->parentSensor_ = this->parentSensor;
00073   this->width_ = this->width;
00074   this->height_ = this->height;
00075   this->depth_ = this->depth;
00076   this->format_ = this->format;
00077   this->camera_ = this->depthCamera;
00078 
00079   GazeboRosCameraUtils::Load(_parent, _sdf);
00080 
00081   // using a different default
00082   if (!_sdf->GetElement("imageTopicName"))
00083     this->image_topic_name_ = "ir/image_raw";
00084   if (!_sdf->HasElement("cameraInfoTopicName"))
00085     this->camera_info_topic_name_ = "ir/camera_info";
00086 
00087   // point cloud stuff
00088   if (!_sdf->GetElement("pointCloudTopicName"))
00089     this->point_cloud_topic_name_ = "points";
00090   else
00091     this->point_cloud_topic_name_ = _sdf->GetElement("pointCloudTopicName")->GetValueString();
00092 
00093   // depth image stuff
00094   if (!_sdf->GetElement("depthImageTopicName"))
00095     this->depth_image_topic_name_ = "depth/image_raw";
00096   else
00097     this->depth_image_topic_name_ = _sdf->GetElement("depthImageTopicName")->GetValueString();
00098 
00099   if (!_sdf->GetElement("depthImageCameraInfoTopicName"))
00100     this->depth_image_camera_info_topic_name_ = "depth/camera_info";
00101   else
00102     this->depth_image_camera_info_topic_name_ = _sdf->GetElement("depthImageCameraInfoTopicName")->GetValueString();
00103 
00104   if (!_sdf->GetElement("pointCloudCutoff"))
00105     this->point_cloud_cutoff_ = 0.4;
00106   else
00107     this->point_cloud_cutoff_ = _sdf->GetElement("pointCloudCutoff")->GetValueDouble();
00108 
00109   ros::AdvertiseOptions point_cloud_ao =
00110     ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
00111       this->point_cloud_topic_name_,1,
00112       boost::bind( &GazeboRosDepthCamera::PointCloudConnect,this),
00113       boost::bind( &GazeboRosDepthCamera::PointCloudDisconnect,this),
00114       ros::VoidPtr(), &this->camera_queue_);
00115   this->point_cloud_pub_ = this->rosnode_->advertise(point_cloud_ao);
00116 
00117   ros::AdvertiseOptions depth_image_ao =
00118     ros::AdvertiseOptions::create< sensor_msgs::Image >(
00119       this->depth_image_topic_name_,1,
00120       boost::bind( &GazeboRosDepthCamera::DepthImageConnect,this),
00121       boost::bind( &GazeboRosDepthCamera::DepthImageDisconnect,this),
00122       ros::VoidPtr(), &this->camera_queue_);
00123   this->depth_image_pub_ = this->rosnode_->advertise(depth_image_ao);
00124 
00125   ros::AdvertiseOptions depth_image_camera_info_ao =
00126     ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
00127         this->depth_image_camera_info_topic_name_,1,
00128         boost::bind( &GazeboRosDepthCamera::DepthInfoConnect,this),
00129         boost::bind( &GazeboRosDepthCamera::DepthInfoDisconnect,this),
00130         ros::VoidPtr(), &this->camera_queue_);
00131   this->depth_image_camera_info_pub_ = this->rosnode_->advertise(depth_image_camera_info_ao);
00132 }
00133 
00135 // Increment count
00136 void GazeboRosDepthCamera::PointCloudConnect()
00137 {
00138   this->point_cloud_connect_count_++;
00139   this->image_connect_count_++;
00140   this->parentSensor->SetActive(true);
00141 }
00143 // Decrement count
00144 void GazeboRosDepthCamera::PointCloudDisconnect()
00145 {
00146   this->point_cloud_connect_count_--;
00147   this->image_connect_count_--;
00148   if (this->point_cloud_connect_count_ <= 0)
00149     this->parentSensor->SetActive(false);
00150 }
00151 
00153 // Increment count
00154 void GazeboRosDepthCamera::DepthImageConnect()
00155 {
00156   this->depth_image_connect_count_++;
00157   this->parentSensor->SetActive(true);
00158 }
00160 // Decrement count
00161 void GazeboRosDepthCamera::DepthImageDisconnect()
00162 {
00163   this->depth_image_connect_count_--;
00164 }
00165 
00167 // Increment count
00168 void GazeboRosDepthCamera::DepthInfoConnect()
00169 {
00170   this->depth_info_connect_count_++;
00171 }
00173 // Decrement count
00174 void GazeboRosDepthCamera::DepthInfoDisconnect()
00175 {
00176   this->depth_info_connect_count_--;
00177 }
00178 
00180 // Update the controller
00181 void GazeboRosDepthCamera::OnNewDepthFrame(const float *_image,
00182     unsigned int _width, unsigned int _height, unsigned int _depth,
00183     const std::string &_format)
00184 {
00185   this->depth_sensor_update_time_ = this->parentSensor->GetLastUpdateTime();
00186   if (this->parentSensor->IsActive())
00187   {
00188     if (this->point_cloud_connect_count_ <= 0 &&
00189         this->depth_image_connect_count_ <= 0 &&
00190         this->image_connect_count_ <= 0)
00191     {
00192       this->parentSensor->SetActive(false);
00193     }
00194     else
00195     {
00196       if (this->point_cloud_connect_count_ > 0)
00197         this->FillPointdCloud(_image);
00198 
00199       if (this->depth_image_connect_count_ > 0)
00200         this->FillDepthImage(_image);
00201     }
00202   }
00203   else
00204   {
00205     if (this->point_cloud_connect_count_ > 0 ||
00206         this->depth_image_connect_count_ <= 0)
00207       // do this first so there's chance for sensor to run 1 frame after activate
00208       this->parentSensor->SetActive(true);
00209   }
00210 }
00211 
00213 // Update the controller
00214 void GazeboRosDepthCamera::OnNewRGBPointCloud(const float *_pcd,
00215     unsigned int _width, unsigned int _height, unsigned int _depth,
00216     const std::string &_format)
00217 {
00218   this->depth_sensor_update_time_ = this->parentSensor->GetLastUpdateTime();
00219   if (!this->parentSensor->IsActive())
00220   {
00221     if (this->point_cloud_connect_count_ > 0)
00222       // do this first so there's chance for sensor to run 1 frame after activate
00223       this->parentSensor->SetActive(true);
00224   }
00225   else
00226   {
00227     if (this->point_cloud_connect_count_ > 0)
00228     {
00229       this->lock_.lock();
00230       this->point_cloud_msg_.header.frame_id = this->frame_name_;
00231       this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00232       this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00233       this->point_cloud_msg_.width = this->width;
00234       this->point_cloud_msg_.height = this->height;
00235       this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
00236 
00237       pcl::PointCloud<pcl::PointXYZRGB> point_cloud;
00238       point_cloud.points.resize(0);
00239       point_cloud.is_dense = true;
00240 
00241       for (unsigned int i = 0; i < _width; i++)
00242       {
00243         for (unsigned int j = 0; j < _height; j++)
00244         {
00245           unsigned int index = (j * _width) + i;
00246           pcl::PointXYZRGB point;
00247           point.x = _pcd[4 * index];
00248           point.y = _pcd[4 * index + 1];
00249           point.z = _pcd[4 * index + 2];
00250           point.rgb = _pcd[4 * index + 3];
00251           point_cloud.points.push_back(point);
00252           if (i == _width /2 && j == _height / 2)
00253           {
00254             uint32_t rgb = *reinterpret_cast<int*>(&point.rgb);
00255             uint8_t r = (rgb >> 16) & 0x0000ff;
00256             uint8_t g = (rgb >> 8)  & 0x0000ff;
00257             uint8_t b = (rgb)       & 0x0000ff;
00258             std::cerr << (int)r << " " << (int)g << " " << (int)b << "\n";
00259           }
00260         }
00261       }
00262       point_cloud.header = this->point_cloud_msg_.header;
00263       pcl::toROSMsg(point_cloud, this->point_cloud_msg_);
00264 
00265       this->point_cloud_pub_.publish(this->point_cloud_msg_);
00266       this->lock_.unlock();
00267     }
00268   }
00269 }
00270 
00272 // Update the controller
00273 void GazeboRosDepthCamera::OnNewImageFrame(const unsigned char *_image,
00274     unsigned int _width, unsigned int _height, unsigned int _depth,
00275     const std::string &_format)
00276 {
00277   //ROS_ERROR("camera_ new frame %s %s",this->parentSensor_->GetName().c_str(),this->frame_name_.c_str());
00278   this->sensor_update_time_ = this->parentSensor->GetLastUpdateTime();
00279 
00280   if (!this->parentSensor->IsActive())
00281   {
00282     if (this->image_connect_count_ > 0)
00283       // do this first so there's chance for sensor to run 1 frame after activate
00284       this->parentSensor->SetActive(true);
00285   }
00286   else
00287   {
00288     if (this->image_connect_count_ > 0)
00289       this->PutCameraData(_image);
00290   }
00291 }
00292 
00294 // Put camera data to the interface
00295 void GazeboRosDepthCamera::FillPointdCloud(const float *_src)
00296 {
00297   this->lock_.lock();
00298 
00299   this->point_cloud_msg_.header.frame_id = this->frame_name_;
00300   this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00301   this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00302   this->point_cloud_msg_.width = this->width;
00303   this->point_cloud_msg_.height = this->height;
00304   this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
00305 
00307   FillPointCloudHelper(this->point_cloud_msg_,
00308                  this->height,
00309                  this->width,
00310                  this->skip_,
00311                  (void*)_src );
00312 
00313   this->point_cloud_pub_.publish(this->point_cloud_msg_);
00314 
00315   this->lock_.unlock();
00316 }
00317 
00319 // Put depth image data to the interface
00320 void GazeboRosDepthCamera::FillDepthImage(const float *_src)
00321 {
00322   this->lock_.lock();
00323   // copy data into image
00324   this->depth_image_msg_.header.frame_id = this->frame_name_;
00325   this->depth_image_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00326   this->depth_image_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00327 
00329   FillDepthImageHelper(this->depth_image_msg_,
00330                  this->height,
00331                  this->width,
00332                  this->skip_,
00333                  (void*)_src );
00334 
00335   this->depth_image_pub_.publish(this->depth_image_msg_);
00336 
00337   this->lock_.unlock();
00338 }
00339 
00340 
00341 // Fill depth information
00342 bool GazeboRosDepthCamera::FillPointCloudHelper(
00343     sensor_msgs::PointCloud2 &point_cloud_msg,
00344     uint32_t rows_arg, uint32_t cols_arg,
00345     uint32_t step_arg, void* data_arg)
00346 {
00347   pcl::PointCloud<pcl::PointXYZRGB> point_cloud;
00348 
00349   point_cloud.points.resize(0);
00350   point_cloud.is_dense = true;
00351 
00352   float* toCopyFrom = (float*)data_arg;
00353   int index = 0;
00354 
00355   double hfov = this->parentSensor->GetDepthCamera()->GetHFOV().Radian();
00356   double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
00357 
00358   // convert depth to point cloud
00359   for (uint32_t j=0; j<rows_arg; j++)
00360   {
00361     double pAngle;
00362     if (rows_arg>1) pAngle = atan2( (double)j - 0.5*(double)(rows_arg-1), fl);
00363     else            pAngle = 0.0;
00364 
00365     for (uint32_t i=0; i<cols_arg; i++)
00366     {
00367       double yAngle;
00368       if (cols_arg>1) yAngle = atan2( (double)i - 0.5*(double)(cols_arg-1), fl);
00369       else            yAngle = 0.0;
00370 
00371       double depth = toCopyFrom[index++];
00372 
00373       // in optical frame
00374       // hardcoded rotation rpy(-M_PI/2, 0, -M_PI/2) is built-in
00375       // to urdf, where the *_optical_frame should have above relative
00376       // rotation from the physical camera *_frame
00377       pcl::PointXYZRGB point;
00378       point.x      = depth * tan(yAngle);
00379       point.y      = depth * tan(pAngle);
00380       if(depth > this->point_cloud_cutoff_)
00381       {
00382         point.z    = depth;
00383       }
00384       else //point in the unseeable range
00385       {
00386         point.x = point.y = point.z = std::numeric_limits<float>::quiet_NaN ();
00387         point_cloud.is_dense = false;
00388       }
00389 
00390       // put image color data for each point
00391       uint8_t*  image_src = (uint8_t*)(&(this->image_msg_.data[0]));
00392       if (this->image_msg_.data.size() == rows_arg*cols_arg*3)
00393       {
00394         // color
00395         point.r = image_src[i*3+j*cols_arg*3+0];
00396         point.g = image_src[i*3+j*cols_arg*3+1];
00397         point.b = image_src[i*3+j*cols_arg*3+2];
00398       }
00399       else if (this->image_msg_.data.size() == rows_arg*cols_arg)
00400       {
00401         // mono (or bayer?  @todo; fix for bayer)
00402         point.r = image_src[i+j*cols_arg];
00403         point.g = image_src[i+j*cols_arg];
00404         point.b = image_src[i+j*cols_arg];
00405       }
00406       else
00407       {
00408         // no image
00409         point.r = 0;
00410         point.g = 0;
00411         point.b = 0;
00412       }
00413 
00414       point_cloud.points.push_back(point);
00415     }
00416   }
00417 
00418   point_cloud.header = point_cloud_msg.header;
00419   pcl::toROSMsg(point_cloud, point_cloud_msg);
00420   return true;
00421 }
00422 
00423 // Fill depth information
00424 bool GazeboRosDepthCamera::FillDepthImageHelper(
00425     sensor_msgs::Image& image_msg,
00426     uint32_t rows_arg, uint32_t cols_arg,
00427     uint32_t step_arg, void* data_arg)
00428 {
00429   image_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00430   image_msg.height = rows_arg;
00431   image_msg.width = cols_arg;
00432   image_msg.step = sizeof(float) * cols_arg;
00433   image_msg.data.resize(rows_arg * cols_arg * sizeof(float));
00434   image_msg.is_bigendian = 0;
00435 
00436   const float bad_point = std::numeric_limits<float>::quiet_NaN();
00437 
00438   float* dest = (float*)(&(image_msg.data[0]));
00439   float* toCopyFrom = (float*)data_arg;
00440   int index = 0;
00441 
00442   // convert depth to point cloud
00443   for (uint32_t j = 0; j < rows_arg; j++)
00444   {
00445     for (uint32_t i = 0; i < cols_arg; i++)
00446     {
00447       float depth = toCopyFrom[index++];
00448 
00449       if (depth > this->point_cloud_cutoff_)
00450       {
00451         dest[i + j * cols_arg] = depth;
00452       }
00453       else //point in the unseeable range
00454       {
00455         dest[i + j * cols_arg] = bad_point;
00456       }
00457     }
00458   }
00459   return true;
00460 }
00461 
00462 void GazeboRosDepthCamera::PublishCameraInfo()
00463 {
00464   ROS_DEBUG("publishing default camera info, then depth camera info");
00465   GazeboRosCameraUtils::PublishCameraInfo();
00466 
00467   if (this->depth_info_connect_count_ > 0)
00468   {
00469     this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
00470     common::Time cur_time = this->world_->GetSimTime();
00471     if (cur_time - this->last_depth_image_camera_info_update_time_ >= this->update_period_)
00472     {
00473       this->PublishCameraInfo(this->depth_image_camera_info_pub_);
00474       this->last_depth_image_camera_info_update_time_ = cur_time;
00475     }
00476   }
00477 }
00478 
00479 //@todo: publish disparity similar to openni_camera_deprecated/src/nodelets/openni_nodelet.cpp.
00480 /*
00481 #include <stereo_msgs/DisparityImage.h>
00482 pub_disparity_ = comm_nh.advertise<stereo_msgs::DisparityImage > ("depth/disparity", 5, subscriberChanged2, subscriberChanged2);
00483 
00484 void GazeboRosDepthCamera::PublishDisparityImage(const DepthImage& depth, ros::Time time)
00485 {
00486   stereo_msgs::DisparityImagePtr disp_msg = boost::make_shared<stereo_msgs::DisparityImage > ();
00487   disp_msg->header.stamp                  = time;
00488   disp_msg->header.frame_id               = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_;
00489   disp_msg->image.header                  = disp_msg->header;
00490   disp_msg->image.encoding                = sensor_msgs::image_encodings::TYPE_32FC1;
00491   disp_msg->image.height                  = depth_height_;
00492   disp_msg->image.width                   = depth_width_;
00493   disp_msg->image.step                    = disp_msg->image.width * sizeof (float);
00494   disp_msg->image.data.resize (disp_msg->image.height * disp_msg->image.step);
00495   disp_msg->T = depth.getBaseline ();
00496   disp_msg->f = depth.getFocalLength () * depth_width_ / depth.getWidth ();
00497 
00499   disp_msg->min_disparity = 0.0;
00500   disp_msg->max_disparity = disp_msg->T * disp_msg->f / 0.3;
00501   disp_msg->delta_d = 0.125;
00502 
00503   depth.fillDisparityImage (depth_width_, depth_height_, reinterpret_cast<float*>(&disp_msg->image.data[0]), disp_msg->image.step);
00504 
00505   pub_disparity_.publish (disp_msg);
00506 }
00507 */
00508 
00509 // Register this plugin with the simulator
00510 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosDepthCamera)
00511 
00512 }


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Mon Oct 6 2014 12:15:44