$search
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 "depth_traits.h" 00009 00010 namespace depth_image_proc { 00011 00012 namespace enc = sensor_msgs::image_encodings; 00013 00014 class PointCloudXyzNodelet : public nodelet::Nodelet 00015 { 00016 // Subscriptions 00017 boost::shared_ptr<image_transport::ImageTransport> it_; 00018 image_transport::CameraSubscriber sub_depth_; 00019 int queue_size_; 00020 00021 // Publications 00022 boost::mutex connect_mutex_; 00023 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud; 00024 ros::Publisher pub_point_cloud_; 00025 00026 image_geometry::PinholeCameraModel model_; 00027 00028 virtual void onInit(); 00029 00030 void connectCb(); 00031 00032 void depthCb(const sensor_msgs::ImageConstPtr& depth_msg, 00033 const sensor_msgs::CameraInfoConstPtr& info_msg); 00034 00035 // Handles float or uint16 depths 00036 template<typename T> 00037 void convert(const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg); 00038 }; 00039 00040 void PointCloudXyzNodelet::onInit() 00041 { 00042 ros::NodeHandle& nh = getNodeHandle(); 00043 ros::NodeHandle& private_nh = getPrivateNodeHandle(); 00044 it_.reset(new image_transport::ImageTransport(nh)); 00045 00046 // Read parameters 00047 private_nh.param("queue_size", queue_size_, 5); 00048 00049 // Monitor whether anyone is subscribed to the output 00050 ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyzNodelet::connectCb, this); 00051 // Make sure we don't enter connectCb() between advertising and assigning to pub_point_cloud_ 00052 boost::lock_guard<boost::mutex> lock(connect_mutex_); 00053 pub_point_cloud_ = nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb); 00054 } 00055 00056 // Handles (un)subscribing when clients (un)subscribe 00057 void PointCloudXyzNodelet::connectCb() 00058 { 00059 boost::lock_guard<boost::mutex> lock(connect_mutex_); 00060 if (pub_point_cloud_.getNumSubscribers() == 0) 00061 { 00062 sub_depth_.shutdown(); 00063 } 00064 else if (!sub_depth_) 00065 { 00066 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle()); 00067 sub_depth_ = it_->subscribeCamera("image_rect", queue_size_, &PointCloudXyzNodelet::depthCb, this, hints); 00068 } 00069 } 00070 00071 void PointCloudXyzNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg, 00072 const sensor_msgs::CameraInfoConstPtr& info_msg) 00073 { 00074 PointCloud::Ptr cloud_msg(new PointCloud); 00075 cloud_msg->header = depth_msg->header; 00076 cloud_msg->height = depth_msg->height; 00077 cloud_msg->width = depth_msg->width; 00078 cloud_msg->is_dense = false; 00079 cloud_msg->points.resize(cloud_msg->height * cloud_msg->width); 00080 00081 // Update camera model 00082 model_.fromCameraInfo(info_msg); 00083 00084 if (depth_msg->encoding == enc::TYPE_16UC1) 00085 { 00086 convert<uint16_t>(depth_msg, cloud_msg); 00087 } 00088 else if (depth_msg->encoding == enc::TYPE_32FC1) 00089 { 00090 convert<float>(depth_msg, cloud_msg); 00091 } 00092 else 00093 { 00094 NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str()); 00095 return; 00096 } 00097 00098 pub_point_cloud_.publish (cloud_msg); 00099 } 00100 00101 template<typename T> 00102 void PointCloudXyzNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg) 00103 { 00104 // Use correct principal point from calibration 00105 float center_x = model_.cx(); 00106 float center_y = model_.cy(); 00107 00108 // Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y) 00109 double unit_scaling = DepthTraits<T>::toMeters( T(1) ); 00110 float constant_x = unit_scaling / model_.fx(); 00111 float constant_y = unit_scaling / model_.fy(); 00112 float bad_point = std::numeric_limits<float>::quiet_NaN(); 00113 00114 PointCloud::iterator pt_iter = cloud_msg->begin(); 00115 const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]); 00116 int row_step = depth_msg->step / sizeof(T); 00117 for (int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step) 00118 { 00119 for (int u = 0; u < (int)cloud_msg->width; ++u) 00120 { 00121 pcl::PointXYZ& pt = *pt_iter++; 00122 T depth = depth_row[u]; 00123 00124 // Missing points denoted by NaNs 00125 if (!DepthTraits<T>::valid(depth)) 00126 { 00127 pt.x = pt.y = pt.z = bad_point; 00128 continue; 00129 } 00130 00131 // Fill in XYZ 00132 pt.x = (u - center_x) * depth * constant_x; 00133 pt.y = (v - center_y) * depth * constant_y; 00134 pt.z = DepthTraits<T>::toMeters(depth); 00135 } 00136 } 00137 } 00138 00139 } // namespace depth_image_proc 00140 00141 // Register as nodelet 00142 #include <pluginlib/class_list_macros.h> 00143 PLUGINLIB_DECLARE_CLASS (depth_image_proc, point_cloud_xyz, depth_image_proc::PointCloudXyzNodelet, nodelet::Nodelet);