iterative_closest_point.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2012-, Open Perception, Inc.
00006  *  
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the copyright holder(s) nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: normal_estimation.cpp 6746 2012-08-08 01:20:30Z rusu $
00037  *
00038  */
00039 
00040 #include <iostream>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/point_types.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/time.h>
00045 #include <pcl/console/parse.h>
00046 #include <pcl/registration/icp.h>
00047 #include <pcl/registration/correspondence_estimation.h>
00048 #include <pcl/registration/correspondence_estimation_normal_shooting.h>
00049 #include <pcl/registration/transformation_estimation_lm.h>
00050 
00051 #include <pcl/registration/correspondence_rejection_one_to_one.h>
00052 #include <pcl/registration/correspondence_rejection_median_distance.h>
00053 #include <pcl/registration/correspondence_rejection_sample_consensus.h>
00054 #include <pcl/registration/correspondence_rejection_trimmed.h>
00055 #include <pcl/registration/correspondence_rejection_var_trimmed.h>
00056 
00057 using namespace pcl;
00058 using namespace pcl::io;
00059 using namespace pcl::console;
00060 using namespace pcl::registration;
00061 
00062 Eigen::Vector4f    translation;
00063 Eigen::Quaternionf orientation;
00064 
00065 void
00066 printHelp (int, char **argv)
00067 {
00068   print_error ("Syntax is: %s input_source.pcd input_target.pcd output.pcd [optional_arguments]\n", argv[0]);
00069 }
00070 
00071 bool
00072 loadCloud (const std::string &filename, pcl::PCLPointCloud2 &cloud)
00073 {
00074   TicToc tt;
00075   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00076 
00077   tt.tic ();
00078   if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00079     return (false);
00080   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00081   print_info ("Available dimensions: "); print_value ("%s\n", getFieldsList (cloud).c_str ());
00082 
00083   return (true);
00084 }
00085 
00086 void
00087 compute (const pcl::PCLPointCloud2::ConstPtr &source,
00088          const pcl::PCLPointCloud2::ConstPtr &target,
00089          pcl::PCLPointCloud2 &transformed_source)
00090 {
00091   // Convert data to PointCloud<T>
00092   PointCloud<PointNormal>::Ptr src (new PointCloud<PointNormal>);
00093   PointCloud<PointNormal>::Ptr tgt (new PointCloud<PointNormal>);
00094   fromPCLPointCloud2 (*source, *src);
00095   fromPCLPointCloud2 (*target, *tgt);
00096 
00097   // Estimate
00098   TicToc tt;
00099   tt.tic ();
00100   
00101   print_highlight (stderr, "Computing ");
00102 
00103 #define Scalar double
00104 //#define Scalar float
00105 
00106   TransformationEstimationLM<PointNormal, PointNormal, Scalar>::Ptr te (new TransformationEstimationLM<PointNormal, PointNormal, Scalar>);
00107   //TransformationEstimationSVD<PointNormal, PointNormal, Scalar>::Ptr te (new TransformationEstimationSVD<PointNormal, PointNormal, Scalar>);
00108   CorrespondenceEstimation<PointNormal, PointNormal, double>::Ptr cens (new CorrespondenceEstimation<PointNormal, PointNormal, double>);
00109   //CorrespondenceEstimationNormalShooting<PointNormal, PointNormal, PointNormal>::Ptr cens (new CorrespondenceEstimationNormalShooting<PointNormal, PointNormal, PointNormal>);
00110   //CorrespondenceEstimationNormalShooting<PointNormal, PointNormal, PointNormal, double>::Ptr cens (new CorrespondenceEstimationNormalShooting<PointNormal, PointNormal, PointNormal, double>);
00111   cens->setInputSource (src);
00112   cens->setInputTarget (tgt);
00113   //cens->setSourceNormals (src);
00114 
00115   CorrespondenceRejectorOneToOne::Ptr cor_rej_o2o (new CorrespondenceRejectorOneToOne);
00116   
00117   CorrespondenceRejectorMedianDistance::Ptr cor_rej_med (new CorrespondenceRejectorMedianDistance);
00118   cor_rej_med->setInputSource<PointNormal> (src);
00119   cor_rej_med->setInputTarget<PointNormal> (tgt);
00120 
00121   CorrespondenceRejectorSampleConsensus<PointNormal>::Ptr cor_rej_sac (new CorrespondenceRejectorSampleConsensus<PointNormal>);
00122   cor_rej_sac->setInputSource (src);
00123   cor_rej_sac->setInputTarget (tgt);
00124   cor_rej_sac->setInlierThreshold (0.005);
00125   cor_rej_sac->setMaximumIterations (10000);
00126 
00127   CorrespondenceRejectorVarTrimmed::Ptr cor_rej_var (new CorrespondenceRejectorVarTrimmed);
00128   cor_rej_var->setInputSource<PointNormal> (src);
00129   cor_rej_var->setInputTarget<PointNormal> (tgt);
00130   
00131   CorrespondenceRejectorTrimmed::Ptr cor_rej_tri (new CorrespondenceRejectorTrimmed);
00132 
00133   IterativeClosestPoint<PointNormal, PointNormal, Scalar> icp;
00134   icp.setCorrespondenceEstimation (cens);
00135   icp.setTransformationEstimation (te);
00136   icp.addCorrespondenceRejector (cor_rej_o2o);
00137   //icp.addCorrespondenceRejector (cor_rej_var);
00138   //icp.addCorrespondenceRejector (cor_rej_med);
00139   //icp.addCorrespondenceRejector (cor_rej_tri);
00140   //icp.addCorrespondenceRejector (cor_rej_sac);
00141   icp.setInputSource (src);
00142   icp.setInputTarget (tgt);
00143   icp.setMaximumIterations (1000);
00144   icp.setTransformationEpsilon (1e-10);
00145   PointCloud<PointNormal> output;
00146   icp.align (output);
00147 
00148   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points], has converged: ");
00149   print_value ("%d", icp.hasConverged ()); print_info (" with score: %f\n",  icp.getFitnessScore ());
00150   Eigen::Matrix4d transformation = icp.getFinalTransformation ();
00151   //Eigen::Matrix4f transformation = icp.getFinalTransformation ();
00152   PCL_DEBUG ("Transformation is:\n\t%5f\t%5f\t%5f\t%5f\n\t%5f\t%5f\t%5f\t%5f\n\t%5f\t%5f\t%5f\t%5f\n\t%5f\t%5f\t%5f\t%5f\n", 
00153       transformation (0, 0), transformation (0, 1), transformation (0, 2), transformation (0, 3),
00154       transformation (1, 0), transformation (1, 1), transformation (1, 2), transformation (1, 3),
00155       transformation (2, 0), transformation (2, 1), transformation (2, 2), transformation (2, 3),
00156       transformation (3, 0), transformation (3, 1), transformation (3, 2), transformation (3, 3));
00157 
00158   // Convert data back
00159   pcl::PCLPointCloud2 output_source;
00160   toPCLPointCloud2 (output, output_source);
00161   concatenateFields (*source, output_source, transformed_source);
00162 }
00163 
00164 void
00165 saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output)
00166 {
00167   TicToc tt;
00168   tt.tic ();
00169 
00170   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00171 
00172   PCDWriter w;
00173   //w.writeBinaryCompressed (filename, output, translation, orientation);
00174   w.writeASCII (filename, output, translation, orientation);
00175   
00176   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00177 }
00178 
00179 int
00180 main (int argc, char** argv)
00181 {
00182   print_info ("Estimate a rigid transformation using IterativeClosestPoint. For more information, use: %s -h\n", argv[0]);
00183 
00184   if (argc < 3)
00185   {
00186     printHelp (argc, argv);
00187     return (-1);
00188   }
00189   
00190   bool debug = false;
00191   pcl::console::parse_argument (argc, argv, "-debug", debug);
00192   if (debug)
00193     pcl::console::setVerbosityLevel (pcl::console::L_DEBUG);
00194 
00195   // Parse the command line arguments for .pcd files
00196   std::vector<int> p_file_indices;
00197   p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00198   if (p_file_indices.size () != 3)
00199   {
00200     print_error ("Need two input PCD files (source, target) and one output PCD file to continue.\n");
00201     return (-1);
00202   }
00203 
00204   // Load the input files
00205   pcl::PCLPointCloud2::Ptr src (new pcl::PCLPointCloud2);
00206   if (!loadCloud (argv[p_file_indices[0]], *src)) return (-1);
00207   pcl::PCLPointCloud2::Ptr tgt (new pcl::PCLPointCloud2);
00208   if (!loadCloud (argv[p_file_indices[1]], *tgt)) return (-1);
00209 
00210   // Perform the feature estimation
00211   pcl::PCLPointCloud2 output;
00212   compute (src, tgt, output);
00213 
00214   // Save into the output file
00215   saveCloud (argv[p_file_indices[2]], output);
00216 
00217   return (0);
00218 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:04