pairwise_incremental_registration.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, 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 Willow Garage, Inc. 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  * $Id$
00035  *
00036  */
00037 
00038 /* \author Radu Bogdan Rusu
00039  * adaptation Raphael Favier*/
00040 
00041 #include <boost/make_shared.hpp>
00042 #include <pcl/point_types.h>
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/point_representation.h>
00045 
00046 #include <pcl/io/pcd_io.h>
00047 
00048 #include <pcl/filters/voxel_grid.h>
00049 #include <pcl/filters/filter.h>
00050 
00051 #include <pcl/features/normal_3d.h>
00052 
00053 #include <pcl/registration/icp.h>
00054 #include <pcl/registration/icp_nl.h>
00055 #include <pcl/registration/transforms.h>
00056 
00057 #include <pcl/visualization/pcl_visualizer.h>
00058 
00059 using pcl::visualization::PointCloudColorHandlerGenericField;
00060 using pcl::visualization::PointCloudColorHandlerCustom;
00061 
00062 //convenient typedefs
00063 typedef pcl::PointXYZ PointT;
00064 typedef pcl::PointCloud<PointT> PointCloud;
00065 typedef pcl::PointNormal PointNormalT;
00066 typedef pcl::PointCloud<PointNormalT> PointCloudWithNormals;
00067 
00068 // This is a tutorial so we can afford having global variables 
00069         //our visualizer
00070         pcl::visualization::PCLVisualizer *p;
00071         //its left and right viewports
00072         int vp_1, vp_2;
00073 
00074 //convenient structure to handle our pointclouds
00075 struct PCD
00076 {
00077   PointCloud::Ptr cloud;
00078   std::string f_name;
00079 
00080   PCD() : cloud (new PointCloud) {};
00081 };
00082 
00083 struct PCDComparator
00084 {
00085   bool operator () (const PCD& p1, const PCD& p2)
00086   {
00087     return (p1.f_name < p2.f_name);
00088   }
00089 };
00090 
00091 
00092 // Define a new point representation for < x, y, z, curvature >
00093 class MyPointRepresentation : public pcl::PointRepresentation <PointNormalT>
00094 {
00095   using pcl::PointRepresentation<PointNormalT>::nr_dimensions_;
00096 public:
00097   MyPointRepresentation ()
00098   {
00099     // Define the number of dimensions
00100     nr_dimensions_ = 4;
00101   }
00102 
00103   // Override the copyToFloatArray method to define our feature vector
00104   virtual void copyToFloatArray (const PointNormalT &p, float * out) const
00105   {
00106     // < x, y, z, curvature >
00107     out[0] = p.x;
00108     out[1] = p.y;
00109     out[2] = p.z;
00110     out[3] = p.curvature;
00111   }
00112 };
00113 
00114 
00116 
00119 void showCloudsLeft(const PointCloud::Ptr cloud_target, const PointCloud::Ptr cloud_source)
00120 {
00121   p->removePointCloud ("vp1_target");
00122   p->removePointCloud ("vp1_source");
00123 
00124   PointCloudColorHandlerCustom<PointT> tgt_h (cloud_target, 0, 255, 0);
00125   PointCloudColorHandlerCustom<PointT> src_h (cloud_source, 255, 0, 0);
00126   p->addPointCloud (cloud_target, tgt_h, "vp1_target", vp_1);
00127   p->addPointCloud (cloud_source, src_h, "vp1_source", vp_1);
00128 
00129   PCL_INFO ("Press q to begin the registration.\n");
00130   p-> spin();
00131 }
00132 
00133 
00135 
00138 void showCloudsRight(const PointCloudWithNormals::Ptr cloud_target, const PointCloudWithNormals::Ptr cloud_source)
00139 {
00140   p->removePointCloud ("source");
00141   p->removePointCloud ("target");
00142 
00143 
00144   PointCloudColorHandlerGenericField<PointNormalT> tgt_color_handler (cloud_target, "curvature");
00145   if (!tgt_color_handler.isCapable ())
00146       PCL_WARN ("Cannot create curvature color handler!");
00147 
00148   PointCloudColorHandlerGenericField<PointNormalT> src_color_handler (cloud_source, "curvature");
00149   if (!src_color_handler.isCapable ())
00150       PCL_WARN ("Cannot create curvature color handler!");
00151 
00152 
00153   p->addPointCloud (cloud_target, tgt_color_handler, "target", vp_2);
00154   p->addPointCloud (cloud_source, src_color_handler, "source", vp_2);
00155 
00156   p->spinOnce();
00157 }
00158 
00160 
00165 void loadData (int argc, char **argv, std::vector<PCD, Eigen::aligned_allocator<PCD> > &models)
00166 {
00167   std::string extension (".pcd");
00168   // Suppose the first argument is the actual test model
00169   for (int i = 1; i < argc; i++)
00170   {
00171     std::string fname = std::string (argv[i]);
00172     // Needs to be at least 5: .plot
00173     if (fname.size () <= extension.size ())
00174       continue;
00175 
00176     std::transform (fname.begin (), fname.end (), fname.begin (), (int(*)(int))tolower);
00177 
00178     //check that the argument is a pcd file
00179     if (fname.compare (fname.size () - extension.size (), extension.size (), extension) == 0)
00180     {
00181       // Load the cloud and saves it into the global list of models
00182       PCD m;
00183       m.f_name = argv[i];
00184       pcl::io::loadPCDFile (argv[i], *m.cloud);
00185       //remove NAN points from the cloud
00186       std::vector<int> indices;
00187       pcl::removeNaNFromPointCloud(*m.cloud,*m.cloud, indices);
00188 
00189       models.push_back (m);
00190     }
00191   }
00192 }
00193 
00194 
00196 
00202 void pairAlign (const PointCloud::Ptr cloud_src, const PointCloud::Ptr cloud_tgt, PointCloud::Ptr output, Eigen::Matrix4f &final_transform, bool downsample = false)
00203 {
00204   //
00205   // Downsample for consistency and speed
00206   // \note enable this for large datasets
00207   PointCloud::Ptr src (new PointCloud);
00208   PointCloud::Ptr tgt (new PointCloud);
00209   pcl::VoxelGrid<PointT> grid;
00210   if (downsample)
00211   {
00212     grid.setLeafSize (0.05, 0.05, 0.05);
00213     grid.setInputCloud (cloud_src);
00214     grid.filter (*src);
00215 
00216     grid.setInputCloud (cloud_tgt);
00217     grid.filter (*tgt);
00218   }
00219   else
00220   {
00221     src = cloud_src;
00222     tgt = cloud_tgt;
00223   }
00224 
00225 
00226   // Compute surface normals and curvature
00227   PointCloudWithNormals::Ptr points_with_normals_src (new PointCloudWithNormals);
00228   PointCloudWithNormals::Ptr points_with_normals_tgt (new PointCloudWithNormals);
00229 
00230   pcl::NormalEstimation<PointT, PointNormalT> norm_est;
00231   pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());
00232   norm_est.setSearchMethod (tree);
00233   norm_est.setKSearch (30);
00234   
00235   norm_est.setInputCloud (src);
00236   norm_est.compute (*points_with_normals_src);
00237   pcl::copyPointCloud (*src, *points_with_normals_src);
00238 
00239   norm_est.setInputCloud (tgt);
00240   norm_est.compute (*points_with_normals_tgt);
00241   pcl::copyPointCloud (*tgt, *points_with_normals_tgt);
00242 
00243   //
00244   // Instantiate our custom point representation (defined above) ...
00245   MyPointRepresentation point_representation;
00246   // ... and weight the 'curvature' dimension so that it is balanced against x, y, and z
00247   float alpha[4] = {1.0, 1.0, 1.0, 1.0};
00248   point_representation.setRescaleValues (alpha);
00249 
00250   //
00251   // Align
00252   pcl::IterativeClosestPointNonLinear<PointNormalT, PointNormalT> reg;
00253   reg.setTransformationEpsilon (1e-6);
00254   // Set the maximum distance between two correspondences (src<->tgt) to 10cm
00255   // Note: adjust this based on the size of your datasets
00256   reg.setMaxCorrespondenceDistance (0.1);  
00257   // Set the point representation
00258   reg.setPointRepresentation (boost::make_shared<const MyPointRepresentation> (point_representation));
00259 
00260   reg.setInputCloud (points_with_normals_src);
00261   reg.setInputTarget (points_with_normals_tgt);
00262 
00263 
00264 
00265   //
00266   // Run the same optimization in a loop and visualize the results
00267   Eigen::Matrix4f Ti = Eigen::Matrix4f::Identity (), prev, targetToSource;
00268   PointCloudWithNormals::Ptr reg_result = points_with_normals_src;
00269   reg.setMaximumIterations (2);
00270   for (int i = 0; i < 30; ++i)
00271   {
00272     PCL_INFO ("Iteration Nr. %d.\n", i);
00273 
00274     // save cloud for visualization purpose
00275     points_with_normals_src = reg_result;
00276 
00277     // Estimate
00278     reg.setInputCloud (points_with_normals_src);
00279     reg.align (*reg_result);
00280 
00281                 //accumulate transformation between each Iteration
00282     Ti = reg.getFinalTransformation () * Ti;
00283 
00284                 //if the difference between this transformation and the previous one
00285                 //is smaller than the threshold, refine the process by reducing
00286                 //the maximal correspondence distance
00287     if (fabs ((reg.getLastIncrementalTransformation () - prev).sum ()) < reg.getTransformationEpsilon ())
00288       reg.setMaxCorrespondenceDistance (reg.getMaxCorrespondenceDistance () - 0.001);
00289     
00290     prev = reg.getLastIncrementalTransformation ();
00291 
00292     // visualize current state
00293     showCloudsRight(points_with_normals_tgt, points_with_normals_src);
00294   }
00295 
00296         //
00297   // Get the transformation from target to source
00298   targetToSource = Ti.inverse();
00299 
00300   //
00301   // Transform target back in source frame
00302   pcl::transformPointCloud (*cloud_tgt, *output, targetToSource);
00303 
00304   p->removePointCloud ("source");
00305   p->removePointCloud ("target");
00306 
00307   PointCloudColorHandlerCustom<PointT> cloud_tgt_h (output, 0, 255, 0);
00308   PointCloudColorHandlerCustom<PointT> cloud_src_h (cloud_src, 255, 0, 0);
00309   p->addPointCloud (output, cloud_tgt_h, "target", vp_2);
00310   p->addPointCloud (cloud_src, cloud_src_h, "source", vp_2);
00311 
00312         PCL_INFO ("Press q to continue the registration.\n");
00313   p->spin ();
00314 
00315   p->removePointCloud ("source"); 
00316   p->removePointCloud ("target");
00317 
00318   //add the source to the transformed target
00319   *output += *cloud_src;
00320   
00321   final_transform = targetToSource;
00322  }
00323 
00324 
00325 /* ---[ */
00326 int main (int argc, char** argv)
00327 {
00328   // Load data
00329   std::vector<PCD, Eigen::aligned_allocator<PCD> > data;
00330   loadData (argc, argv, data);
00331 
00332   // Check user input
00333   if (data.empty ())
00334   {
00335     PCL_ERROR ("Syntax is: %s <source.pcd> <target.pcd> [*]", argv[0]);
00336     PCL_ERROR ("[*] - multiple files can be added. The registration results of (i, i+1) will be registered against (i+2), etc");
00337     return (-1);
00338   }
00339   PCL_INFO ("Loaded %d datasets.", (int)data.size ());
00340   
00341   // Create a PCLVisualizer object
00342   p = new pcl::visualization::PCLVisualizer (argc, argv, "Pairwise Incremental Registration example");
00343   p->createViewPort (0.0, 0, 0.5, 1.0, vp_1);
00344   p->createViewPort (0.5, 0, 1.0, 1.0, vp_2);
00345 
00346         PointCloud::Ptr result (new PointCloud), source, target;
00347   Eigen::Matrix4f GlobalTransform = Eigen::Matrix4f::Identity (), pairTransform;
00348   
00349   for (size_t i = 1; i < data.size (); ++i)
00350   {
00351     source = data[i-1].cloud;
00352     target = data[i].cloud;
00353 
00354     // Add visualization data
00355     showCloudsLeft(source, target);
00356 
00357     PointCloud::Ptr temp (new PointCloud);
00358     PCL_INFO ("Aligning %s (%d) with %s (%d).\n", data[i-1].f_name.c_str (), source->points.size (), data[i].f_name.c_str (), target->points.size ());
00359     pairAlign (source, target, temp, pairTransform, true);
00360 
00361     //transform current pair into the global transform
00362     pcl::transformPointCloud (*temp, *result, GlobalTransform);
00363 
00364     //update the global transform
00365     GlobalTransform = pairTransform * GlobalTransform;
00366 
00367                 //save aligned pair, transformed into the first cloud's frame
00368     std::stringstream ss;
00369     ss << i << ".pcd";
00370     pcl::io::savePCDFile (ss.str (), *result, true);
00371 
00372   }
00373 }
00374 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:33