point_cloud_xyz.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 <ros/ros.h>
00035 #include <nodelet/nodelet.h>
00036 #include <image_transport/image_transport.h>
00037 #include <pcl_ros/point_cloud.h>
00038 #include <pcl/point_types.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <image_geometry/pinhole_camera_model.h>
00041 #include <boost/thread.hpp>
00042 #include "depth_traits.h"
00043 
00044 namespace depth_image_proc {
00045 
00046 namespace enc = sensor_msgs::image_encodings;
00047 
00048 class PointCloudXyzNodelet : public nodelet::Nodelet
00049 {
00050   // Subscriptions
00051   boost::shared_ptr<image_transport::ImageTransport> it_;
00052   image_transport::CameraSubscriber sub_depth_;
00053   int queue_size_;
00054 
00055   // Publications
00056   boost::mutex connect_mutex_;
00057   typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00058   ros::Publisher pub_point_cloud_;
00059 
00060   image_geometry::PinholeCameraModel model_;
00061 
00062   virtual void onInit();
00063 
00064   void connectCb();
00065 
00066   void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00067                const sensor_msgs::CameraInfoConstPtr& info_msg);
00068 
00069   // Handles float or uint16 depths
00070   template<typename T>
00071   void convert(const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg);
00072 };
00073 
00074 void PointCloudXyzNodelet::onInit()
00075 {
00076   ros::NodeHandle& nh         = getNodeHandle();
00077   ros::NodeHandle& private_nh = getPrivateNodeHandle();
00078   it_.reset(new image_transport::ImageTransport(nh));
00079 
00080   // Read parameters
00081   private_nh.param("queue_size", queue_size_, 5);
00082 
00083   // Monitor whether anyone is subscribed to the output
00084   ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyzNodelet::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_ = nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
00088 }
00089 
00090 // Handles (un)subscribing when clients (un)subscribe
00091 void PointCloudXyzNodelet::connectCb()
00092 {
00093   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00094   if (pub_point_cloud_.getNumSubscribers() == 0)
00095   {
00096     sub_depth_.shutdown();
00097   }
00098   else if (!sub_depth_)
00099   {
00100     image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00101     sub_depth_ = it_->subscribeCamera("image_rect", queue_size_, &PointCloudXyzNodelet::depthCb, this, hints);
00102   }
00103 }
00104 
00105 void PointCloudXyzNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00106                                    const sensor_msgs::CameraInfoConstPtr& info_msg)
00107 {
00108   PointCloud::Ptr cloud_msg(new PointCloud);
00109   cloud_msg->header = depth_msg->header;
00110   cloud_msg->height = depth_msg->height;
00111   cloud_msg->width  = depth_msg->width;
00112   cloud_msg->is_dense = false;
00113   cloud_msg->points.resize(cloud_msg->height * cloud_msg->width);
00114 
00115   // Update camera model
00116   model_.fromCameraInfo(info_msg);
00117 
00118   if (depth_msg->encoding == enc::TYPE_16UC1)
00119   {
00120     convert<uint16_t>(depth_msg, cloud_msg);
00121   }
00122   else if (depth_msg->encoding == enc::TYPE_32FC1)
00123   {
00124     convert<float>(depth_msg, cloud_msg);
00125   }
00126   else
00127   {
00128     NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
00129     return;
00130   }
00131 
00132   pub_point_cloud_.publish (cloud_msg);
00133 }
00134 
00135 template<typename T>
00136 void PointCloudXyzNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg)
00137 {
00138   // Use correct principal point from calibration
00139   float center_x = model_.cx();
00140   float center_y = model_.cy();
00141 
00142   // Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y)
00143   double unit_scaling = DepthTraits<T>::toMeters( T(1) );
00144   float constant_x = unit_scaling / model_.fx();
00145   float constant_y = unit_scaling / model_.fy();
00146   float bad_point = std::numeric_limits<float>::quiet_NaN();
00147 
00148   PointCloud::iterator pt_iter = cloud_msg->begin();
00149   const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
00150   int row_step = depth_msg->step / sizeof(T);
00151   for (int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
00152   {
00153     for (int u = 0; u < (int)cloud_msg->width; ++u)
00154     {
00155       pcl::PointXYZ& pt = *pt_iter++;
00156       T depth = depth_row[u];
00157 
00158       // Missing points denoted by NaNs
00159       if (!DepthTraits<T>::valid(depth))
00160       {
00161         pt.x = pt.y = pt.z = bad_point;
00162         continue;
00163       }
00164 
00165       // Fill in XYZ
00166       pt.x = (u - center_x) * depth * constant_x;
00167       pt.y = (v - center_y) * depth * constant_y;
00168       pt.z = DepthTraits<T>::toMeters(depth);
00169     }
00170   }
00171 }
00172 
00173 } // namespace depth_image_proc
00174 
00175 // Register as nodelet
00176 #include <pluginlib/class_list_macros.h>
00177 PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyzNodelet,nodelet::Nodelet);


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Mon Oct 6 2014 00:46:03