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


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:53