gazebo_ros_openni_kinect.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2013 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 /*
00019    Desc: GazeboRosOpenniKinect plugin for simulating cameras in Gazebo
00020    Author: John Hsu
00021    Date: 24 Sept 2008
00022  */
00023 
00024 #include <algorithm>
00025 #include <assert.h>
00026 #include <boost/thread/thread.hpp>
00027 #include <boost/bind.hpp>
00028 
00029 #include <gazebo_plugins/gazebo_ros_openni_kinect.h>
00030 
00031 #include <gazebo/sensors/Sensor.hh>
00032 #include <sdf/sdf.hh>
00033 #include <gazebo/sensors/SensorTypes.hh>
00034 
00035 // for creating PointCloud2 from pcl point cloud
00036 #include <pcl_conversions/pcl_conversions.h>
00037 
00038 #include <tf/tf.h>
00039 
00040 namespace gazebo
00041 {
00042 // Register this plugin with the simulator
00043 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosOpenniKinect)
00044 
00045 
00046 // Constructor
00047 GazeboRosOpenniKinect::GazeboRosOpenniKinect()
00048 {
00049   this->point_cloud_connect_count_ = 0;
00050   this->depth_info_connect_count_ = 0;
00051   this->depth_image_connect_count_ = 0;
00052   this->last_depth_image_camera_info_update_time_ = common::Time(0);
00053 }
00054 
00056 // Destructor
00057 GazeboRosOpenniKinect::~GazeboRosOpenniKinect()
00058 {
00059 }
00060 
00062 // Load the controller
00063 void GazeboRosOpenniKinect::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00064 {
00065   DepthCameraPlugin::Load(_parent, _sdf);
00066 
00067   // copying from DepthCameraPlugin into GazeboRosCameraUtils
00068   this->parentSensor_ = this->parentSensor;
00069   this->width_ = this->width;
00070   this->height_ = this->height;
00071   this->depth_ = this->depth;
00072   this->format_ = this->format;
00073   this->camera_ = this->depthCamera;
00074 
00075   // using a different default
00076   if (!_sdf->GetElement("imageTopicName"))
00077     this->image_topic_name_ = "ir/image_raw";
00078   if (!_sdf->HasElement("cameraInfoTopicName"))
00079     this->camera_info_topic_name_ = "ir/camera_info";
00080 
00081   // point cloud stuff
00082   if (!_sdf->GetElement("pointCloudTopicName"))
00083     this->point_cloud_topic_name_ = "points";
00084   else
00085     this->point_cloud_topic_name_ = _sdf->GetElement("pointCloudTopicName")->Get<std::string>();
00086 
00087   // depth image stuff
00088   if (!_sdf->GetElement("depthImageTopicName"))
00089     this->depth_image_topic_name_ = "depth/image_raw";
00090   else
00091     this->depth_image_topic_name_ = _sdf->GetElement("depthImageTopicName")->Get<std::string>();
00092 
00093   if (!_sdf->GetElement("depthImageCameraInfoTopicName"))
00094     this->depth_image_camera_info_topic_name_ = "depth/camera_info";
00095   else
00096     this->depth_image_camera_info_topic_name_ = _sdf->GetElement("depthImageCameraInfoTopicName")->Get<std::string>();
00097 
00098   if (!_sdf->GetElement("pointCloudCutoff"))
00099     this->point_cloud_cutoff_ = 0.4;
00100   else
00101     this->point_cloud_cutoff_ = _sdf->GetElement("pointCloudCutoff")->Get<double>();
00102 
00103   load_connection_ = GazeboRosCameraUtils::OnLoad(boost::bind(&GazeboRosOpenniKinect::Advertise, this));
00104   GazeboRosCameraUtils::Load(_parent, _sdf);
00105 }
00106 
00107 void GazeboRosOpenniKinect::Advertise()
00108 {
00109   ros::AdvertiseOptions point_cloud_ao = 
00110     ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
00111       this->point_cloud_topic_name_,1,
00112       boost::bind( &GazeboRosOpenniKinect::PointCloudConnect,this),
00113       boost::bind( &GazeboRosOpenniKinect::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( &GazeboRosOpenniKinect::DepthImageConnect,this),
00121       boost::bind( &GazeboRosOpenniKinect::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( &GazeboRosOpenniKinect::DepthInfoConnect,this),
00129         boost::bind( &GazeboRosOpenniKinect::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 GazeboRosOpenniKinect::PointCloudConnect()
00137 {
00138   this->point_cloud_connect_count_++;
00139   (*this->image_connect_count_)++;
00140   this->parentSensor->SetActive(true);
00141 }
00143 // Decrement count
00144 void GazeboRosOpenniKinect::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 GazeboRosOpenniKinect::DepthImageConnect()
00155 {
00156   this->depth_image_connect_count_++;
00157   this->parentSensor->SetActive(true);
00158 }
00160 // Decrement count
00161 void GazeboRosOpenniKinect::DepthImageDisconnect()
00162 {
00163   this->depth_image_connect_count_--;
00164 }
00165 
00167 // Increment count
00168 void GazeboRosOpenniKinect::DepthInfoConnect()
00169 {
00170   this->depth_info_connect_count_++;
00171 }
00173 // Decrement count
00174 void GazeboRosOpenniKinect::DepthInfoDisconnect()
00175 {
00176   this->depth_info_connect_count_--;
00177 }
00178 
00180 // Update the controller
00181 void GazeboRosOpenniKinect::OnNewDepthFrame(const float *_image, 
00182     unsigned int _width, unsigned int _height, unsigned int _depth, 
00183     const std::string &_format)
00184 {
00185   if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
00186     return;
00187 
00188   this->depth_sensor_update_time_ = this->parentSensor->GetLastUpdateTime();
00189   if (this->parentSensor->IsActive())
00190   {
00191     if (this->point_cloud_connect_count_ <= 0 &&
00192         this->depth_image_connect_count_ <= 0 &&
00193         (*this->image_connect_count_) <= 0)
00194     {
00195       this->parentSensor->SetActive(false);
00196     }
00197     else
00198     {
00199       if (this->point_cloud_connect_count_ > 0)
00200         this->FillPointdCloud(_image);
00201 
00202       if (this->depth_image_connect_count_ > 0)
00203         this->FillDepthImage(_image);
00204     }
00205   }
00206   else
00207   {
00208     if (this->point_cloud_connect_count_ > 0 ||
00209         this->depth_image_connect_count_ <= 0)
00210       // do this first so there's chance for sensor to run 1 frame after activate
00211       this->parentSensor->SetActive(true);
00212   }
00213   PublishCameraInfo();
00214 }
00215 
00217 // Update the controller
00218 void GazeboRosOpenniKinect::OnNewImageFrame(const unsigned char *_image, 
00219     unsigned int _width, unsigned int _height, unsigned int _depth, 
00220     const std::string &_format)
00221 {
00222   if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
00223     return;
00224 
00225   //ROS_ERROR("camera_ new frame %s %s",this->parentSensor_->GetName().c_str(),this->frame_name_.c_str());
00226   this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
00227 
00228   if (this->parentSensor->IsActive())
00229   {
00230     if (this->point_cloud_connect_count_ <= 0 &&
00231         this->depth_image_connect_count_ <= 0 &&
00232         (*this->image_connect_count_) <= 0)
00233     {
00234       this->parentSensor->SetActive(false);
00235     }
00236     else
00237     {
00238       if ((*this->image_connect_count_) > 0)
00239         this->PutCameraData(_image);
00240     }
00241   }
00242   else
00243   {
00244     if ((*this->image_connect_count_) > 0)
00245       // do this first so there's chance for sensor to run 1 frame after activate
00246       this->parentSensor->SetActive(true);
00247   }
00248 }
00249 
00251 // Put point cloud data to the interface
00252 void GazeboRosOpenniKinect::FillPointdCloud(const float *_src)
00253 {
00254   this->lock_.lock();
00255 
00256   this->point_cloud_msg_.header.frame_id = this->frame_name_;
00257   this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00258   this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00259   this->point_cloud_msg_.width = this->width;
00260   this->point_cloud_msg_.height = this->height;
00261   this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
00262 
00264   FillPointCloudHelper(this->point_cloud_msg_,
00265                  this->height,
00266                  this->width,
00267                  this->skip_,
00268                  (void*)_src );
00269 
00270   this->point_cloud_pub_.publish(this->point_cloud_msg_);
00271 
00272   this->lock_.unlock();
00273 }
00274 
00276 // Put depth image data to the interface
00277 void GazeboRosOpenniKinect::FillDepthImage(const float *_src)
00278 {
00279   this->lock_.lock();
00280   // copy data into image
00281   this->depth_image_msg_.header.frame_id = this->frame_name_;
00282   this->depth_image_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00283   this->depth_image_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00284 
00286   FillDepthImageHelper(this->depth_image_msg_,
00287                  this->height,
00288                  this->width,
00289                  this->skip_,
00290                  (void*)_src );
00291 
00292   this->depth_image_pub_.publish(this->depth_image_msg_);
00293 
00294   this->lock_.unlock();
00295 }
00296 
00297 
00298 // Fill depth information
00299 bool GazeboRosOpenniKinect::FillPointCloudHelper(
00300     sensor_msgs::PointCloud2 &point_cloud_msg,
00301     uint32_t rows_arg, uint32_t cols_arg,
00302     uint32_t step_arg, void* data_arg)
00303 {
00304   pcl::PointCloud<pcl::PointXYZRGB> point_cloud;
00305 
00306   point_cloud.points.resize(0);
00307   point_cloud.is_dense = true;
00308 
00309   float* toCopyFrom = (float*)data_arg;
00310   int index = 0;
00311 
00312   double hfov = this->parentSensor->GetDepthCamera()->GetHFOV().Radian();
00313   double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
00314 
00315   // convert depth to point cloud
00316   point_cloud.points.resize(cols_arg * rows_arg);
00317   for (uint32_t j=0; j<rows_arg; j++)
00318   {
00319     double pAngle;
00320     if (rows_arg>1) pAngle = atan2( (double)j - 0.5*(double)(rows_arg-1), fl);
00321     else            pAngle = 0.0;
00322 
00323     for (uint32_t i=0; i<cols_arg; i++)
00324     {
00325       double yAngle;
00326       if (cols_arg>1) yAngle = atan2( (double)i - 0.5*(double)(cols_arg-1), fl);
00327       else            yAngle = 0.0;
00328 
00329       double depth = toCopyFrom[index++]; // + 0.0*this->myParent->GetNearClip();
00330 
00331       // in optical frame
00332       // hardcoded rotation rpy(-M_PI/2, 0, -M_PI/2) is built-in
00333       // to urdf, where the *_optical_frame should have above relative
00334       // rotation from the physical camera *_frame
00335       pcl::PointXYZRGB point;
00336       point.x      = depth * tan(yAngle);
00337       point.y      = depth * tan(pAngle);
00338       if(depth > this->point_cloud_cutoff_)
00339       {
00340         point.z    = depth;
00341       }
00342       else //point in the unseeable range
00343       {
00344         point.x = point.y = point.z = std::numeric_limits<float>::quiet_NaN ();
00345         point_cloud.is_dense = false;
00346       }
00347 
00348       // put image color data for each point
00349       uint8_t*  image_src = (uint8_t*)(&(this->image_msg_.data[0]));
00350       if (this->image_msg_.data.size() == rows_arg*cols_arg*3)
00351       {
00352         // color
00353         point.r = image_src[i*3+j*cols_arg*3+0];
00354         point.g = image_src[i*3+j*cols_arg*3+1];
00355         point.b = image_src[i*3+j*cols_arg*3+2];
00356       }
00357       else if (this->image_msg_.data.size() == rows_arg*cols_arg)
00358       {
00359         // mono (or bayer?  @todo; fix for bayer)
00360         point.r = image_src[i+j*cols_arg];
00361         point.g = image_src[i+j*cols_arg];
00362         point.b = image_src[i+j*cols_arg];
00363       }
00364       else
00365       {
00366         // no image
00367         point.r = 0;
00368         point.g = 0;
00369         point.b = 0;
00370       }
00371 
00372       point_cloud.points[i + j * cols_arg] = point;
00373     }
00374   }
00375 
00376   point_cloud.header = pcl_conversions::toPCL(point_cloud_msg.header);
00377   point_cloud.width = cols_arg;
00378   point_cloud.height = rows_arg;
00379   pcl::toROSMsg(point_cloud, point_cloud_msg);
00380   return true;
00381 }
00382 
00383 // Fill depth information
00384 bool GazeboRosOpenniKinect::FillDepthImageHelper(
00385     sensor_msgs::Image& image_msg,
00386     uint32_t rows_arg, uint32_t cols_arg,
00387     uint32_t step_arg, void* data_arg)
00388 {
00389   image_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00390   image_msg.height = rows_arg;
00391   image_msg.width = cols_arg;
00392   image_msg.step = sizeof(float) * cols_arg;
00393   image_msg.data.resize(rows_arg * cols_arg * sizeof(float));
00394   image_msg.is_bigendian = 0;
00395 
00396   const float bad_point = std::numeric_limits<float>::quiet_NaN();
00397 
00398   float* dest = (float*)(&(image_msg.data[0]));
00399   float* toCopyFrom = (float*)data_arg;
00400   int index = 0;
00401 
00402   // convert depth to point cloud
00403   for (uint32_t j = 0; j < rows_arg; j++)
00404   {
00405     for (uint32_t i = 0; i < cols_arg; i++)
00406     {
00407       float depth = toCopyFrom[index++];
00408 
00409       if (depth > this->point_cloud_cutoff_)
00410       {
00411         dest[i + j * cols_arg] = depth;
00412       }
00413       else //point in the unseeable range
00414       {
00415         dest[i + j * cols_arg] = bad_point;
00416       }
00417     }
00418   }
00419   return true;
00420 }
00421 
00422 void GazeboRosOpenniKinect::PublishCameraInfo()
00423 {
00424   ROS_DEBUG("publishing default camera info, then openni kinect camera info");
00425   GazeboRosCameraUtils::PublishCameraInfo();
00426 
00427   if (this->depth_info_connect_count_ > 0)
00428   {
00429     this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
00430     common::Time cur_time = this->world_->GetSimTime();
00431     if (cur_time - this->last_depth_image_camera_info_update_time_ >= this->update_period_)
00432     {
00433       this->PublishCameraInfo(this->depth_image_camera_info_pub_);
00434       this->last_depth_image_camera_info_update_time_ = cur_time;
00435     }
00436   }
00437 }
00438 
00439 //@todo: publish disparity similar to openni_camera_deprecated/src/nodelets/openni_nodelet.cpp.
00440 /*
00441 #include <stereo_msgs/DisparityImage.h>
00442 pub_disparity_ = comm_nh.advertise<stereo_msgs::DisparityImage > ("depth/disparity", 5, subscriberChanged2, subscriberChanged2);
00443 
00444 void GazeboRosDepthCamera::PublishDisparityImage(const DepthImage& depth, ros::Time time)
00445 {
00446   stereo_msgs::DisparityImagePtr disp_msg = boost::make_shared<stereo_msgs::DisparityImage > ();
00447   disp_msg->header.stamp                  = time;
00448   disp_msg->header.frame_id               = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_;
00449   disp_msg->image.header                  = disp_msg->header;
00450   disp_msg->image.encoding                = sensor_msgs::image_encodings::TYPE_32FC1;
00451   disp_msg->image.height                  = depth_height_;
00452   disp_msg->image.width                   = depth_width_;
00453   disp_msg->image.step                    = disp_msg->image.width * sizeof (float);
00454   disp_msg->image.data.resize (disp_msg->image.height * disp_msg->image.step);
00455   disp_msg->T = depth.getBaseline ();
00456   disp_msg->f = depth.getFocalLength () * depth_width_ / depth.getWidth ();
00457 
00459   disp_msg->min_disparity = 0.0;
00460   disp_msg->max_disparity = disp_msg->T * disp_msg->f / 0.3;
00461   disp_msg->delta_d = 0.125;
00462 
00463   depth.fillDisparityImage (depth_width_, depth_height_, reinterpret_cast<float*>(&disp_msg->image.data[0]), disp_msg->image.step);
00464 
00465   pub_disparity_.publish (disp_msg);
00466 }
00467 */
00468 
00469 }


gazebo_plugins
Author(s): John Hsu
autogenerated on Fri Aug 28 2015 10:47:25