pointcloud_registration_nodelet.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, Hozefa Indorewala <indorewala@ias.in.tum.de>
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /*
00031  * Author: Hozefa Indorewala
00032  * This node subscribes to a PointCloud2 topic, receives point clouds and then registers them and publishes
00033  * the result on /merged_pointcloud (PointCloud2)
00034  */
00035 
00036 #include <ros/ros.h>
00037 #include <pcl_ros/publisher.h>
00038 #include <pcl_ros/pcl_nodelet.h>
00039 #include <sensor_msgs/PointCloud2.h>
00040 #include <sensor_msgs/PointCloud.h>
00041 #include <sensor_msgs/point_cloud_conversion.h>
00042 #include <pointcloud_registration/pointcloud_registration_point_types.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <Eigen/SVD>
00045 #include "pcl/filters/statistical_outlier_removal.h" // to filter outliers
00046 
00047 #include "pcl/filters/voxel_grid.h" //for downsampling the point cloud
00048 
00049 #include "pcl/kdtree/kdtree_flann.h" //for the kdtree
00050 
00051 #include "pcl/registration/transforms.h" //for the transformation function
00052 
00053 #include <pcl/features/normal_3d_omp.h>
00054 #include <pluginlib/class_list_macros.h>
00055 
00056 #include <pointcloud_registration/icp/icp_correspondences_check.h> //for icp
00057 #include <algorithm> //for the sort and unique functions
00058 
00059 #include <ctime>
00060 namespace pointcloud_registration
00061 {
00062 const float PI = 3.14159265;
00063 
00064 
00066 bool pclSort (pcl::PointXYZINormal i, pcl::PointXYZINormal j)
00067 {
00068   return (i.x < j.x);
00069 }
00070 
00072 bool pclUnique (pcl::PointXYZINormal i, pcl::PointXYZINormal j)
00073 {
00074   double x_diff = fabs(i.x - j.x);
00075   double y_diff = fabs(i.y - j.y);
00076   double z_diff = fabs(i.z - j.z);
00077   if(x_diff < 0.0001 && y_diff < 0.0001 && z_diff < 0.0001 )
00078     return 1;
00079   else
00080     return 0;
00081 }
00083 
00084 class PointCloudRegistration:public pcl_ros::PCLNodelet
00085 {
00086   public:
00087     PointCloudRegistration();
00088     ~PointCloudRegistration();
00089     void onInit();
00090     void pointcloudRegistrationCallBack(const sensor_msgs::PointCloud& msg);
00091     Eigen::Matrix4f getOverlapTransformation();
00092     void publishPointCloud(pcl::PointCloud<pcl::PointXYZINormal> &pointcloud);
00093     pcl::PointCloud<pcl::PointXYZINormal> convertFromMsgToPointCloud(const sensor_msgs::PointCloud& pointcloud_msg);
00094 
00095   protected:
00096     using pcl_ros::PCLNodelet::pnh_;
00097   private:
00098     //ros::NodeHandle nh_;
00099   std::string merged_pointcloud_topic_, subscribe_pointcloud_topic_, frame_id_, field_;
00100     int max_number_of_iterations_icp_, max_nn_icp_, max_nn_overlap_;
00101     double downsample_leafsize_, epsilon_z_, epsilon_curvature_, epsilon_transformation_, radius_icp_, radius_overlap_;
00102     bool downsample_pointcloud_before_, downsample_pointcloud_after_, filter_outliers_, curvature_check_;
00103     int scan_index_;
00104     time_t start, end;
00105     Eigen::Matrix4f final_transformation_;
00106     ros::Subscriber pointcloud_subscriber_;
00107     ros::Publisher pointcloud_merged_publisher_;
00108 
00109     pcl::IterativeClosestPointCorrespondencesCheck<pcl::PointXYZINormal, pcl::PointXYZINormal> icp_; // for icp
00110     pcl::KdTreeFLANN<pcl::PointXYZINormal> kdtree_;  // for kdtree
00111     bool firstCloudReceived_, secondCloudReceived_;
00112     pcl::PointCloud<pcl::PointXYZINormal> pointcloud2_current_, pointcloud2_merged_, pointcloud2_transformed_;
00113 };
00114 
00116 
00117 Eigen::Matrix4f PointCloudRegistration::getOverlapTransformation()
00118 {
00119   // In this function we extract the overlapped region of the two points cloud and compute
00120   // the transformation and return it.
00121 
00122   if(firstCloudReceived_ == false && secondCloudReceived_ == false )
00123   {
00124     ROS_ERROR("getOverlapTransformation called before receiving atleast 2 point clouds");
00125     exit(1);
00126   }
00127   else
00128   {
00129     //searching for overlapped points in the point cloud
00130     // Allocate enough space to hold the results
00131     std::vector<int> nn_indices (max_nn_overlap_);
00132     std::vector<float> nn_dists (max_nn_overlap_);
00133 
00134     boost::shared_ptr <pcl::PointCloud<pcl::PointXYZINormal> > overlap_model (new pcl::PointCloud<pcl::PointXYZINormal>());
00135     boost::shared_ptr <pcl::PointCloud<pcl::PointXYZINormal> > overlap_current (new pcl::PointCloud<pcl::PointXYZINormal>());
00136 
00137     //pcl::PointCloud<pcl::PointXYZINormal> overlap_model, overlap_current;
00138     Eigen::Matrix4f transformation;
00139 
00140     std::vector<pcl:: PointXYZINormal, Eigen::aligned_allocator<pcl:: PointXYZINormal> >::iterator it;
00141     for(size_t idx = 0 ; idx < pointcloud2_current_.points.size(); idx++ )
00142     {
00143       kdtree_.radiusSearch(pointcloud2_current_, idx, radius_overlap_, nn_indices, nn_dists, max_nn_overlap_);
00144 
00145       if(nn_indices.size() > 0 )
00146       {
00147         overlap_current->points.push_back(pointcloud2_current_.points[idx]);
00148               for(size_t i = 0 ; i < nn_indices.size(); i++)
00149         {
00150           overlap_model->points.push_back (kdtree_.getInputCloud()->points[nn_indices[i]]);
00151         }
00152       }
00153     }
00154     ROS_INFO("performed search for overlapping points");
00155 
00156     //Getting rid of duplicate points in model
00157     std::sort(overlap_model->points.begin(), overlap_model->points.end(), pclSort);
00158     it = std::unique(overlap_model->points.begin(), overlap_model->points.end(), pclUnique);
00159     overlap_model->points.resize(it - overlap_model->points.begin());
00160 
00161     ROS_INFO("setting ICP clouds");
00162 
00163     icp_.setInputTarget (overlap_model);
00164     icp_.setInputCloud (overlap_current);
00165 
00166     ROS_INFO ("performing ICP");
00167     icp_.align (pointcloud2_transformed_);
00168     transformation = icp_.getFinalTransformation();
00169     return (transformation);
00170   }
00171 }
00172 
00174 
00175 void PointCloudRegistration::publishPointCloud(pcl::PointCloud<pcl::PointXYZINormal> &pointcloud)
00176 {
00177   sensor_msgs::PointCloud2 mycloud;
00178   pcl::toROSMsg(pointcloud, mycloud);
00179 
00180   if( downsample_pointcloud_after_ == true)
00181   {
00182     // for downsampling of pointclouds
00183     pcl::VoxelGrid<sensor_msgs::PointCloud2> sor_;
00184     sensor_msgs::PointCloud2 mycloud_downsampled;
00185 
00186     //Now we will downsample the point cloud
00187     sor_.setInputCloud (boost::make_shared<sensor_msgs::PointCloud2> (mycloud));
00188     sor_.setLeafSize (downsample_leafsize_, downsample_leafsize_, downsample_leafsize_);
00189     sor_.filter (mycloud_downsampled);
00190     mycloud_downsampled.header.frame_id = frame_id_;
00191     mycloud_downsampled.header.stamp = ros::Time::now();
00192 
00193     pointcloud_merged_publisher_.publish(mycloud_downsampled);
00194   }
00195   else
00196   {
00197     mycloud.header.frame_id = frame_id_;
00198     mycloud.header.stamp = ros::Time::now();
00199 
00200     pointcloud_merged_publisher_.publish(mycloud);
00201   }
00202   ROS_INFO("Merged Point cloud published");
00203 }
00205 
00206 pcl::PointCloud<pcl::PointXYZINormal> PointCloudRegistration::convertFromMsgToPointCloud(const sensor_msgs::PointCloud& pointcloud_msg)
00207 {
00208   //incrementing the scan index
00209   scan_index_++;
00210   // Declaring some variables required in this function
00211   sensor_msgs::PointCloud2 pointcloud2_msg;
00212   pcl::PointCloud<pcl::PointXYZI> pointcloud_pcl_step01, pointcloud_pcl_step02;
00213   pcl::PointCloud<pcl::PointXYZINormal> pointcloud_pcl_normals;
00214   pcl::NormalEstimation<pcl::PointXYZI, pcl::Normal> n;
00215   pcl::KdTreeFLANN<pcl::PointXYZI>::Ptr tree_ptr_;
00216   tree_ptr_ = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZI> > ();
00217   std::vector<int> indices;
00218 
00219   // Converting from PointCloud msg format to PointCloud2 msg format
00220 
00221   sensor_msgs::convertPointCloudToPointCloud2(pointcloud_msg, pointcloud2_msg);
00222 
00223   //This is done because there is a bug in PCL.
00224   for(u_int i = 0 ; i < pointcloud2_msg.fields.size(); i++)
00225   {
00226     if(pointcloud2_msg.fields[i].name == "intensities")
00227     {
00228       pointcloud2_msg.fields[i].name = "intensity";
00229     }
00230   }
00231 
00232   // STEP 01: Check if we should downsample the input cloud or not
00233   if(downsample_pointcloud_before_ == true)
00234   {
00235     ROS_INFO ("PointCloud before downsampling: %d .", pointcloud2_msg.width * pointcloud2_msg.height);
00236     sensor_msgs::PointCloud2 pointcloud_downsampled_msg;
00237     pcl::VoxelGrid<sensor_msgs::PointCloud2> sor_; // for downsampling of pointclouds
00238 
00239     //Now we will downsample the point cloud
00240     sor_.setInputCloud (boost::make_shared<sensor_msgs::PointCloud2> (pointcloud2_msg));
00241     sor_.setLeafSize (downsample_leafsize_, downsample_leafsize_, downsample_leafsize_);
00242     sor_.filter (pointcloud_downsampled_msg);
00243     ROS_INFO ("PointCloud after downsampling: %d .", pointcloud_downsampled_msg.width * pointcloud_downsampled_msg.height);
00244 
00245     // Converting from PointCloud2 msg format to pcl pointcloud format
00246     pcl::fromROSMsg(pointcloud_downsampled_msg, pointcloud_pcl_step01);
00247   }
00248   else
00249   {
00250     // Converting from PointCloud2 msg format to pcl pointcloud format
00251     pcl::fromROSMsg(pointcloud2_msg, pointcloud_pcl_step01);
00252   }
00253 
00254   // STEP 02: Check if we should filter the outliers or not
00255 
00256   if(filter_outliers_)
00257   {
00258     // Removing outliers
00259     pcl::StatisticalOutlierRemoval<pcl::PointXYZI> sor;
00260     sor.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointXYZI> >(pointcloud_pcl_step01));
00261     sor.setMeanK (50);
00262     sor.setStddevMulThresh (1.0);
00263     sor.filter (pointcloud_pcl_step02);
00264   }
00265   else
00266   {
00267     pointcloud_pcl_step02 = pointcloud_pcl_step01;
00268   }
00269   tree_ptr_->setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointXYZI> > (pointcloud_pcl_step02));
00270   indices.resize (pointcloud_pcl_step02.points.size ());
00271   for (size_t i = 0; i < indices.size (); ++i)
00272   {
00273     indices[i] = i;
00274   }
00275 
00276   // STEP 03: Here we perform Normal Estimation on the input cloud
00277 
00278   // Object
00279   pcl::PointCloud<pcl::Normal> normals;
00280   // set parameters
00281 
00282   n.setInputCloud (boost::make_shared <const pcl::PointCloud<pcl::PointXYZI> > (pointcloud_pcl_step02));
00283   n.setIndices (boost::make_shared <std::vector<int> > (indices));
00284   n.setSearchMethod (tree_ptr_);
00285   n.setKSearch (10);
00286 
00287   // estimate
00288   n.compute (normals);
00289 
00290   // STEP 04: Here we copy data from the normals and the input cloud into the pcl::PointXYZINormal cloud
00291 
00292   pointcloud_pcl_normals.points.resize(pointcloud_pcl_step02.points.size());
00293 
00294   for(u_int i = 0 ; i < pointcloud_pcl_step02.points.size(); i++)
00295   {
00296     pointcloud_pcl_normals.points[i].x = pointcloud_pcl_step02.points[i].x;
00297     pointcloud_pcl_normals.points[i].y = pointcloud_pcl_step02.points[i].y;
00298     pointcloud_pcl_normals.points[i].z = pointcloud_pcl_step02.points[i].z;
00299     //pointcloud_pcl_normals.points[i].rgb = pointcloud_pcl_step02.points[i].rgb;
00300     pointcloud_pcl_normals.points[i].intensity = pointcloud_pcl_step02.points[i].intensity;
00301     pointcloud_pcl_normals.points[i].normal[0] = normals.points[i].normal[0];
00302     pointcloud_pcl_normals.points[i].normal[1] = normals.points[i].normal[1];
00303     pointcloud_pcl_normals.points[i].normal[2] = normals.points[i].normal[2];
00304     pointcloud_pcl_normals.points[i].curvature = normals.points[i].curvature;
00305     //pointcloud_pcl_normals.points[i].scan_index = scan_index_;
00306   }
00307 
00308   pointcloud_pcl_normals.header.frame_id = pointcloud_pcl_normals.header.frame_id;
00309   pointcloud_pcl_normals.header.stamp = pointcloud_pcl_normals.header.stamp;
00310   pointcloud_pcl_normals.width    = pointcloud_pcl_normals.points.size ();
00311   pointcloud_pcl_normals.height   = 1;
00312   pointcloud_pcl_normals.is_dense = false;
00313 
00314   return (pointcloud_pcl_normals);
00315 }
00316 
00318 
00319 void PointCloudRegistration::onInit()
00320 {
00321   pcl_ros::PCLNodelet::onInit ();
00322   pnh_->param("publish_merged_pointcloud_topic", merged_pointcloud_topic_, std::string("/merged_pointcloud"));
00323   pnh_->param("subscribe_pointcloud_topic", subscribe_pointcloud_topic_, std::string("/shoulder_cloud"));
00324   pnh_->param("max_number_of_iterations_icp", max_number_of_iterations_icp_, 50);
00325   pnh_->param("max_nn_icp", max_nn_icp_, 100);
00326   pnh_->param("max_nn_overlap", max_nn_overlap_, 10);
00327   pnh_->param("radius_icp", radius_icp_, 0.05);
00328   pnh_->param("radius_overlap", radius_overlap_, 0.05);
00329   pnh_->param("curvature_check", curvature_check_, true);
00330   pnh_->param("downsample_pointcloud_before", downsample_pointcloud_before_, false);
00331   pnh_->param("downsample_pointcloud_after", downsample_pointcloud_after_, false);
00332   pnh_->param("filter_outliers", filter_outliers_, true);
00333   pnh_->param("downsample_leafsize", downsample_leafsize_, 0.05);
00334   pnh_->param("epsilon_z", epsilon_z_, 0.001);
00335   pnh_->param("epsilon_curvature", epsilon_curvature_, 0.001);
00336   pnh_->param("epsilon_transformation", epsilon_transformation_, 1e-6);
00337   pnh_->param("field", field_, std::string("z"));
00338 
00339   firstCloudReceived_ = false;
00340   secondCloudReceived_ = false;
00341 
00342   pointcloud_subscriber_ = pnh_->subscribe(subscribe_pointcloud_topic_, 100, &PointCloudRegistration::pointcloudRegistrationCallBack, this);
00343   pointcloud_merged_publisher_ = pnh_->advertise<sensor_msgs::PointCloud2>(merged_pointcloud_topic_, 100);
00344 
00345   scan_index_ = 0;
00346   icp_.setMaximumIterations(max_number_of_iterations_icp_);
00347   icp_.setTransformationEpsilon(epsilon_transformation_);
00348   icp_.setParameters(radius_icp_, max_nn_icp_, epsilon_z_, epsilon_curvature_, curvature_check_, field_);
00349   ROS_INFO("pointcloud_registration node is up and running.");
00350 
00351   ros::spin();
00352 }
00353 
00355 PointCloudRegistration::PointCloudRegistration()
00356 {
00357 
00358 }
00359 PointCloudRegistration::~PointCloudRegistration()
00360 {
00361   ROS_INFO("Shutting down pointcloud_registration node!.");
00362 }
00363 
00365 
00366 void PointCloudRegistration::pointcloudRegistrationCallBack(const sensor_msgs::PointCloud& pointcloud_msg)
00367 {
00368   frame_id_ = pointcloud_msg.header.frame_id;
00369   start = time(NULL);
00370   if( firstCloudReceived_ == false)
00371   {
00372     pointcloud2_current_ = convertFromMsgToPointCloud(pointcloud_msg);
00373     ROS_INFO("Size of point cloud received = %d", (int) pointcloud2_current_.points.size());
00374     firstCloudReceived_ = true;
00375     ROS_INFO("Received first point cloud.");
00376     kdtree_.setInputCloud(boost::make_shared< pcl::PointCloud < pcl::PointXYZINormal> > (pointcloud2_current_));
00377 
00378     pointcloud2_merged_ = pointcloud2_current_;
00379   }
00380   else if( secondCloudReceived_ == false)
00381   {
00382     ROS_INFO("Received second point cloud.");
00383     secondCloudReceived_ = true;
00384     pointcloud2_current_ = convertFromMsgToPointCloud(pointcloud_msg);
00385     ROS_INFO("converted point cloud from message.. computing overlap transform");
00386 
00387     //Now we get the transformation from the overlapped regions of the 2 point clouds
00388     final_transformation_= getOverlapTransformation();
00389     ROS_INFO("overlap tranform found, transforming now");
00390 
00391     pcl::transformPointCloud(pointcloud2_current_, pointcloud2_transformed_, final_transformation_);
00392     pointcloud2_merged_ += pointcloud2_transformed_;
00393 
00394   }
00395   else
00396   {
00397     ROS_INFO("Received point cloud.");
00398     pointcloud2_current_ = convertFromMsgToPointCloud(pointcloud_msg);
00399     kdtree_.setInputCloud(boost::make_shared< pcl::PointCloud < pcl::PointXYZINormal> > (pointcloud2_merged_));
00400 
00401     //Now we get the transformation from the overlapped regions of the 2 point clouds
00402     final_transformation_= getOverlapTransformation();
00403     pcl::transformPointCloud(pointcloud2_current_, pointcloud2_transformed_, final_transformation_);
00404 
00405     pointcloud2_merged_ += pointcloud2_transformed_;
00406   }
00407 
00408   publishPointCloud(pointcloud2_merged_);
00409   end = time(NULL);
00410   ROS_INFO("Time taken: %d seconds", (int)(end - start));
00411 
00412 }
00413 }
00415  PLUGINLIB_DECLARE_CLASS(pointcloud_registration,PointCloudRegistration,pointcloud_registration::PointCloudRegistration,nodelet::Nodelet);
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pointcloud_registration
Author(s): Hozefa Indorewala
autogenerated on Sun Oct 6 2013 11:55:57