26 #include <boost/thread/thread.hpp>
27 #include <boost/bind.hpp>
31 #include <gazebo/sensors/Sensor.hh>
33 #include <gazebo/sensors/SensorTypes.hh>
35 #ifdef ENABLE_PROFILER
36 #include <ignition/common/Profiler.hh>
46 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosOpenniKinect)
52 this->point_cloud_connect_count_ = 0;
53 this->depth_info_connect_count_ = 0;
54 this->depth_image_connect_count_ = 0;
55 this->last_depth_image_camera_info_update_time_ = common::Time(0);
68 DepthCameraPlugin::Load(_parent, _sdf);
72 this->
width_ = this->width;
74 this->
depth_ = this->depth;
76 this->
camera_ = this->depthCamera;
79 if (!_sdf->HasElement(
"imageTopicName"))
81 if (!_sdf->HasElement(
"cameraInfoTopicName"))
85 if (!_sdf->HasElement(
"pointCloudTopicName"))
91 if (!_sdf->HasElement(
"depthImageTopicName"))
96 if (!_sdf->HasElement(
"depthImageCameraInfoTopicName"))
101 if (!_sdf->HasElement(
"pointCloudCutoff"))
105 if (!_sdf->HasElement(
"pointCloudCutoffMax"))
111 if (!_sdf->HasElement(
"useDepth16UC1Format"))
123 ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
131 ros::AdvertiseOptions::create< sensor_msgs::Image >(
139 ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
153 this->parentSensor->SetActive(
true);
162 this->parentSensor->SetActive(
false);
170 this->parentSensor->SetActive(
true);
195 unsigned int _width,
unsigned int _height,
unsigned int _depth,
196 const std::string &_format)
198 #ifdef ENABLE_PROFILER
199 IGN_PROFILE(
"GazeboRosOpenniKinect::OnNewDepthFrame");
203 #ifdef ENABLE_PROFILER
204 IGN_PROFILE_BEGIN(
"fill ROS message");
207 if (this->parentSensor->IsActive())
213 this->parentSensor->SetActive(
false);
229 this->parentSensor->SetActive(
true);
231 #ifdef ENABLE_PROFILER
233 IGN_PROFILE_BEGIN(
"PublishCameraInfo");
236 #ifdef ENABLE_PROFILER
244 unsigned int _width,
unsigned int _height,
unsigned int _depth,
245 const std::string &_format)
253 if (this->parentSensor->IsActive())
259 this->parentSensor->SetActive(
false);
271 this->parentSensor->SetActive(
true);
297 this->
lock_.unlock();
319 this->
lock_.unlock();
325 sensor_msgs::PointCloud2 &point_cloud_msg,
326 uint32_t rows_arg, uint32_t cols_arg,
327 uint32_t step_arg,
void* data_arg)
332 pcd_modifier.
resize(rows_arg*cols_arg);
333 point_cloud_msg.is_dense =
true;
340 float* toCopyFrom = (
float*)data_arg;
343 double hfov = this->parentSensor->DepthCamera()->HFOV().Radian();
344 double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
347 for (uint32_t j=0; j<rows_arg; j++)
350 if (rows_arg>1) pAngle = atan2( (
double)j - 0.5*(
double)(rows_arg-1), fl);
353 for (uint32_t i=0; i<cols_arg; i++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
356 if (cols_arg>1) yAngle = atan2( (
double)i - 0.5*(
double)(cols_arg-1), fl);
359 double depth = toCopyFrom[index++];
368 *iter_x = depth * tan(yAngle);
369 *iter_y = depth * tan(pAngle);
374 *iter_x = *iter_y = *iter_z = std::numeric_limits<float>::quiet_NaN ();
375 point_cloud_msg.is_dense =
false;
379 uint8_t* image_src = (uint8_t*)(&(this->
image_msg_.data[0]));
380 if (this->
image_msg_.data.size() == rows_arg*cols_arg*3)
383 iter_rgb[0] = image_src[i*3+j*cols_arg*3+0];
384 iter_rgb[1] = image_src[i*3+j*cols_arg*3+1];
385 iter_rgb[2] = image_src[i*3+j*cols_arg*3+2];
387 else if (this->
image_msg_.data.size() == rows_arg*cols_arg)
390 iter_rgb[0] = image_src[i+j*cols_arg];
391 iter_rgb[1] = image_src[i+j*cols_arg];
392 iter_rgb[2] = image_src[i+j*cols_arg];
405 point_cloud_msg.height = rows_arg;
406 point_cloud_msg.width = cols_arg;
407 point_cloud_msg.row_step = point_cloud_msg.point_step * point_cloud_msg.width;
414 sensor_msgs::Image& image_msg,
415 uint32_t rows_arg, uint32_t cols_arg,
416 uint32_t step_arg,
void* data_arg)
418 image_msg.height = rows_arg;
419 image_msg.width = cols_arg;
420 image_msg.is_bigendian = 0;
423 union uint16_or_float
425 uint16_t* dest_uint16;
428 uint16_or_float dest;
432 image_msg.step =
sizeof(float) * cols_arg;
433 image_msg.data.resize(rows_arg * cols_arg *
sizeof(
float));
434 dest.dest_float = (
float*)(&(image_msg.data[0]));
439 image_msg.step =
sizeof(uint16_t) * cols_arg;
440 image_msg.data.resize(rows_arg * cols_arg *
sizeof(uint16_t));
441 dest.dest_uint16 = (uint16_t*)(&(image_msg.data[0]));
444 float* toCopyFrom = (
float*)data_arg;
448 for (uint32_t j = 0; j < rows_arg; j++)
450 for (uint32_t i = 0; i < cols_arg; i++)
452 float depth = toCopyFrom[index++];
458 dest.dest_float[i + j * cols_arg] = depth;
460 dest.dest_uint16[i + j * cols_arg] = depth * 1000.0;
465 dest.dest_float[i + j * cols_arg] = std::numeric_limits<float>::quiet_NaN();
467 dest.dest_uint16[i + j * cols_arg] = 0;
476 ROS_DEBUG_NAMED(
"openni_kinect",
"publishing default camera info, then openni kinect camera info");
482 #if GAZEBO_MAJOR_VERSION >= 8
483 common::Time cur_time = this->
world_->SimTime();
485 common::Time cur_time = this->
world_->GetSimTime();