$search
00001 #include <ros/ros.h> 00002 #include <nodelet/nodelet.h> 00003 #include <image_transport/image_transport.h> 00004 #include <image_transport/subscriber_filter.h> 00005 #include <message_filters/subscriber.h> 00006 #include <message_filters/synchronizer.h> 00007 #include <message_filters/sync_policies/approximate_time.h> 00008 #include <pcl_ros/point_cloud.h> 00009 #include <pcl/point_types.h> 00010 #include <sensor_msgs/image_encodings.h> 00011 #include <image_geometry/pinhole_camera_model.h> 00012 #include "depth_traits.h" 00013 00014 namespace depth_image_proc { 00015 00016 using namespace message_filters::sync_policies; 00017 namespace enc = sensor_msgs::image_encodings; 00018 00019 typedef union 00020 { 00021 struct /*anonymous*/ 00022 { 00023 unsigned char Blue; 00024 unsigned char Green; 00025 unsigned char Red; 00026 unsigned char Alpha; 00027 }; 00028 float float_value; 00029 long long_value; 00030 } RGBValue; 00031 00032 class PointCloudXyzrgbNodelet : public nodelet::Nodelet 00033 { 00034 ros::NodeHandlePtr rgb_nh_; 00035 boost::shared_ptr<image_transport::ImageTransport> rgb_it_, depth_it_; 00036 00037 // Subscriptions 00038 image_transport::SubscriberFilter sub_depth_, sub_rgb_; 00039 message_filters::Subscriber<sensor_msgs::CameraInfo> sub_info_; 00040 typedef ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> SyncPolicy; 00041 typedef message_filters::Synchronizer<SyncPolicy> Synchronizer; 00042 boost::shared_ptr<Synchronizer> sync_; 00043 00044 // Publications 00045 boost::mutex connect_mutex_; 00046 typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud; 00047 ros::Publisher pub_point_cloud_; 00048 00049 image_geometry::PinholeCameraModel model_; 00050 00051 virtual void onInit(); 00052 00053 void connectCb(); 00054 00055 void imageCb(const sensor_msgs::ImageConstPtr& depth_msg, 00056 const sensor_msgs::ImageConstPtr& rgb_msg, 00057 const sensor_msgs::CameraInfoConstPtr& info_msg); 00058 00059 template<typename T> 00060 void convert(const sensor_msgs::ImageConstPtr& depth_msg, 00061 const sensor_msgs::ImageConstPtr& rgb_msg, 00062 const PointCloud::Ptr& cloud_msg, 00063 int red_offset, int green_offset, int blue_offset, int color_step); 00064 }; 00065 00066 void PointCloudXyzrgbNodelet::onInit() 00067 { 00068 ros::NodeHandle& nh = getNodeHandle(); 00069 ros::NodeHandle& private_nh = getPrivateNodeHandle(); 00070 rgb_nh_.reset( new ros::NodeHandle(nh, "rgb") ); 00071 ros::NodeHandle depth_nh(nh, "depth_registered"); 00072 rgb_it_ .reset( new image_transport::ImageTransport(*rgb_nh_) ); 00073 depth_it_.reset( new image_transport::ImageTransport(depth_nh) ); 00074 00075 // Read parameters 00076 int queue_size; 00077 private_nh.param("queue_size", queue_size, 5); 00078 00079 // Synchronize inputs. Topic subscriptions happen on demand in the connection callback. 00080 sync_.reset( new Synchronizer(SyncPolicy(queue_size), sub_depth_, sub_rgb_, sub_info_) ); 00081 sync_->registerCallback(boost::bind(&PointCloudXyzrgbNodelet::imageCb, this, _1, _2, _3)); 00082 00083 // Monitor whether anyone is subscribed to the output 00084 ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyzrgbNodelet::connectCb, this); 00085 // Make sure we don't enter connectCb() between advertising and assigning to pub_point_cloud_ 00086 boost::lock_guard<boost::mutex> lock(connect_mutex_); 00087 pub_point_cloud_ = depth_nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb); 00088 } 00089 00090 // Handles (un)subscribing when clients (un)subscribe 00091 void PointCloudXyzrgbNodelet::connectCb() 00092 { 00093 boost::lock_guard<boost::mutex> lock(connect_mutex_); 00094 if (pub_point_cloud_.getNumSubscribers() == 0) 00095 { 00096 sub_depth_.unsubscribe(); 00097 sub_rgb_ .unsubscribe(); 00098 sub_info_ .unsubscribe(); 00099 } 00100 else if (!sub_depth_.getSubscriber()) 00101 { 00102 sub_depth_.subscribe(*depth_it_, "image_rect", 1); 00103 sub_rgb_ .subscribe(*rgb_it_, "image_rect_color", 1); 00104 sub_info_ .subscribe(*rgb_nh_, "camera_info", 1); 00105 } 00106 } 00107 00108 void PointCloudXyzrgbNodelet::imageCb(const sensor_msgs::ImageConstPtr& depth_msg, 00109 const sensor_msgs::ImageConstPtr& rgb_msg, 00110 const sensor_msgs::CameraInfoConstPtr& info_msg) 00111 { 00112 // Check for bad inputs 00113 if (depth_msg->header.frame_id != rgb_msg->header.frame_id) 00114 { 00115 NODELET_ERROR_THROTTLE(5, "Depth image frame id [%s] doesn't match RGB image frame id [%s]", 00116 depth_msg->header.frame_id.c_str(), rgb_msg->header.frame_id.c_str()); 00117 return; 00118 } 00119 00120 if (depth_msg->width != rgb_msg->width || depth_msg->height != rgb_msg->height) 00121 { 00122 NODELET_ERROR_THROTTLE(5, "Depth resolution (%ux%u) does not match RGB resolution (%ux%u)", 00123 depth_msg->width, depth_msg->height, rgb_msg->width, rgb_msg->height); 00124 return; 00125 } 00126 00127 // Supported color encodings: RGB8, BGR8, MONO8 00128 int red_offset, green_offset, blue_offset, color_step; 00129 if (rgb_msg->encoding == enc::RGB8) 00130 { 00131 red_offset = 0; 00132 green_offset = 1; 00133 blue_offset = 2; 00134 color_step = 3; 00135 } 00136 else if (rgb_msg->encoding == enc::BGR8) 00137 { 00138 red_offset = 2; 00139 green_offset = 1; 00140 blue_offset = 0; 00141 color_step = 3; 00142 } 00143 else if (rgb_msg->encoding == enc::MONO8) 00144 { 00145 red_offset = 0; 00146 green_offset = 0; 00147 blue_offset = 0; 00148 color_step = 1; 00149 } 00150 else 00151 { 00152 NODELET_ERROR_THROTTLE(5, "Unsupported encoding [%s]", rgb_msg->encoding.c_str()); 00153 return; 00154 } 00155 00156 // Allocate new point cloud message 00157 PointCloud::Ptr cloud_msg (new PointCloud); 00158 cloud_msg->header = depth_msg->header; // Use depth image time stamp 00159 cloud_msg->height = depth_msg->height; 00160 cloud_msg->width = depth_msg->width; 00161 cloud_msg->is_dense = false; 00162 cloud_msg->points.resize (cloud_msg->height * cloud_msg->width); 00163 00164 // Update camera model 00165 model_.fromCameraInfo(info_msg); 00166 00167 if (depth_msg->encoding == enc::TYPE_16UC1) 00168 { 00169 convert<uint16_t>(depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); 00170 } 00171 else if (depth_msg->encoding == enc::TYPE_32FC1) 00172 { 00173 convert<float>(depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); 00174 } 00175 else 00176 { 00177 NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str()); 00178 return; 00179 } 00180 00181 pub_point_cloud_.publish (cloud_msg); 00182 } 00183 00184 template<typename T> 00185 void PointCloudXyzrgbNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg, 00186 const sensor_msgs::ImageConstPtr& rgb_msg, 00187 const PointCloud::Ptr& cloud_msg, 00188 int red_offset, int green_offset, int blue_offset, int color_step) 00189 { 00190 // Use correct principal point from calibration 00191 float center_x = model_.cx(); 00192 float center_y = model_.cy(); 00193 00194 // Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y) 00195 double unit_scaling = DepthTraits<T>::toMeters( T(1) ); 00196 float constant_x = unit_scaling / model_.fx(); 00197 float constant_y = unit_scaling / model_.fy(); 00198 float bad_point = std::numeric_limits<float>::quiet_NaN (); 00199 00200 const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]); 00201 int row_step = depth_msg->step / sizeof(T); 00202 const uint8_t* rgb = &rgb_msg->data[0]; 00203 int rgb_skip = rgb_msg->step - rgb_msg->width * color_step; 00204 PointCloud::iterator pt_iter = cloud_msg->begin (); 00205 00206 for (int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step, rgb += rgb_skip) 00207 { 00208 for (int u = 0; u < (int)cloud_msg->width; ++u, rgb += color_step) 00209 { 00210 pcl::PointXYZRGB& pt = *pt_iter++; 00211 T depth = depth_row[u]; 00212 00213 // Check for invalid measurements 00214 if (!DepthTraits<T>::valid(depth)) 00215 { 00216 pt.x = pt.y = pt.z = bad_point; 00217 } 00218 else 00219 { 00220 // Fill in XYZ 00221 pt.x = (u - center_x) * depth * constant_x; 00222 pt.y = (v - center_y) * depth * constant_y; 00223 pt.z = DepthTraits<T>::toMeters(depth); 00224 } 00225 00226 // Fill in color 00227 RGBValue color; 00228 color.Red = rgb[red_offset]; 00229 color.Green = rgb[green_offset]; 00230 color.Blue = rgb[blue_offset]; 00231 color.Alpha = 0; 00232 pt.rgb = color.float_value; 00233 } 00234 } 00235 } 00236 00237 } // namespace depth_image_proc 00238 00239 // Register as nodelet 00240 #include <pluginlib/class_list_macros.h> 00241 PLUGINLIB_DECLARE_CLASS (depth_image_proc, point_cloud_xyzrgb, depth_image_proc::PointCloudXyzrgbNodelet, nodelet::Nodelet);