00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #include <algorithm>
00024 #include <assert.h>
00025 #include <boost/thread/thread.hpp>
00026 #include <boost/bind.hpp>
00027
00028 #include <gazebo_plugins/gazebo_ros_depth_camera.h>
00029
00030 #include <gazebo/sensors/Sensor.hh>
00031 #include <sdf/sdf.hh>
00032 #include <gazebo/sensors/SensorTypes.hh>
00033
00034 #include <pcl_conversions/pcl_conversions.h>
00035
00036 #include <tf/tf.h>
00037
00038 namespace gazebo
00039 {
00040
00041 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosDepthCamera)
00042
00043
00044
00045 GazeboRosDepthCamera::GazeboRosDepthCamera()
00046 {
00047 this->point_cloud_connect_count_ = 0;
00048 this->depth_info_connect_count_ = 0;
00049 this->last_depth_image_camera_info_update_time_ = common::Time(0);
00050 }
00051
00053
00054 GazeboRosDepthCamera::~GazeboRosDepthCamera()
00055 {
00056 }
00057
00059
00060 void GazeboRosDepthCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00061 {
00062 DepthCameraPlugin::Load(_parent, _sdf);
00063
00064
00065 if (!ros::isInitialized())
00066 {
00067 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00068 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00069 return;
00070 }
00071
00072
00073 this->parentSensor_ = this->parentSensor;
00074 this->width_ = this->width;
00075 this->height_ = this->height;
00076 this->depth_ = this->depth;
00077 this->format_ = this->format;
00078 this->camera_ = this->depthCamera;
00079
00080
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
00087 if (!_sdf->GetElement("pointCloudTopicName"))
00088 this->point_cloud_topic_name_ = "points";
00089 else
00090 this->point_cloud_topic_name_ = _sdf->GetElement("pointCloudTopicName")->Get<std::string>();
00091
00092
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")->Get<std::string>();
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")->Get<std::string>();
00102
00103 if (!_sdf->GetElement("pointCloudCutoff"))
00104 this->point_cloud_cutoff_ = 0.4;
00105 else
00106 this->point_cloud_cutoff_ = _sdf->GetElement("pointCloudCutoff")->Get<double>();
00107
00108 load_connection_ = GazeboRosCameraUtils::OnLoad(boost::bind(&GazeboRosDepthCamera::Advertise, this));
00109 GazeboRosCameraUtils::Load(_parent, _sdf);
00110 }
00111
00112 void GazeboRosDepthCamera::Advertise()
00113 {
00114 ros::AdvertiseOptions point_cloud_ao =
00115 ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
00116 this->point_cloud_topic_name_,1,
00117 boost::bind( &GazeboRosDepthCamera::PointCloudConnect,this),
00118 boost::bind( &GazeboRosDepthCamera::PointCloudDisconnect,this),
00119 ros::VoidPtr(), &this->camera_queue_);
00120 this->point_cloud_pub_ = this->rosnode_->advertise(point_cloud_ao);
00121
00122 ros::AdvertiseOptions depth_image_ao =
00123 ros::AdvertiseOptions::create< sensor_msgs::Image >(
00124 this->depth_image_topic_name_,1,
00125 boost::bind( &GazeboRosDepthCamera::DepthImageConnect,this),
00126 boost::bind( &GazeboRosDepthCamera::DepthImageDisconnect,this),
00127 ros::VoidPtr(), &this->camera_queue_);
00128 this->depth_image_pub_ = this->rosnode_->advertise(depth_image_ao);
00129
00130 ros::AdvertiseOptions depth_image_camera_info_ao =
00131 ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
00132 this->depth_image_camera_info_topic_name_,1,
00133 boost::bind( &GazeboRosDepthCamera::DepthInfoConnect,this),
00134 boost::bind( &GazeboRosDepthCamera::DepthInfoDisconnect,this),
00135 ros::VoidPtr(), &this->camera_queue_);
00136 this->depth_image_camera_info_pub_ = this->rosnode_->advertise(depth_image_camera_info_ao);
00137 }
00138
00139
00141
00142 void GazeboRosDepthCamera::PointCloudConnect()
00143 {
00144 this->point_cloud_connect_count_++;
00145 (*this->image_connect_count_)++;
00146 this->parentSensor->SetActive(true);
00147 }
00149
00150 void GazeboRosDepthCamera::PointCloudDisconnect()
00151 {
00152 this->point_cloud_connect_count_--;
00153 (*this->image_connect_count_)--;
00154 if (this->point_cloud_connect_count_ <= 0)
00155 this->parentSensor->SetActive(false);
00156 }
00157
00159
00160 void GazeboRosDepthCamera::DepthImageConnect()
00161 {
00162 this->depth_image_connect_count_++;
00163 this->parentSensor->SetActive(true);
00164 }
00166
00167 void GazeboRosDepthCamera::DepthImageDisconnect()
00168 {
00169 this->depth_image_connect_count_--;
00170 }
00171
00173
00174 void GazeboRosDepthCamera::DepthInfoConnect()
00175 {
00176 this->depth_info_connect_count_++;
00177 }
00179
00180 void GazeboRosDepthCamera::DepthInfoDisconnect()
00181 {
00182 this->depth_info_connect_count_--;
00183 }
00184
00186
00187 void GazeboRosDepthCamera::OnNewDepthFrame(const float *_image,
00188 unsigned int _width, unsigned int _height, unsigned int _depth,
00189 const std::string &_format)
00190 {
00191 if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
00192 return;
00193
00194 this->depth_sensor_update_time_ = this->parentSensor->GetLastUpdateTime();
00195 if (this->parentSensor->IsActive())
00196 {
00197 if (this->point_cloud_connect_count_ <= 0 &&
00198 this->depth_image_connect_count_ <= 0 &&
00199 (*this->image_connect_count_) <= 0)
00200 {
00201 this->parentSensor->SetActive(false);
00202 }
00203 else
00204 {
00205 if (this->point_cloud_connect_count_ > 0)
00206 this->FillPointdCloud(_image);
00207
00208 if (this->depth_image_connect_count_ > 0)
00209 this->FillDepthImage(_image);
00210 }
00211 }
00212 else
00213 {
00214 if (this->point_cloud_connect_count_ > 0 ||
00215 this->depth_image_connect_count_ <= 0)
00216
00217 this->parentSensor->SetActive(true);
00218 }
00219 }
00220
00222
00223 void GazeboRosDepthCamera::OnNewRGBPointCloud(const float *_pcd,
00224 unsigned int _width, unsigned int _height, unsigned int _depth,
00225 const std::string &_format)
00226 {
00227 if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
00228 return;
00229
00230 this->depth_sensor_update_time_ = this->parentSensor->GetLastUpdateTime();
00231 if (!this->parentSensor->IsActive())
00232 {
00233 if (this->point_cloud_connect_count_ > 0)
00234
00235 this->parentSensor->SetActive(true);
00236 }
00237 else
00238 {
00239 if (this->point_cloud_connect_count_ > 0)
00240 {
00241 this->lock_.lock();
00242 this->point_cloud_msg_.header.frame_id = this->frame_name_;
00243 this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00244 this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00245 this->point_cloud_msg_.width = this->width;
00246 this->point_cloud_msg_.height = this->height;
00247 this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
00248
00249 pcl::PointCloud<pcl::PointXYZRGB> point_cloud;
00250 point_cloud.points.resize(0);
00251 point_cloud.is_dense = true;
00252
00253 for (unsigned int i = 0; i < _width; i++)
00254 {
00255 for (unsigned int j = 0; j < _height; j++)
00256 {
00257 unsigned int index = (j * _width) + i;
00258 pcl::PointXYZRGB point;
00259 point.x = _pcd[4 * index];
00260 point.y = _pcd[4 * index + 1];
00261 point.z = _pcd[4 * index + 2];
00262 point.rgb = _pcd[4 * index + 3];
00263 point_cloud.points.push_back(point);
00264 if (i == _width /2 && j == _height / 2)
00265 {
00266 uint32_t rgb = *reinterpret_cast<int*>(&point.rgb);
00267 uint8_t r = (rgb >> 16) & 0x0000ff;
00268 uint8_t g = (rgb >> 8) & 0x0000ff;
00269 uint8_t b = (rgb) & 0x0000ff;
00270 std::cerr << (int)r << " " << (int)g << " " << (int)b << "\n";
00271 }
00272 }
00273 }
00274
00275 point_cloud.header = pcl_conversions::toPCL(point_cloud_msg_.header);
00276
00277 pcl::toROSMsg(point_cloud, this->point_cloud_msg_);
00278
00279 this->point_cloud_pub_.publish(this->point_cloud_msg_);
00280 this->lock_.unlock();
00281 }
00282 }
00283 }
00284
00286
00287 void GazeboRosDepthCamera::OnNewImageFrame(const unsigned char *_image,
00288 unsigned int _width, unsigned int _height, unsigned int _depth,
00289 const std::string &_format)
00290 {
00291 if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
00292 return;
00293
00294
00295 this->sensor_update_time_ = this->parentSensor->GetLastUpdateTime();
00296
00297 if (!this->parentSensor->IsActive())
00298 {
00299 if ((*this->image_connect_count_) > 0)
00300
00301 this->parentSensor->SetActive(true);
00302 }
00303 else
00304 {
00305 if ((*this->image_connect_count_) > 0)
00306 this->PutCameraData(_image);
00307 }
00308 }
00309
00311
00312 void GazeboRosDepthCamera::FillPointdCloud(const float *_src)
00313 {
00314 this->lock_.lock();
00315
00316 this->point_cloud_msg_.header.frame_id = this->frame_name_;
00317 this->point_cloud_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00318 this->point_cloud_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00319 this->point_cloud_msg_.width = this->width;
00320 this->point_cloud_msg_.height = this->height;
00321 this->point_cloud_msg_.row_step = this->point_cloud_msg_.point_step * this->width;
00322
00324 FillPointCloudHelper(this->point_cloud_msg_,
00325 this->height,
00326 this->width,
00327 this->skip_,
00328 (void*)_src );
00329
00330 this->point_cloud_pub_.publish(this->point_cloud_msg_);
00331
00332 this->lock_.unlock();
00333 }
00334
00336
00337 void GazeboRosDepthCamera::FillDepthImage(const float *_src)
00338 {
00339 this->lock_.lock();
00340
00341 this->depth_image_msg_.header.frame_id = this->frame_name_;
00342 this->depth_image_msg_.header.stamp.sec = this->depth_sensor_update_time_.sec;
00343 this->depth_image_msg_.header.stamp.nsec = this->depth_sensor_update_time_.nsec;
00344
00346 FillDepthImageHelper(this->depth_image_msg_,
00347 this->height,
00348 this->width,
00349 this->skip_,
00350 (void*)_src );
00351
00352 this->depth_image_pub_.publish(this->depth_image_msg_);
00353
00354 this->lock_.unlock();
00355 }
00356
00357
00358
00359 bool GazeboRosDepthCamera::FillPointCloudHelper(
00360 sensor_msgs::PointCloud2 &point_cloud_msg,
00361 uint32_t rows_arg, uint32_t cols_arg,
00362 uint32_t step_arg, void* data_arg)
00363 {
00364 pcl::PointCloud<pcl::PointXYZRGB> point_cloud;
00365
00366 point_cloud.points.resize(0);
00367 point_cloud.is_dense = true;
00368
00369 float* toCopyFrom = (float*)data_arg;
00370 int index = 0;
00371
00372 double hfov = this->parentSensor->GetDepthCamera()->GetHFOV().Radian();
00373 double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
00374
00375
00376 for (uint32_t j=0; j<rows_arg; j++)
00377 {
00378 double pAngle;
00379 if (rows_arg>1) pAngle = atan2( (double)j - 0.5*(double)(rows_arg-1), fl);
00380 else pAngle = 0.0;
00381
00382 for (uint32_t i=0; i<cols_arg; i++)
00383 {
00384 double yAngle;
00385 if (cols_arg>1) yAngle = atan2( (double)i - 0.5*(double)(cols_arg-1), fl);
00386 else yAngle = 0.0;
00387
00388 double depth = toCopyFrom[index++];
00389
00390
00391
00392
00393
00394 pcl::PointXYZRGB point;
00395 point.x = depth * tan(yAngle);
00396 point.y = depth * tan(pAngle);
00397 if(depth > this->point_cloud_cutoff_)
00398 {
00399 point.z = depth;
00400 }
00401 else
00402 {
00403 point.x = point.y = point.z = std::numeric_limits<float>::quiet_NaN ();
00404 point_cloud.is_dense = false;
00405 }
00406
00407
00408 uint8_t* image_src = (uint8_t*)(&(this->image_msg_.data[0]));
00409 if (this->image_msg_.data.size() == rows_arg*cols_arg*3)
00410 {
00411
00412 point.r = image_src[i*3+j*cols_arg*3+0];
00413 point.g = image_src[i*3+j*cols_arg*3+1];
00414 point.b = image_src[i*3+j*cols_arg*3+2];
00415 }
00416 else if (this->image_msg_.data.size() == rows_arg*cols_arg)
00417 {
00418
00419 point.r = image_src[i+j*cols_arg];
00420 point.g = image_src[i+j*cols_arg];
00421 point.b = image_src[i+j*cols_arg];
00422 }
00423 else
00424 {
00425
00426 point.r = 0;
00427 point.g = 0;
00428 point.b = 0;
00429 }
00430
00431 point_cloud.points.push_back(point);
00432 }
00433 }
00434
00435 point_cloud.header = pcl_conversions::toPCL(point_cloud_msg.header);
00436
00437 pcl::toROSMsg(point_cloud, point_cloud_msg);
00438 return true;
00439 }
00440
00441
00442 bool GazeboRosDepthCamera::FillDepthImageHelper(
00443 sensor_msgs::Image& image_msg,
00444 uint32_t rows_arg, uint32_t cols_arg,
00445 uint32_t step_arg, void* data_arg)
00446 {
00447 image_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00448 image_msg.height = rows_arg;
00449 image_msg.width = cols_arg;
00450 image_msg.step = sizeof(float) * cols_arg;
00451 image_msg.data.resize(rows_arg * cols_arg * sizeof(float));
00452 image_msg.is_bigendian = 0;
00453
00454 const float bad_point = std::numeric_limits<float>::quiet_NaN();
00455
00456 float* dest = (float*)(&(image_msg.data[0]));
00457 float* toCopyFrom = (float*)data_arg;
00458 int index = 0;
00459
00460
00461 for (uint32_t j = 0; j < rows_arg; j++)
00462 {
00463 for (uint32_t i = 0; i < cols_arg; i++)
00464 {
00465 float depth = toCopyFrom[index++];
00466
00467 if (depth > this->point_cloud_cutoff_)
00468 {
00469 dest[i + j * cols_arg] = depth;
00470 }
00471 else
00472 {
00473 dest[i + j * cols_arg] = bad_point;
00474 }
00475 }
00476 }
00477 return true;
00478 }
00479
00480 void GazeboRosDepthCamera::PublishCameraInfo()
00481 {
00482 ROS_DEBUG("publishing default camera info, then depth camera info");
00483 GazeboRosCameraUtils::PublishCameraInfo();
00484
00485 if (this->depth_info_connect_count_ > 0)
00486 {
00487 this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
00488 common::Time cur_time = this->world_->GetSimTime();
00489 if (cur_time - this->last_depth_image_camera_info_update_time_ >= this->update_period_)
00490 {
00491 this->PublishCameraInfo(this->depth_image_camera_info_pub_);
00492 this->last_depth_image_camera_info_update_time_ = cur_time;
00493 }
00494 }
00495 }
00496
00497
00498
00499
00500
00501
00502
00503
00504
00505
00506
00507
00508
00509
00510
00511
00512
00513
00514
00515
00517
00518
00519
00520
00521
00522
00523
00524
00525
00526
00527
00528 }