00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
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
00036 #include <pcl_conversions/pcl_conversions.h>
00037
00038 #include <tf/tf.h>
00039
00040 namespace gazebo
00041 {
00042
00043 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosOpenniKinect)
00044
00045
00046
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
00057 GazeboRosOpenniKinect::~GazeboRosOpenniKinect()
00058 {
00059 }
00060
00062
00063 void GazeboRosOpenniKinect::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00064 {
00065 DepthCameraPlugin::Load(_parent, _sdf);
00066
00067
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
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
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
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
00136 void GazeboRosOpenniKinect::PointCloudConnect()
00137 {
00138 this->point_cloud_connect_count_++;
00139 (*this->image_connect_count_)++;
00140 this->parentSensor->SetActive(true);
00141 }
00143
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
00154 void GazeboRosOpenniKinect::DepthImageConnect()
00155 {
00156 this->depth_image_connect_count_++;
00157 this->parentSensor->SetActive(true);
00158 }
00160
00161 void GazeboRosOpenniKinect::DepthImageDisconnect()
00162 {
00163 this->depth_image_connect_count_--;
00164 }
00165
00167
00168 void GazeboRosOpenniKinect::DepthInfoConnect()
00169 {
00170 this->depth_info_connect_count_++;
00171 }
00173
00174 void GazeboRosOpenniKinect::DepthInfoDisconnect()
00175 {
00176 this->depth_info_connect_count_--;
00177 }
00178
00180
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
00211 this->parentSensor->SetActive(true);
00212 }
00213 PublishCameraInfo();
00214 }
00215
00217
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
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
00246 this->parentSensor->SetActive(true);
00247 }
00248 }
00249
00251
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
00277 void GazeboRosOpenniKinect::FillDepthImage(const float *_src)
00278 {
00279 this->lock_.lock();
00280
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
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
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++];
00330
00331
00332
00333
00334
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
00343 {
00344 point.x = point.y = point.z = std::numeric_limits<float>::quiet_NaN ();
00345 point_cloud.is_dense = false;
00346 }
00347
00348
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
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
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
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
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
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
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
00440
00441
00442
00443
00444
00445
00446
00447
00448
00449
00450
00451
00452
00453
00454
00455
00456
00457
00459
00460
00461
00462
00463
00464
00465
00466
00467
00468
00469 }