Point Cloud Library (PCL)  1.4.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
icp.hpp
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) 2010-2011, Willow Garage, 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 Willow Garage, Inc. 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: icp.hpp 3503 2011-12-12 06:07:28Z rusu $
00037  *
00038  */
00039 
00040 #include <boost/unordered_map.hpp>
00041 
00043 template <typename PointSource, typename PointTarget> void
00044 pcl::IterativeClosestPoint<PointSource, PointTarget>::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess)
00045 {
00046   // Allocate enough space to hold the results
00047   std::vector<int> nn_indices (1);
00048   std::vector<float> nn_dists (1);
00049 
00050   // Point cloud containing the correspondences of each point in <input, indices>
00051   PointCloudTarget input_corresp;
00052   input_corresp.points.resize (indices_->size ());
00053 
00054   nr_iterations_ = 0;
00055   converged_ = false;
00056   double dist_threshold = corr_dist_threshold_ * corr_dist_threshold_;
00057 
00058   // If the guessed transformation is non identity
00059   if (guess != Eigen::Matrix4f::Identity ())
00060   {
00061     // Initialise final transformation to the guessed one
00062     final_transformation_ = guess;
00063     // Apply guessed transformation prior to search for neighbours
00064     transformPointCloud (output, output, guess);
00065   }
00066 
00067   // Resize the vector of distances between correspondences 
00068   std::vector<float> previous_correspondence_distances (indices_->size ());
00069   correspondence_distances_.resize (indices_->size ());
00070 
00071   while (!converged_)           // repeat until convergence
00072   {
00073     // Save the previously estimated transformation
00074     previous_transformation_ = transformation_;
00075     // And the previous set of distances
00076     previous_correspondence_distances = correspondence_distances_;
00077 
00078     int cnt = 0;
00079     std::vector<int> source_indices (indices_->size ());
00080     std::vector<int> target_indices (indices_->size ());
00081 
00082     // Iterating over the entire index vector and  find all correspondences
00083     for (size_t idx = 0; idx < indices_->size (); ++idx)
00084     {
00085       if (!this->searchForNeighbors (output, (*indices_)[idx], nn_indices, nn_dists))
00086       {
00087         PCL_ERROR ("[pcl::%s::computeTransformation] Unable to find a nearest neighbor in the target dataset for point %d in the source!\n", getClassName ().c_str (), (*indices_)[idx]);
00088         return;
00089       }
00090 
00091       // Check if the distance to the nearest neighbor is smaller than the user imposed threshold
00092       if (nn_dists[0] < dist_threshold)
00093       {
00094         source_indices[cnt] = (*indices_)[idx];
00095         target_indices[cnt] = nn_indices[0];
00096         cnt++;
00097       }
00098 
00099       // Save the nn_dists[0] to a global vector of distances
00100       correspondence_distances_[(*indices_)[idx]] = std::min (nn_dists[0], (float)dist_threshold);
00101     }
00102     if (cnt < min_number_correspondences_)
00103     {
00104       PCL_ERROR ("[pcl::%s::computeTransformation] Not enough correspondences found. Relax your threshold parameters.\n", getClassName ().c_str ());
00105       converged_ = false;
00106       return;
00107     }
00108 
00109     // Resize to the actual number of valid correspondences
00110     source_indices.resize (cnt); target_indices.resize (cnt);
00111 
00112     std::vector<int> source_indices_good;
00113     std::vector<int> target_indices_good;
00114     {
00115       // From the set of correspondences found, attempt to remove outliers
00116       // Create the registration model
00117       typedef typename SampleConsensusModelRegistration<PointSource>::Ptr SampleConsensusModelRegistrationPtr;
00118       SampleConsensusModelRegistrationPtr model;
00119       model.reset (new SampleConsensusModelRegistration<PointSource> (output.makeShared (), source_indices));
00120       // Pass the target_indices
00121       model->setInputTarget (target_, target_indices);
00122       // Create a RANSAC model
00123       RandomSampleConsensus<PointSource> sac (model, inlier_threshold_);
00124       sac.setMaxIterations (1000);
00125 
00126       // Compute the set of inliers
00127       if (!sac.computeModel ())
00128       {
00129         source_indices_good = source_indices;
00130         target_indices_good = target_indices;
00131       }
00132       else
00133       {
00134         std::vector<int> inliers;
00135         // Get the inliers
00136         sac.getInliers (inliers);
00137         source_indices_good.resize (inliers.size ());
00138         target_indices_good.resize (inliers.size ());
00139 
00140         boost::unordered_map<int, int> source_to_target;
00141         for (unsigned int i = 0; i < source_indices.size(); ++i)
00142           source_to_target[source_indices[i]] = target_indices[i];
00143 
00144         // Copy just the inliers
00145         std::copy(inliers.begin(), inliers.end(), source_indices_good.begin());
00146         for (size_t i = 0; i < inliers.size (); ++i)
00147           target_indices_good[i] = source_to_target[inliers[i]];
00148       }
00149     }
00150 
00151     // Check whether we have enough correspondences
00152     cnt = (int)source_indices_good.size ();
00153     if (cnt < min_number_correspondences_)
00154     {
00155       PCL_ERROR ("[pcl::%s::computeTransformation] Not enough correspondences found. Relax your threshold parameters.\n", getClassName ().c_str ());
00156       converged_ = false;
00157       return;
00158     }
00159 
00160     PCL_DEBUG ("[pcl::%s::computeTransformation] Number of correspondences %d [%f%%] out of %lu points [100.0%%], RANSAC rejected: %lu [%f%%].\n", getClassName ().c_str (), cnt, (cnt * 100.0) / indices_->size (), (unsigned long)indices_->size (), (unsigned long)source_indices.size () - cnt, (source_indices.size () - cnt) * 100.0 / source_indices.size ());
00161   
00162     // Estimate the transform
00163     //rigid_transformation_estimation_(output, source_indices_good, *target_, target_indices_good, transformation_);
00164     transformation_estimation_->estimateRigidTransformation (output, source_indices_good, *target_, target_indices_good, transformation_);
00165 
00166     // Tranform the data
00167     transformPointCloud (output, output, transformation_);
00168 
00169     // Obtain the final transformation    
00170     final_transformation_ = transformation_ * final_transformation_;
00171 
00172     nr_iterations_++;
00173 
00174     // Update the vizualization of icp convergence
00175     if (update_visualizer_ != 0)
00176       update_visualizer_(output, source_indices_good, *target_, target_indices_good );
00177 
00178     // Various/Different convergence termination criteria
00179     // 1. Number of iterations has reached the maximum user imposed number of iterations (via 
00180     //    setMaximumIterations)
00181     // 2. The epsilon (difference) between the previous transformation and the current estimated transformation 
00182     //    is smaller than an user imposed value (via setTransformationEpsilon)
00183     // 3. The sum of Euclidean squared errors is smaller than a user defined threshold (via 
00184     //    setEuclideanFitnessEpsilon)
00185 
00186     if (nr_iterations_ >= max_iterations_ ||
00187         fabs ((transformation_ - previous_transformation_).sum ()) < transformation_epsilon_ ||
00188         fabs (this->getFitnessScore (correspondence_distances_, previous_correspondence_distances)) <= euclidean_fitness_epsilon_
00189        )
00190     {
00191       converged_ = true;
00192       PCL_DEBUG ("[pcl::%s::computeTransformation] Convergence reached. Number of iterations: %d out of %d. Transformation difference: %f\n",
00193                  getClassName ().c_str (), nr_iterations_, max_iterations_, fabs ((transformation_ - previous_transformation_).sum ()));
00194 
00195       PCL_DEBUG ("nr_iterations_ (%d) >= max_iterations_ (%d)\n", nr_iterations_, max_iterations_);
00196       PCL_DEBUG ("fabs ((transformation_ - previous_transformation_).sum ()) (%f) < transformation_epsilon_ (%f)\n",
00197                  fabs ((transformation_ - previous_transformation_).sum ()), transformation_epsilon_);
00198       PCL_DEBUG ("fabs (getFitnessScore (correspondence_distances_, previous_correspondence_distances)) (%f) <= euclidean_fitness_epsilon_ (%f)\n",
00199                  fabs (this->getFitnessScore (correspondence_distances_, previous_correspondence_distances)),
00200                  euclidean_fitness_epsilon_);
00201 
00202     }
00203   }
00204 }
00205 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines