point_cloud_xyzrgb.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 #include <boost/version.hpp>
00035 #if ((BOOST_VERSION / 100) % 1000) >= 53
00036 #include <boost/thread/lock_guard.hpp>
00037 #endif
00038 
00039 #include <ros/ros.h>
00040 #include <nodelet/nodelet.h>
00041 #include <image_transport/image_transport.h>
00042 #include <image_transport/subscriber_filter.h>
00043 #include <message_filters/subscriber.h>
00044 #include <message_filters/synchronizer.h>
00045 #include <message_filters/sync_policies/approximate_time.h>
00046 #include <pcl_ros/point_cloud.h>
00047 #include <pcl/point_types.h>
00048 #include <sensor_msgs/image_encodings.h>
00049 #include <image_geometry/pinhole_camera_model.h>
00050 #include <depth_image_proc/depth_traits.h>
00051 #include <cv_bridge/cv_bridge.h>
00052 #include <opencv2/imgproc/imgproc.hpp>
00053 
00054 #include <pcl_conversions/pcl_conversions.h>
00055 
00056 namespace depth_image_proc {
00057 
00058 using namespace message_filters::sync_policies;
00059 namespace enc = sensor_msgs::image_encodings;
00060 
00061 typedef union
00062 {
00063   struct /*anonymous*/
00064   {
00065     unsigned char Blue;
00066     unsigned char Green;
00067     unsigned char Red;
00068     unsigned char Alpha;
00069   };
00070   float float_value;
00071   long long_value;
00072 } RGBValue;
00073 
00074 class PointCloudXyzrgbNodelet : public nodelet::Nodelet
00075 {
00076   ros::NodeHandlePtr rgb_nh_;
00077   boost::shared_ptr<image_transport::ImageTransport> rgb_it_, depth_it_;
00078   
00079   // Subscriptions
00080   image_transport::SubscriberFilter sub_depth_, sub_rgb_;
00081   message_filters::Subscriber<sensor_msgs::CameraInfo> sub_info_;
00082   typedef ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> SyncPolicy;
00083   typedef message_filters::Synchronizer<SyncPolicy> Synchronizer;
00084   boost::shared_ptr<Synchronizer> sync_;
00085 
00086   // Publications
00087   boost::mutex connect_mutex_;
00088   typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
00089   ros::Publisher pub_point_cloud_;
00090 
00091   image_geometry::PinholeCameraModel model_;
00092 
00093   virtual void onInit();
00094 
00095   void connectCb();
00096 
00097   void imageCb(const sensor_msgs::ImageConstPtr& depth_msg,
00098                const sensor_msgs::ImageConstPtr& rgb_msg,
00099                const sensor_msgs::CameraInfoConstPtr& info_msg);
00100 
00101   template<typename T>
00102   void convert(const sensor_msgs::ImageConstPtr& depth_msg,
00103                const sensor_msgs::ImageConstPtr& rgb_msg,
00104                const PointCloud::Ptr& cloud_msg,
00105                int red_offset, int green_offset, int blue_offset, int color_step);
00106 };
00107 
00108 void PointCloudXyzrgbNodelet::onInit()
00109 {
00110   ros::NodeHandle& nh         = getNodeHandle();
00111   ros::NodeHandle& private_nh = getPrivateNodeHandle();
00112   rgb_nh_.reset( new ros::NodeHandle(nh, "rgb") );
00113   ros::NodeHandle depth_nh(nh, "depth_registered");
00114   rgb_it_  .reset( new image_transport::ImageTransport(*rgb_nh_) );
00115   depth_it_.reset( new image_transport::ImageTransport(depth_nh) );
00116 
00117   // Read parameters
00118   int queue_size;
00119   private_nh.param("queue_size", queue_size, 5);
00120 
00121   // Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
00122   sync_.reset( new Synchronizer(SyncPolicy(queue_size), sub_depth_, sub_rgb_, sub_info_) );
00123   sync_->registerCallback(boost::bind(&PointCloudXyzrgbNodelet::imageCb, this, _1, _2, _3));
00124   
00125   // Monitor whether anyone is subscribed to the output
00126   ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyzrgbNodelet::connectCb, this);
00127   // Make sure we don't enter connectCb() between advertising and assigning to pub_point_cloud_
00128   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00129   pub_point_cloud_ = depth_nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
00130 }
00131 
00132 // Handles (un)subscribing when clients (un)subscribe
00133 void PointCloudXyzrgbNodelet::connectCb()
00134 {
00135   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00136   if (pub_point_cloud_.getNumSubscribers() == 0)
00137   {
00138     sub_depth_.unsubscribe();
00139     sub_rgb_  .unsubscribe();
00140     sub_info_ .unsubscribe();
00141   }
00142   else if (!sub_depth_.getSubscriber())
00143   {
00144     ros::NodeHandle& private_nh = getPrivateNodeHandle();
00145     // parameter for depth_image_transport hint
00146     std::string depth_image_transport_param = "depth_image_transport";
00147 
00148     // depth image can use different transport.(e.g. compressedDepth)
00149     image_transport::TransportHints depth_hints("raw",ros::TransportHints(), private_nh, depth_image_transport_param);
00150     sub_depth_.subscribe(*depth_it_, "image_rect",       1, depth_hints);
00151 
00152     // rgb uses normal ros transport hints.
00153     image_transport::TransportHints hints("raw", ros::TransportHints(), private_nh);
00154     sub_rgb_  .subscribe(*rgb_it_,   "image_rect_color", 1, hints);
00155     sub_info_ .subscribe(*rgb_nh_,   "camera_info",      1);
00156   }
00157 }
00158 
00159 void PointCloudXyzrgbNodelet::imageCb(const sensor_msgs::ImageConstPtr& depth_msg,
00160                                       const sensor_msgs::ImageConstPtr& rgb_msg_in,
00161                                       const sensor_msgs::CameraInfoConstPtr& info_msg)
00162 {
00163   // Check for bad inputs
00164   if (depth_msg->header.frame_id != rgb_msg_in->header.frame_id)
00165   {
00166     NODELET_ERROR_THROTTLE(5, "Depth image frame id [%s] doesn't match RGB image frame id [%s]",
00167                            depth_msg->header.frame_id.c_str(), rgb_msg_in->header.frame_id.c_str());
00168     return;
00169   }
00170 
00171   // Update camera model
00172   model_.fromCameraInfo(info_msg);
00173 
00174   // Check if the input image has to be resized
00175   sensor_msgs::ImageConstPtr rgb_msg = rgb_msg_in;
00176   if (depth_msg->width != rgb_msg->width || depth_msg->height != rgb_msg->height)
00177   {
00178     sensor_msgs::CameraInfo info_msg_tmp = *info_msg;
00179     info_msg_tmp.width = depth_msg->width;
00180     info_msg_tmp.height = depth_msg->height;
00181     float ratio = float(depth_msg->width)/float(rgb_msg->width);
00182     info_msg_tmp.K[0] *= ratio;
00183     info_msg_tmp.K[2] *= ratio;
00184     info_msg_tmp.K[4] *= ratio;
00185     info_msg_tmp.K[5] *= ratio;
00186     info_msg_tmp.P[0] *= ratio;
00187     info_msg_tmp.P[2] *= ratio;
00188     info_msg_tmp.P[5] *= ratio;
00189     info_msg_tmp.P[6] *= ratio;
00190     model_.fromCameraInfo(info_msg_tmp);
00191 
00192     cv_bridge::CvImageConstPtr cv_ptr;
00193     try
00194     {
00195       cv_ptr = cv_bridge::toCvShare(rgb_msg, rgb_msg->encoding);
00196     }
00197     catch (cv_bridge::Exception& e)
00198     {
00199       ROS_ERROR("cv_bridge exception: %s", e.what());
00200       return;
00201     }
00202     cv_bridge::CvImage cv_rsz;
00203     cv_rsz.header = cv_ptr->header;
00204     cv_rsz.encoding = cv_ptr->encoding;
00205     cv::resize(cv_ptr->image.rowRange(0,depth_msg->height/ratio), cv_rsz.image, cv::Size(depth_msg->width, depth_msg->height));
00206     if ((rgb_msg->encoding == enc::RGB8) || (rgb_msg->encoding == enc::BGR8) || (rgb_msg->encoding == enc::MONO8))
00207       rgb_msg = cv_rsz.toImageMsg();
00208     else
00209       rgb_msg = cv_bridge::toCvCopy(cv_rsz.toImageMsg(), enc::RGB8)->toImageMsg();
00210 
00211     //NODELET_ERROR_THROTTLE(5, "Depth resolution (%ux%u) does not match RGB resolution (%ux%u)",
00212     //                       depth_msg->width, depth_msg->height, rgb_msg->width, rgb_msg->height);
00213     //return;
00214   } else
00215     rgb_msg = rgb_msg_in;
00216 
00217   // Supported color encodings: RGB8, BGR8, MONO8
00218   int red_offset, green_offset, blue_offset, color_step;
00219   if (rgb_msg->encoding == enc::RGB8)
00220   {
00221     red_offset   = 0;
00222     green_offset = 1;
00223     blue_offset  = 2;
00224     color_step   = 3;
00225   }
00226   else if (rgb_msg->encoding == enc::BGR8)
00227   {
00228     red_offset   = 2;
00229     green_offset = 1;
00230     blue_offset  = 0;
00231     color_step   = 3;
00232   }
00233   else if (rgb_msg->encoding == enc::MONO8)
00234   {
00235     red_offset   = 0;
00236     green_offset = 0;
00237     blue_offset  = 0;
00238     color_step   = 1;
00239   }
00240   else
00241   {
00242     try
00243     {
00244       rgb_msg = cv_bridge::toCvCopy(rgb_msg, enc::RGB8)->toImageMsg();
00245     }
00246     catch (cv_bridge::Exception& e)
00247     {
00248       NODELET_ERROR_THROTTLE(5, "Unsupported encoding [%s]: %s", rgb_msg->encoding.c_str(), e.what());
00249       return;
00250     }
00251     red_offset   = 0;
00252     green_offset = 1;
00253     blue_offset  = 2;
00254     color_step   = 3;
00255   }
00256 
00257   // Allocate new point cloud message
00258   PointCloud::Ptr cloud_msg (new PointCloud);
00259   cloud_msg->header = pcl_conversions::toPCL(depth_msg->header); // Use depth image time stamp
00260   cloud_msg->height = depth_msg->height;
00261   cloud_msg->width  = depth_msg->width;
00262   cloud_msg->is_dense = false;
00263   cloud_msg->points.resize (cloud_msg->height * cloud_msg->width);
00264 
00265   if (depth_msg->encoding == enc::TYPE_16UC1)
00266   {
00267     convert<uint16_t>(depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step);
00268   }
00269   else if (depth_msg->encoding == enc::TYPE_32FC1)
00270   {
00271     convert<float>(depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step);
00272   }
00273   else
00274   {
00275     NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
00276     return;
00277   }
00278 
00279   pub_point_cloud_.publish (cloud_msg);
00280 }
00281 
00282 template<typename T>
00283 void PointCloudXyzrgbNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
00284                                       const sensor_msgs::ImageConstPtr& rgb_msg,
00285                                       const PointCloud::Ptr& cloud_msg,
00286                                       int red_offset, int green_offset, int blue_offset, int color_step)
00287 {
00288   // Use correct principal point from calibration
00289   float center_x = model_.cx();
00290   float center_y = model_.cy();
00291 
00292   // Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y)
00293   double unit_scaling = DepthTraits<T>::toMeters( T(1) );
00294   float constant_x = unit_scaling / model_.fx();
00295   float constant_y = unit_scaling / model_.fy();
00296   float bad_point = std::numeric_limits<float>::quiet_NaN ();
00297   
00298   const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
00299   int row_step = depth_msg->step / sizeof(T);
00300   const uint8_t* rgb = &rgb_msg->data[0];
00301   int rgb_skip = rgb_msg->step - rgb_msg->width * color_step;
00302   PointCloud::iterator pt_iter = cloud_msg->begin ();
00303 
00304   for (int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step, rgb += rgb_skip)
00305   {
00306     for (int u = 0; u < (int)cloud_msg->width; ++u, rgb += color_step)
00307     {
00308       pcl::PointXYZRGB& pt = *pt_iter++;
00309       T depth = depth_row[u];
00310 
00311       // Check for invalid measurements
00312       if (!DepthTraits<T>::valid(depth))
00313       {
00314         pt.x = pt.y = pt.z = bad_point;
00315       }
00316       else
00317       {
00318         // Fill in XYZ
00319         pt.x = (u - center_x) * depth * constant_x;
00320         pt.y = (v - center_y) * depth * constant_y;
00321         pt.z = DepthTraits<T>::toMeters(depth);
00322       }
00323 
00324       // Fill in color
00325       RGBValue color;
00326       color.Red   = rgb[red_offset];
00327       color.Green = rgb[green_offset];
00328       color.Blue  = rgb[blue_offset];
00329       color.Alpha = 0;
00330       pt.rgb = color.float_value;
00331     }
00332   }
00333 }
00334 
00335 } // namespace depth_image_proc
00336 
00337 // Register as nodelet
00338 #include <pluginlib/class_list_macros.h>
00339 PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyzrgbNodelet,nodelet::Nodelet);


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Wed Aug 26 2015 11:57:40