point_cloud2.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/exact_time.h>
00008 #include <message_filters/sync_policies/approximate_time.h>
00009 #include <image_geometry/stereo_camera_model.h>
00010 
00011 #include <stereo_msgs/DisparityImage.h>
00012 #include <sensor_msgs/PointCloud2.h>
00013 #include <sensor_msgs/image_encodings.h>
00014 
00015 namespace stereo_image_proc {
00016 
00017 using namespace sensor_msgs;
00018 using namespace stereo_msgs;
00019 using namespace message_filters::sync_policies;
00020 
00021 class PointCloud2Nodelet : public nodelet::Nodelet
00022 {
00023   boost::shared_ptr<image_transport::ImageTransport> it_;
00024 
00025   // Subscriptions
00026   image_transport::SubscriberFilter sub_l_image_;
00027   message_filters::Subscriber<CameraInfo> sub_l_info_, sub_r_info_;
00028   message_filters::Subscriber<DisparityImage> sub_disparity_;
00029   typedef ExactTime<Image, CameraInfo, CameraInfo, DisparityImage> ExactPolicy;
00030   typedef ApproximateTime<Image, CameraInfo, CameraInfo, DisparityImage> ApproximatePolicy;
00031   typedef message_filters::Synchronizer<ExactPolicy> ExactSync;
00032   typedef message_filters::Synchronizer<ApproximatePolicy> ApproximateSync;
00033   boost::shared_ptr<ExactSync> exact_sync_;
00034   boost::shared_ptr<ApproximateSync> approximate_sync_;
00035 
00036   // Publications
00037   boost::mutex connect_mutex_;
00038   ros::Publisher pub_points2_;
00039 
00040   // Processing state (note: only safe because we're single-threaded!)
00041   image_geometry::StereoCameraModel model_;
00042   cv::Mat_<cv::Vec3f> points_mat_; // scratch buffer
00043   
00044   virtual void onInit();
00045 
00046   void connectCb();
00047 
00048   void imageCb(const ImageConstPtr& l_image_msg,
00049                const CameraInfoConstPtr& l_info_msg,
00050                const CameraInfoConstPtr& r_info_msg,
00051                const DisparityImageConstPtr& disp_msg);
00052 };
00053 
00054 void PointCloud2Nodelet::onInit()
00055 {
00056   ros::NodeHandle &nh = getNodeHandle();
00057   ros::NodeHandle &private_nh = getPrivateNodeHandle();
00058   it_.reset(new image_transport::ImageTransport(nh));
00059 
00060   // Synchronize inputs. Topic subscriptions happen on demand in the connection
00061   // callback. Optionally do approximate synchronization.
00062   int queue_size;
00063   private_nh.param("queue_size", queue_size, 5);
00064   bool approx;
00065   private_nh.param("approximate_sync", approx, false);
00066   if (approx)
00067   {
00068     approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size),
00069                                                  sub_l_image_, sub_l_info_,
00070                                                  sub_r_info_, sub_disparity_) );
00071     approximate_sync_->registerCallback(boost::bind(&PointCloud2Nodelet::imageCb,
00072                                                     this, _1, _2, _3, _4));
00073   }
00074   else
00075   {
00076     exact_sync_.reset( new ExactSync(ExactPolicy(queue_size),
00077                                      sub_l_image_, sub_l_info_,
00078                                      sub_r_info_, sub_disparity_) );
00079     exact_sync_->registerCallback(boost::bind(&PointCloud2Nodelet::imageCb,
00080                                               this, _1, _2, _3, _4));
00081   }
00082 
00083   // Monitor whether anyone is subscribed to the output
00084   ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloud2Nodelet::connectCb, this);
00085   // Make sure we don't enter connectCb() between advertising and assigning to pub_points2_
00086   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00087   pub_points2_  = nh.advertise<PointCloud2>("points2",  1, connect_cb, connect_cb);
00088 }
00089 
00090 // Handles (un)subscribing when clients (un)subscribe
00091 void PointCloud2Nodelet::connectCb()
00092 {
00093   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00094   if (pub_points2_.getNumSubscribers() == 0)
00095   {
00096     sub_l_image_  .unsubscribe();
00097     sub_l_info_   .unsubscribe();
00098     sub_r_info_   .unsubscribe();
00099     sub_disparity_.unsubscribe();
00100   }
00101   else if (!sub_l_image_.getSubscriber())
00102   {
00103     ros::NodeHandle &nh = getNodeHandle();
00104     // Queue size 1 should be OK; the one that matters is the synchronizer queue size.
00105     image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00106     sub_l_image_  .subscribe(*it_, "left/image_rect_color", 1, hints);
00107     sub_l_info_   .subscribe(nh,   "left/camera_info", 1);
00108     sub_r_info_   .subscribe(nh,   "right/camera_info", 1);
00109     sub_disparity_.subscribe(nh,   "disparity", 1);
00110   }
00111 }
00112 
00113 inline bool isValidPoint(const cv::Vec3f& pt)
00114 {
00115   // Check both for disparities explicitly marked as invalid (where OpenCV maps pt.z to MISSING_Z)
00116   // and zero disparities (point mapped to infinity).
00117   return pt[2] != image_geometry::StereoCameraModel::MISSING_Z && !std::isinf(pt[2]);
00118 }
00119 
00120 void PointCloud2Nodelet::imageCb(const ImageConstPtr& l_image_msg,
00121                                  const CameraInfoConstPtr& l_info_msg,
00122                                  const CameraInfoConstPtr& r_info_msg,
00123                                  const DisparityImageConstPtr& disp_msg)
00124 {
00125   // Update the camera model
00126   model_.fromCameraInfo(l_info_msg, r_info_msg);
00127 
00128   // Calculate point cloud
00129   const Image& dimage = disp_msg->image;
00130   const cv::Mat_<float> dmat(dimage.height, dimage.width, (float*)&dimage.data[0], dimage.step);
00131   model_.projectDisparityImageTo3d(dmat, points_mat_, true);
00132   cv::Mat_<cv::Vec3f> mat = points_mat_;
00133 
00134   // Fill in new PointCloud2 message (2D image-like layout)
00135   PointCloud2Ptr points_msg = boost::make_shared<PointCloud2>();
00136   points_msg->header = disp_msg->header;
00137   points_msg->height = mat.rows;
00138   points_msg->width  = mat.cols;
00139   points_msg->fields.resize (4);
00140   points_msg->fields[0].name = "x";
00141   points_msg->fields[0].offset = 0;
00142   points_msg->fields[0].count = 1;
00143   points_msg->fields[0].datatype = PointField::FLOAT32;
00144   points_msg->fields[1].name = "y";
00145   points_msg->fields[1].offset = 4;
00146   points_msg->fields[1].count = 1;
00147   points_msg->fields[1].datatype = PointField::FLOAT32;
00148   points_msg->fields[2].name = "z";
00149   points_msg->fields[2].offset = 8;
00150   points_msg->fields[2].count = 1;
00151   points_msg->fields[2].datatype = PointField::FLOAT32;
00152   points_msg->fields[3].name = "rgb";
00153   points_msg->fields[3].offset = 12;
00154   points_msg->fields[3].count = 1;
00155   points_msg->fields[3].datatype = PointField::FLOAT32;
00156   //points_msg->is_bigendian = false; ???
00157   static const int STEP = 16;
00158   points_msg->point_step = STEP;
00159   points_msg->row_step = points_msg->point_step * points_msg->width;
00160   points_msg->data.resize (points_msg->row_step * points_msg->height);
00161   points_msg->is_dense = false; // there may be invalid points
00162  
00163   float bad_point = std::numeric_limits<float>::quiet_NaN ();
00164   int offset = 0;
00165   for (int v = 0; v < mat.rows; ++v)
00166   {
00167     for (int u = 0; u < mat.cols; ++u, offset += STEP)
00168     {
00169       if (isValidPoint(mat(v,u)))
00170       {
00171         // x,y,z,rgba
00172         memcpy (&points_msg->data[offset + 0], &mat(v,u)[0], sizeof (float));
00173         memcpy (&points_msg->data[offset + 4], &mat(v,u)[1], sizeof (float));
00174         memcpy (&points_msg->data[offset + 8], &mat(v,u)[2], sizeof (float));
00175       }
00176       else
00177       {
00178         memcpy (&points_msg->data[offset + 0], &bad_point, sizeof (float));
00179         memcpy (&points_msg->data[offset + 4], &bad_point, sizeof (float));
00180         memcpy (&points_msg->data[offset + 8], &bad_point, sizeof (float));
00181       }
00182     }
00183   }
00184 
00185   // Fill in color
00186   namespace enc = sensor_msgs::image_encodings;
00187   const std::string& encoding = l_image_msg->encoding;
00188   offset = 0;
00189   if (encoding == enc::MONO8)
00190   {
00191     const cv::Mat_<uint8_t> color(l_image_msg->height, l_image_msg->width,
00192                                   (uint8_t*)&l_image_msg->data[0],
00193                                   l_image_msg->step);
00194     for (int v = 0; v < mat.rows; ++v)
00195     {
00196       for (int u = 0; u < mat.cols; ++u, offset += STEP)
00197       {
00198         if (isValidPoint(mat(v,u)))
00199         {
00200           uint8_t g = color(v,u);
00201           int32_t rgb = (g << 16) | (g << 8) | g;
00202           memcpy (&points_msg->data[offset + 12], &rgb, sizeof (int32_t));
00203         }
00204         else
00205         {
00206           memcpy (&points_msg->data[offset + 12], &bad_point, sizeof (float));
00207         }
00208       }
00209     }
00210   }
00211   else if (encoding == enc::RGB8)
00212   {
00213     const cv::Mat_<cv::Vec3b> color(l_image_msg->height, l_image_msg->width,
00214                                     (cv::Vec3b*)&l_image_msg->data[0],
00215                                     l_image_msg->step);
00216     for (int v = 0; v < mat.rows; ++v)
00217     {
00218       for (int u = 0; u < mat.cols; ++u, offset += STEP)
00219       {
00220         if (isValidPoint(mat(v,u)))
00221         {
00222           const cv::Vec3b& rgb = color(v,u);
00223           int32_t rgb_packed = (rgb[0] << 16) | (rgb[1] << 8) | rgb[2];
00224           memcpy (&points_msg->data[offset + 12], &rgb_packed, sizeof (int32_t));
00225         }
00226         else
00227         {
00228           memcpy (&points_msg->data[offset + 12], &bad_point, sizeof (float));
00229         }
00230       }
00231     }
00232   }
00233   else if (encoding == enc::BGR8)
00234   {
00235     const cv::Mat_<cv::Vec3b> color(l_image_msg->height, l_image_msg->width,
00236                                     (cv::Vec3b*)&l_image_msg->data[0],
00237                                     l_image_msg->step);
00238     for (int v = 0; v < mat.rows; ++v)
00239     {
00240       for (int u = 0; u < mat.cols; ++u, offset += STEP)
00241       {
00242         if (isValidPoint(mat(v,u)))
00243         {
00244           const cv::Vec3b& bgr = color(v,u);
00245           int32_t rgb_packed = (bgr[2] << 16) | (bgr[1] << 8) | bgr[0];
00246           memcpy (&points_msg->data[offset + 12], &rgb_packed, sizeof (int32_t));
00247         }
00248         else
00249         {
00250           memcpy (&points_msg->data[offset + 12], &bad_point, sizeof (float));
00251         }
00252       }
00253     }
00254   }
00255   else
00256   {
00257     NODELET_WARN_THROTTLE(30, "Could not fill color channel of the point cloud, "
00258                           "unsupported encoding '%s'", encoding.c_str());
00259   }
00260 
00261   pub_points2_.publish(points_msg);
00262 }
00263 
00264 } // namespace stereo_image_proc
00265 
00266 // Register nodelet
00267 #include <pluginlib/class_list_macros.h>
00268 PLUGINLIB_DECLARE_CLASS(stereo_image_proc, point_cloud2,
00269                         stereo_image_proc::PointCloud2Nodelet, nodelet::Nodelet)


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Fri Jan 3 2014 11:24:49