25 #include <boost/thread/thread.hpp>
26 #include <boost/bind.hpp>
30 #include <gazebo/sensors/Sensor.hh>
32 #include <gazebo/sensors/SensorTypes.hh>
34 #ifdef ENABLE_PROFILER
35 #include <ignition/common/Profiler.hh>
45 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosDepthCamera)
51 this->point_cloud_connect_count_ = 0;
52 this->normals_connect_count_ = 0;
53 this->depth_image_connect_count_ = 0;
54 this->depth_info_connect_count_ = 0;
55 this->reflectance_connect_count_ = 0;
56 this->last_depth_image_camera_info_update_time_ = common::Time(0);
73 DepthCameraPlugin::Load(_parent, _sdf);
78 ROS_FATAL_STREAM_NAMED(
"depth_camera",
"A ROS node for Gazebo has not been initialized, unable to load plugin. "
79 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
85 this->
width_ = this->width;
87 this->
depth_ = this->depth;
89 this->
camera_ = this->depthCamera;
92 if (!_sdf->HasElement(
"imageTopicName"))
94 if (!_sdf->HasElement(
"cameraInfoTopicName"))
98 if (!_sdf->HasElement(
"pointCloudTopicName"))
104 if (!_sdf->HasElement(
"reflectanceTopicName"))
110 if (!_sdf->HasElement(
"normalsTopicName"))
116 if (!_sdf->HasElement(
"depthImageTopicName"))
121 if (!_sdf->HasElement(
"depthImageCameraInfoTopicName"))
126 if (!_sdf->HasElement(
"pointCloudCutoff"))
131 if (!_sdf->HasElement(
"reduceNormals"))
137 if (!_sdf->HasElement(
"useDepth16UC1Format"))
149 ros::AdvertiseOptions::create<sensor_msgs::PointCloud2 >(
157 ros::AdvertiseOptions::create< sensor_msgs::Image >(
165 ros::AdvertiseOptions::create<sensor_msgs::CameraInfo>(
172 #if GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 12
174 ros::AdvertiseOptions::create<sensor_msgs::Image>(
182 ros::AdvertiseOptions::create<visualization_msgs::MarkerArray >(
197 this->parentSensor->SetActive(
true);
207 this->parentSensor->SetActive(
false);
216 this->parentSensor->SetActive(
true);
225 this->parentSensor->SetActive(
true);
235 this->parentSensor->SetActive(
false);
245 this->parentSensor->SetActive(
false);
253 this->parentSensor->SetActive(
true);
279 unsigned int _width,
unsigned int _height,
unsigned int _depth,
280 const std::string &_format)
282 #ifdef ENABLE_PROFILER
283 IGN_PROFILE(
"GazeboRosDepthCamera::OnNewDepthFrame");
287 #ifdef ENABLE_PROFILER
288 IGN_PROFILE_BEGIN(
"fill ROS message");
290 # if GAZEBO_MAJOR_VERSION >= 7
296 if (this->parentSensor->IsActive())
303 this->parentSensor->SetActive(
false);
322 this->parentSensor->SetActive(
true);
324 #ifdef ENABLE_PROFILER
332 unsigned int _width,
unsigned int _height,
unsigned int _depth,
333 const std::string &_format)
335 #ifdef ENABLE_PROFILER
336 IGN_PROFILE(
"GazeboRosDepthCamera::OnNewRGBPointCloud");
340 #ifdef ENABLE_PROFILER
341 IGN_PROFILE_BEGIN(
"fill ROS message");
343 # if GAZEBO_MAJOR_VERSION >= 7
349 if (!this->parentSensor->IsActive())
353 this->parentSensor->SetActive(
true);
362 pcd_ =
new float[_width * _height * 4];
364 memcpy(
pcd_, _pcd,
sizeof(
float)* _width * _height * 4);
375 pcd_modifier.
resize(_width*_height);
384 for (
unsigned int i = 0; i < _width; i++)
386 for (
unsigned int j = 0; j < _height; j++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
388 unsigned int index = (j * _width) + i;
389 *iter_x = _pcd[4 * index];
390 *iter_y = _pcd[4 * index + 1];
391 *iter_z = _pcd[4 * index + 2];
392 *iter_rgb = _pcd[4 * index + 3];
397 this->
lock_.unlock();
400 #ifdef ENABLE_PROFILER
405 #if GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 12
408 void GazeboRosDepthCamera::OnNewReflectanceFrame(
const float *_image,
409 unsigned int _width,
unsigned int _height,
unsigned int _depth,
410 const std::string &_format)
412 #ifdef ENABLE_PROFILER
413 IGN_PROFILE(
"GazeboRosDepthCamera::OnNewReflectanceFrame");
418 #ifdef ENABLE_PROFILER
419 IGN_PROFILE_BEGIN(
"fill ROS message");
424 boost::mutex::scoped_lock lock(this->
lock_);
433 4*_width,
reinterpret_cast<const void*
>(_image));
438 #ifdef ENABLE_PROFILER
447 unsigned int _width,
unsigned int _height,
unsigned int _depth,
448 const std::string &_format)
450 #ifdef ENABLE_PROFILER
451 IGN_PROFILE(
"GazeboRosDepthCamera::OnNewImageFrame");
455 #ifdef ENABLE_PROFILER
456 IGN_PROFILE_BEGIN(
"fill ROS message");
459 # if GAZEBO_MAJOR_VERSION >= 7
465 if (!this->parentSensor->IsActive())
469 this->parentSensor->SetActive(
true);
480 #ifdef ENABLE_PROFILER
485 #if GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 12
486 void GazeboRosDepthCamera::OnNewNormalsFrame(
const float * _normals,
487 unsigned int _width,
unsigned int _height,
488 unsigned int _depth,
const std::string &_format)
490 #ifdef ENABLE_PROFILER
491 IGN_PROFILE(
"GazeboRosDepthCamera::OnNewNormalsFrame");
495 #ifdef ENABLE_PROFILER
496 IGN_PROFILE_BEGIN(
"fill ROS message");
498 visualization_msgs::MarkerArray m_array;
500 if (!this->parentSensor->IsActive())
504 this->parentSensor->SetActive(
true);
510 boost::mutex::scoped_lock lock(this->
lock_);
513 for (
unsigned int i = 0; i < _width; i++)
515 for (
unsigned int j = 0; j < _height; j++)
518 unsigned int index = (j * _width) + i;
521 visualization_msgs::Marker m;
522 m.type = visualization_msgs::Marker::ARROW;
526 m.action = visualization_msgs::Marker::ADD;
539 float x = _normals[4 * index];
540 float y = _normals[4 * index + 1];
541 float z = _normals[4 * index + 2];
543 m.pose.position.x =
pcd_[4 * index];
544 m.pose.position.y =
pcd_[4 * index + 1];
545 m.pose.position.z =
pcd_[4 * index + 2];
548 tf::Vector3 axis_vector(x, y, z);
550 if (!axis_vector.isZero())
552 tf::Vector3 vector(1.0, 0.0, 0.0);
553 tf::Vector3 right_vector = axis_vector.cross(vector);
554 right_vector.normalized();
555 q.
setRotation(right_vector, -1.0*acos(axis_vector.dot(vector)));
559 m.pose.orientation.x = q.x();
560 m.pose.orientation.y = q.y();
561 m.pose.orientation.z = q.z();
562 m.pose.orientation.w = q.w();
564 m_array.markers.push_back(m);
572 #ifdef ENABLE_PROFILER
600 this->
lock_.unlock();
622 this->
lock_.unlock();
628 sensor_msgs::PointCloud2 &point_cloud_msg,
629 uint32_t rows_arg, uint32_t cols_arg,
630 uint32_t step_arg,
void* data_arg)
634 pcd_modifier.
resize(rows_arg*cols_arg);
641 point_cloud_msg.is_dense =
true;
643 float* toCopyFrom = (
float*)data_arg;
646 double hfov = this->parentSensor->DepthCamera()->HFOV().Radian();
647 double fl = ((double)this->width) / (2.0 *tan(hfov/2.0));
649 if (
pcd_ ==
nullptr){
650 pcd_ =
new float[rows_arg * cols_arg * 4];
654 for (uint32_t j=0; j<rows_arg; j++)
657 if (rows_arg>1) pAngle = atan2( (
double)j - 0.5*(
double)(rows_arg-1), fl);
660 for (uint32_t i=0; i<cols_arg; i++, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb)
663 if (cols_arg>1) yAngle = atan2( (
double)i - 0.5*(
double)(cols_arg-1), fl);
666 double depth = toCopyFrom[index++];
672 unsigned int index = (j * cols_arg) + i;
673 *iter_x = depth * tan(yAngle);
674 *iter_y = depth * tan(pAngle);
678 pcd_[4 * index + 2] = *iter_z;
682 *iter_x = *iter_y = *iter_z = std::numeric_limits<float>::quiet_NaN ();
683 pcd_[4 * index + 2] = 0;
684 point_cloud_msg.is_dense =
false;
687 pcd_[4 * index] = *iter_x;
688 pcd_[4 * index + 1] = *iter_y;
689 pcd_[4 * index + 3] = 0;
692 uint8_t* image_src = (uint8_t*)(&(this->
image_msg_.data[0]));
693 if (this->
image_msg_.data.size() == rows_arg*cols_arg*3)
696 iter_rgb[0] = image_src[i*3+j*cols_arg*3+0];
697 iter_rgb[1] = image_src[i*3+j*cols_arg*3+1];
698 iter_rgb[2] = image_src[i*3+j*cols_arg*3+2];
700 else if (this->
image_msg_.data.size() == rows_arg*cols_arg)
703 iter_rgb[0] = image_src[i+j*cols_arg];
704 iter_rgb[1] = image_src[i+j*cols_arg];
705 iter_rgb[2] = image_src[i+j*cols_arg];
722 sensor_msgs::Image& image_msg,
723 uint32_t rows_arg, uint32_t cols_arg,
724 uint32_t step_arg,
void* data_arg)
726 image_msg.height = rows_arg;
727 image_msg.width = cols_arg;
728 image_msg.is_bigendian = 0;
731 union uint16_or_float
733 uint16_t* dest_uint16;
736 uint16_or_float dest;
740 image_msg.step =
sizeof(float) * cols_arg;
741 image_msg.data.resize(rows_arg * cols_arg *
sizeof(
float));
742 dest.dest_float = (
float*)(&(image_msg.data[0]));
747 image_msg.step =
sizeof(uint16_t) * cols_arg;
748 image_msg.data.resize(rows_arg * cols_arg *
sizeof(uint16_t));
749 dest.dest_uint16 = (uint16_t*)(&(image_msg.data[0]));
752 float* toCopyFrom = (
float*)data_arg;
756 for (uint32_t j = 0; j < rows_arg; j++)
758 for (uint32_t i = 0; i < cols_arg; i++)
760 float depth = toCopyFrom[index++];
765 dest.dest_float[i + j * cols_arg] = depth;
767 dest.dest_uint16[i + j * cols_arg] = depth * 1000.0;
772 dest.dest_float[i + j * cols_arg] = std::numeric_limits<float>::quiet_NaN();
774 dest.dest_uint16[i + j * cols_arg] = 0;
783 ROS_DEBUG_NAMED(
"depth_camera",
"publishing default camera info, then depth camera info");
788 # if GAZEBO_MAJOR_VERSION >= 7
789 common::Time sensor_update_time = this->
parentSensor_->LastMeasurementTime();
791 common::Time sensor_update_time = this->
parentSensor_->GetLastMeasurementTime();