Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <pcl_ros/point_cloud.h>
00005 #include <pcl/point_types.h>
00006 #include <sensor_msgs/image_encodings.h>
00007 #include <image_geometry/pinhole_camera_model.h>
00008 #include <boost/thread.hpp>
00009 #include "depth_traits.h"
00010
00011 namespace depth_image_proc {
00012
00013 namespace enc = sensor_msgs::image_encodings;
00014
00015 class PointCloudXyzNodelet : public nodelet::Nodelet
00016 {
00017
00018 boost::shared_ptr<image_transport::ImageTransport> it_;
00019 image_transport::CameraSubscriber sub_depth_;
00020 int queue_size_;
00021
00022
00023 boost::mutex connect_mutex_;
00024 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00025 ros::Publisher pub_point_cloud_;
00026
00027 image_geometry::PinholeCameraModel model_;
00028
00029 virtual void onInit();
00030
00031 void connectCb();
00032
00033 void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00034 const sensor_msgs::CameraInfoConstPtr& info_msg);
00035
00036
00037 template<typename T>
00038 void convert(const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg);
00039 };
00040
00041 void PointCloudXyzNodelet::onInit()
00042 {
00043 ros::NodeHandle& nh = getNodeHandle();
00044 ros::NodeHandle& private_nh = getPrivateNodeHandle();
00045 it_.reset(new image_transport::ImageTransport(nh));
00046
00047
00048 private_nh.param("queue_size", queue_size_, 5);
00049
00050
00051 ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyzNodelet::connectCb, this);
00052
00053 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00054 pub_point_cloud_ = nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
00055 }
00056
00057
00058 void PointCloudXyzNodelet::connectCb()
00059 {
00060 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00061 if (pub_point_cloud_.getNumSubscribers() == 0)
00062 {
00063 sub_depth_.shutdown();
00064 }
00065 else if (!sub_depth_)
00066 {
00067 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00068 sub_depth_ = it_->subscribeCamera("image_rect", queue_size_, &PointCloudXyzNodelet::depthCb, this, hints);
00069 }
00070 }
00071
00072 void PointCloudXyzNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00073 const sensor_msgs::CameraInfoConstPtr& info_msg)
00074 {
00075 PointCloud::Ptr cloud_msg(new PointCloud);
00076 cloud_msg->header = depth_msg->header;
00077 cloud_msg->height = depth_msg->height;
00078 cloud_msg->width = depth_msg->width;
00079 cloud_msg->is_dense = false;
00080 cloud_msg->points.resize(cloud_msg->height * cloud_msg->width);
00081
00082
00083 model_.fromCameraInfo(info_msg);
00084
00085 if (depth_msg->encoding == enc::TYPE_16UC1)
00086 {
00087 convert<uint16_t>(depth_msg, cloud_msg);
00088 }
00089 else if (depth_msg->encoding == enc::TYPE_32FC1)
00090 {
00091 convert<float>(depth_msg, cloud_msg);
00092 }
00093 else
00094 {
00095 NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
00096 return;
00097 }
00098
00099 pub_point_cloud_.publish (cloud_msg);
00100 }
00101
00102 template<typename T>
00103 void PointCloudXyzNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg)
00104 {
00105
00106 float center_x = model_.cx();
00107 float center_y = model_.cy();
00108
00109
00110 double unit_scaling = DepthTraits<T>::toMeters( T(1) );
00111 float constant_x = unit_scaling / model_.fx();
00112 float constant_y = unit_scaling / model_.fy();
00113 float bad_point = std::numeric_limits<float>::quiet_NaN();
00114
00115 PointCloud::iterator pt_iter = cloud_msg->begin();
00116 const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
00117 int row_step = depth_msg->step / sizeof(T);
00118 for (int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
00119 {
00120 for (int u = 0; u < (int)cloud_msg->width; ++u)
00121 {
00122 pcl::PointXYZ& pt = *pt_iter++;
00123 T depth = depth_row[u];
00124
00125
00126 if (!DepthTraits<T>::valid(depth))
00127 {
00128 pt.x = pt.y = pt.z = bad_point;
00129 continue;
00130 }
00131
00132
00133 pt.x = (u - center_x) * depth * constant_x;
00134 pt.y = (v - center_y) * depth * constant_y;
00135 pt.z = DepthTraits<T>::toMeters(depth);
00136 }
00137 }
00138 }
00139
00140 }
00141
00142
00143 #include <pluginlib/class_list_macros.h>
00144 PLUGINLIB_DECLARE_CLASS (depth_image_proc, point_cloud_xyz, depth_image_proc::PointCloudXyzNodelet, nodelet::Nodelet);