gazebo_ros_openni_kinect.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: GazeboRosOpenniKinect 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 GazeboRosOpenniKinect 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_openni_kinect.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 GazeboRosOpenniKinect::GazeboRosOpenniKinect()
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 GazeboRosOpenniKinect::~GazeboRosOpenniKinect()
00062 {
00063 }
00064 
00066 // Load the controller
00067 void GazeboRosOpenniKinect::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00068 {
00069   DepthCameraPlugin::Load(_parent, _sdf);
00070 
00071   this->parentSensor_ = this->parentSensor;
00072   this->width_ = this->width;
00073   this->height_ = this->height;
00074   this->depth_ = this->depth;
00075   this->format_ = this->format;
00076   this->camera_ = this->depthCamera;
00077 
00078   GazeboRosCameraUtils::Load(_parent, _sdf);
00079 
00080   // using a different default
00081   if (!_sdf->GetElement("imageTopicName"))
00082     this->image_topic_name_ = "ir/image_raw";
00083   if (!_sdf->HasElement("cameraInfoTopicName"))
00084     this->camera_info_topic_name_ = "ir/camera_info";
00085 
00086   // point cloud stuff
00087   if (!_sdf->GetElement("pointCloudTopicName"))
00088     this->point_cloud_topic_name_ = "points";
00089   else
00090     this->point_cloud_topic_name_ = _sdf->GetElement("pointCloudTopicName")->GetValueString();
00091 
00092   // depth image stuff
00093   if (!_sdf->GetElement("depthImageTopicName"))
00094     this->depth_image_topic_name_ = "depth/image_raw";
00095   else
00096     this->depth_image_topic_name_ = _sdf->GetElement("depthImageTopicName")->GetValueString();
00097 
00098   if (!_sdf->GetElement("depthImageCameraInfoTopicName"))
00099     this->depth_image_camera_info_topic_name_ = "depth/camera_info";
00100   else
00101     this->depth_image_camera_info_topic_name_ = _sdf->GetElement("depthImageCameraInfoTopicName")->GetValueString();
00102 
00103   if (!_sdf->GetElement("pointCloudCutoff"))
00104     this->point_cloud_cutoff_ = 0.4;
00105   else
00106     this->point_cloud_cutoff_ = _sdf->GetElement("pointCloudCutoff")->GetValueDouble();
00107 
00108   ros::AdvertiseOptions point_cloud_ao = 
00109     ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
00110       this->point_cloud_topic_name_,1,
00111       boost::bind( &GazeboRosOpenniKinect::PointCloudConnect,this),
00112       boost::bind( &GazeboRosOpenniKinect::PointCloudDisconnect,this), 
00113       ros::VoidPtr(), &this->camera_queue_);
00114   this->point_cloud_pub_ = this->rosnode_->advertise(point_cloud_ao);
00115 
00116   ros::AdvertiseOptions depth_image_ao = 
00117     ros::AdvertiseOptions::create< sensor_msgs::Image >(
00118       this->depth_image_topic_name_,1,
00119       boost::bind( &GazeboRosOpenniKinect::DepthImageConnect,this),
00120       boost::bind( &GazeboRosOpenniKinect::DepthImageDisconnect,this), 
00121       ros::VoidPtr(), &this->camera_queue_);
00122   this->depth_image_pub_ = this->rosnode_->advertise(depth_image_ao);
00123 
00124   ros::AdvertiseOptions depth_image_camera_info_ao = 
00125     ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
00126         this->depth_image_camera_info_topic_name_,1,
00127         boost::bind( &GazeboRosOpenniKinect::DepthInfoConnect,this),
00128         boost::bind( &GazeboRosOpenniKinect::DepthInfoDisconnect,this), 
00129         ros::VoidPtr(), &this->camera_queue_);
00130   this->depth_image_camera_info_pub_ = this->rosnode_->advertise(depth_image_camera_info_ao);
00131 }
00132 
00134 // Increment count
00135 void GazeboRosOpenniKinect::PointCloudConnect()
00136 {
00137   this->point_cloud_connect_count_++;
00138   this->image_connect_count_++;
00139   this->parentSensor->SetActive(true);
00140 }
00142 // Decrement count
00143 void GazeboRosOpenniKinect::PointCloudDisconnect()
00144 {
00145   this->point_cloud_connect_count_--;
00146   this->image_connect_count_--;
00147   if (this->point_cloud_connect_count_ <= 0)
00148     this->parentSensor->SetActive(false);
00149 }
00150 
00152 // Increment count
00153 void GazeboRosOpenniKinect::DepthImageConnect()
00154 {
00155   this->depth_image_connect_count_++;
00156   this->parentSensor->SetActive(true);
00157 }
00159 // Decrement count
00160 void GazeboRosOpenniKinect::DepthImageDisconnect()
00161 {
00162   this->depth_image_connect_count_--;
00163 }
00164 
00166 // Increment count
00167 void GazeboRosOpenniKinect::DepthInfoConnect()
00168 {
00169   this->depth_info_connect_count_++;
00170 }
00172 // Decrement count
00173 void GazeboRosOpenniKinect::DepthInfoDisconnect()
00174 {
00175   this->depth_info_connect_count_--;
00176 }
00177 
00179 // Update the controller
00180 void GazeboRosOpenniKinect::OnNewDepthFrame(const float *_image, 
00181     unsigned int _width, unsigned int _height, unsigned int _depth, 
00182     const std::string &_format)
00183 {
00184   this->depth_sensor_update_time_ = this->parentSensor->GetLastUpdateTime();
00185   if (this->parentSensor->IsActive())
00186   {
00187     if (this->point_cloud_connect_count_ <= 0 &&
00188         this->depth_image_connect_count_ <= 0 &&
00189         this->image_connect_count_ <= 0)
00190     {
00191       this->parentSensor->SetActive(false);
00192     }
00193     else
00194     {
00195       if (this->point_cloud_connect_count_ > 0)
00196         this->FillPointdCloud(_image);
00197 
00198       if (this->depth_image_connect_count_ > 0)
00199         this->FillDepthImage(_image);
00200     }
00201   }
00202   else
00203   {
00204     if (this->point_cloud_connect_count_ > 0 ||
00205         this->depth_image_connect_count_ <= 0)
00206       // do this first so there's chance for sensor to run 1 frame after activate
00207       this->parentSensor->SetActive(true);
00208   }
00209 }
00210 
00212 // Update the controller
00213 void GazeboRosOpenniKinect::OnNewImageFrame(const unsigned char *_image, 
00214     unsigned int _width, unsigned int _height, unsigned int _depth, 
00215     const std::string &_format)
00216 {
00217   //ROS_ERROR("camera_ new frame %s %s",this->parentSensor_->GetName().c_str(),this->frame_name_.c_str());
00218   this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
00219 
00220   if (this->parentSensor->IsActive())
00221   {
00222     if (this->point_cloud_connect_count_ <= 0 &&
00223         this->depth_image_connect_count_ <= 0 &&
00224         this->image_connect_count_ <= 0)
00225     {
00226       this->parentSensor->SetActive(false);
00227     }
00228     else
00229     {
00230       if (this->image_connect_count_ > 0)
00231         this->PutCameraData(_image);
00232     }
00233   }
00234   else
00235   {
00236     if (this->image_connect_count_ > 0)
00237       // do this first so there's chance for sensor to run 1 frame after activate
00238       this->parentSensor->SetActive(true);
00239   }
00240 }
00241 
00243 // Put point cloud data to the interface
00244 void GazeboRosOpenniKinect::FillPointdCloud(const float *_src)
00245 {
00246   this->lock_.lock();
00247 
00248   this->point_cloud_msg_.header.frame_id = this->frame_name_;
00249   this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00250   this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00251   this->point_cloud_msg_.width = this->width;
00252   this->point_cloud_msg_.height = this->height;
00253   this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
00254 
00256   FillPointCloudHelper(this->point_cloud_msg_,
00257                  this->height,
00258                  this->width,
00259                  this->skip_,
00260                  (void*)_src );
00261 
00262   this->point_cloud_pub_.publish(this->point_cloud_msg_);
00263 
00264   this->lock_.unlock();
00265 }
00266 
00268 // Put depth image data to the interface
00269 void GazeboRosOpenniKinect::FillDepthImage(const float *_src)
00270 {
00271   this->lock_.lock();
00272   // copy data into image
00273   this->depth_image_msg_.header.frame_id = this->frame_name_;
00274   this->depth_image_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00275   this->depth_image_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00276 
00278   FillDepthImageHelper(this->depth_image_msg_,
00279                  this->height,
00280                  this->width,
00281                  this->skip_,
00282                  (void*)_src );
00283 
00284   this->depth_image_pub_.publish(this->depth_image_msg_);
00285 
00286   this->lock_.unlock();
00287 }
00288 
00289 
00290 // Fill depth information
00291 bool GazeboRosOpenniKinect::FillPointCloudHelper(
00292     sensor_msgs::PointCloud2 &point_cloud_msg,
00293     uint32_t rows_arg, uint32_t cols_arg,
00294     uint32_t step_arg, void* data_arg)
00295 {
00296   pcl::PointCloud<pcl::PointXYZRGB> point_cloud;
00297 
00298   point_cloud.points.resize(0);
00299   point_cloud.is_dense = true;
00300 
00301   float* toCopyFrom = (float*)data_arg;
00302   int index = 0;
00303 
00304   double hfov = this->parentSensor->GetDepthCamera()->GetHFOV().GetAsRadian();
00305   double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
00306 
00307   // convert depth to point cloud
00308   for (uint32_t j=0; j<rows_arg; j++)
00309   {
00310     double pAngle;
00311     if (rows_arg>1) pAngle = atan2( (double)j - 0.5*(double)(rows_arg-1), fl);
00312     else            pAngle = 0.0;
00313 
00314     for (uint32_t i=0; i<cols_arg; i++)
00315     {
00316       double yAngle;
00317       if (cols_arg>1) yAngle = atan2( (double)i - 0.5*(double)(cols_arg-1), fl);
00318       else            yAngle = 0.0;
00319 
00320       double depth = toCopyFrom[index++]; // + 0.0*this->myParent->GetNearClip();
00321 
00322       // in optical frame
00323       // hardcoded rotation rpy(-M_PI/2, 0, -M_PI/2) is built-in
00324       // to urdf, where the *_optical_frame should have above relative
00325       // rotation from the physical camera *_frame
00326       pcl::PointXYZRGB point;
00327       point.x      = depth * tan(yAngle);
00328       point.y      = depth * tan(pAngle);
00329       if(depth > this->point_cloud_cutoff_)
00330       {
00331         point.z    = depth;
00332       }
00333       else //point in the unseeable range
00334       {
00335         point.x = point.y = point.z = std::numeric_limits<float>::quiet_NaN ();
00336         point_cloud.is_dense = false;
00337       }
00338 
00339       // put image color data for each point
00340       uint8_t*  image_src = (uint8_t*)(&(this->image_msg_.data[0]));
00341       if (this->image_msg_.data.size() == rows_arg*cols_arg*3)
00342       {
00343         // color
00344         point.r = image_src[i*3+j*cols_arg*3+0];
00345         point.g = image_src[i*3+j*cols_arg*3+1];
00346         point.b = image_src[i*3+j*cols_arg*3+2];
00347       }
00348       else if (this->image_msg_.data.size() == rows_arg*cols_arg)
00349       {
00350         // mono
00351         point.r = image_src[i+j*cols_arg];
00352         point.g = image_src[i+j*cols_arg];
00353         point.b = image_src[i+j*cols_arg];
00354       }
00355       else
00356       {
00357         // no image
00358         point.r = 0;
00359         point.g = 0;
00360         point.b = 0;
00361       }
00362 
00363       point_cloud.points.push_back(point);
00364     }
00365   }
00366 
00367   point_cloud.header = point_cloud_msg.header;
00368   pcl::toROSMsg(point_cloud, point_cloud_msg);
00369   return true;
00370 }
00371 
00372 // Fill depth information
00373 bool GazeboRosOpenniKinect::FillDepthImageHelper(
00374     sensor_msgs::Image& image_msg,
00375     uint32_t rows_arg, uint32_t cols_arg,
00376     uint32_t step_arg, void* data_arg)
00377 {
00378   image_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00379   image_msg.height = rows_arg;
00380   image_msg.width = cols_arg;
00381   image_msg.step = 1;
00382   image_msg.data.resize(rows_arg * cols_arg * sizeof(float));
00383   image_msg.is_bigendian = 0;
00384 
00385   const float bad_point = std::numeric_limits<float>::quiet_NaN();
00386 
00387   float* dest = (float*)(&(image_msg.data[0]));
00388   float* toCopyFrom = (float*)data_arg;
00389   int index = 0;
00390 
00391   // convert depth to point cloud
00392   for (uint32_t j = 0; j < rows_arg; j++)
00393   {
00394     for (uint32_t i = 0; i < cols_arg; i++)
00395     {
00396       float depth = 0;
00397       for (uint32_t s = 0; s < step_arg; s++) // if depth > 1 (e.g. rgb), average
00398         depth += toCopyFrom[index++];
00399       depth = depth / (float)step_arg;
00400 
00401       if (depth > this->point_cloud_cutoff_)
00402       {
00403         dest[i + j * cols_arg] = depth;
00404       }
00405       else //point in the unseeable range
00406       {
00407         dest[i + j * cols_arg] = bad_point;
00408       }
00409     }
00410   }
00411   return true;
00412 }
00413 
00414 void GazeboRosOpenniKinect::PublishCameraInfo()
00415 {
00416   ROS_DEBUG("publishing default camera info, then openni kinect camera info");
00417   GazeboRosCameraUtils::PublishCameraInfo();
00418 
00419   if (this->depth_info_connect_count_ > 0)
00420   {
00421     this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
00422     common::Time cur_time = this->world_->GetSimTime();
00423     if (cur_time - this->last_depth_image_camera_info_update_time_ >= this->update_period_)
00424     {
00425       this->PublishCameraInfo(this->depth_image_camera_info_pub_);
00426       this->last_depth_image_camera_info_update_time_ = cur_time;
00427     }
00428   }
00429 }
00430 
00431 //@todo: publish disparity similar to openni_camera_deprecated/src/nodelets/openni_nodelet.cpp.
00432 /*
00433 #include <stereo_msgs/DisparityImage.h>
00434 pub_disparity_ = comm_nh.advertise<stereo_msgs::DisparityImage > ("depth/disparity", 5, subscriberChanged2, subscriberChanged2);
00435 
00436 void GazeboRosDepthCamera::PublishDisparityImage(const DepthImage& depth, ros::Time time)
00437 {
00438   stereo_msgs::DisparityImagePtr disp_msg = boost::make_shared<stereo_msgs::DisparityImage > ();
00439   disp_msg->header.stamp                  = time;
00440   disp_msg->header.frame_id               = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_;
00441   disp_msg->image.header                  = disp_msg->header;
00442   disp_msg->image.encoding                = sensor_msgs::image_encodings::TYPE_32FC1;
00443   disp_msg->image.height                  = depth_height_;
00444   disp_msg->image.width                   = depth_width_;
00445   disp_msg->image.step                    = disp_msg->image.width * sizeof (float);
00446   disp_msg->image.data.resize (disp_msg->image.height * disp_msg->image.step);
00447   disp_msg->T = depth.getBaseline ();
00448   disp_msg->f = depth.getFocalLength () * depth_width_ / depth.getWidth ();
00449 
00451   disp_msg->min_disparity = 0.0;
00452   disp_msg->max_disparity = disp_msg->T * disp_msg->f / 0.3;
00453   disp_msg->delta_d = 0.125;
00454 
00455   depth.fillDisparityImage (depth_width_, depth_height_, reinterpret_cast<float*>(&disp_msg->image.data[0]), disp_msg->image.step);
00456 
00457   pub_disparity_.publish (disp_msg);
00458 }
00459 */
00460 
00461 // Register this plugin with the simulator
00462 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosOpenniKinect)
00463 
00464 }


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Sun Jan 5 2014 11:34:58