util3d_registration.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
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     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap/core/util3d_registration.h"
00029 
00030 #include "rtabmap/core/util3d_transforms.h"
00031 #include "rtabmap/core/util3d_filtering.h"
00032 #include "rtabmap/core/util3d.h"
00033 
00034 #include <pcl/registration/icp.h>
00035 #include <pcl/registration/transformation_estimation_2D.h>
00036 #include <pcl/registration/transformation_estimation_svd.h>
00037 #include <pcl/sample_consensus/sac_model_registration.h>
00038 #include <pcl/sample_consensus/ransac.h>
00039 #include <rtabmap/utilite/ULogger.h>
00040 
00041 namespace rtabmap
00042 {
00043 
00044 namespace util3d
00045 {
00046 
00047 // Get transform from cloud2 to cloud1
00048 Transform transformFromXYZCorrespondencesSVD(
00049         const pcl::PointCloud<pcl::PointXYZ> & cloud1,
00050         const pcl::PointCloud<pcl::PointXYZ> & cloud2)
00051 {
00052         pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ> svd;
00053 
00054         // Perform the alignment
00055         Eigen::Matrix4f matrix;
00056         svd.estimateRigidTransformation(cloud1, cloud2, matrix);
00057         return Transform::fromEigen4f(matrix);
00058 }
00059 
00060 // Get transform from cloud2 to cloud1
00061 Transform transformFromXYZCorrespondences(
00062                 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud1,
00063                 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud2,
00064                 double inlierThreshold,
00065                 int iterations,
00066                 int refineIterations,
00067                 double refineSigma,
00068                 std::vector<int> * inliersOut,
00069                 double * varianceOut)
00070 {
00071         //NOTE: this method is a mix of two methods:
00072         //  - getRemainingCorrespondences() in pcl/registration/impl/correspondence_rejection_sample_consensus.hpp
00073         //  - refineModel() in pcl/sample_consensus/sac.h
00074 
00075         if(varianceOut)
00076         {
00077                 *varianceOut = 1.0;
00078         }
00079         Transform transform;
00080         if(cloud1->size() >=3 && cloud1->size() == cloud2->size())
00081         {
00082                 // RANSAC
00083                 UDEBUG("iterations=%d inlierThreshold=%f", iterations, inlierThreshold);
00084                 std::vector<int> source_indices (cloud2->size());
00085                 std::vector<int> target_indices (cloud1->size());
00086 
00087                 // Copy the query-match indices
00088                 for (int i = 0; i < (int)cloud1->size(); ++i)
00089                 {
00090                         source_indices[i] = i;
00091                         target_indices[i] = i;
00092                 }
00093 
00094                 // From the set of correspondences found, attempt to remove outliers
00095                 // Create the registration model
00096                 pcl::SampleConsensusModelRegistration<pcl::PointXYZ>::Ptr model;
00097                 model.reset(new pcl::SampleConsensusModelRegistration<pcl::PointXYZ>(cloud2, source_indices));
00098                 // Pass the target_indices
00099                 model->setInputTarget (cloud1, target_indices);
00100                 // Create a RANSAC model
00101                 pcl::RandomSampleConsensus<pcl::PointXYZ> sac (model, inlierThreshold);
00102                 sac.setMaxIterations(iterations);
00103 
00104                 // Compute the set of inliers
00105                 if(sac.computeModel())
00106                 {
00107                         std::vector<int> inliers;
00108                         Eigen::VectorXf model_coefficients;
00109 
00110                         sac.getInliers(inliers);
00111                         sac.getModelCoefficients (model_coefficients);
00112 
00113                         if (refineIterations>0)
00114                         {
00115                                 double error_threshold = inlierThreshold;
00116                                 int refine_iterations = 0;
00117                                 bool inlier_changed = false, oscillating = false;
00118                                 std::vector<int> new_inliers, prev_inliers = inliers;
00119                                 std::vector<size_t> inliers_sizes;
00120                                 Eigen::VectorXf new_model_coefficients = model_coefficients;
00121                                 do
00122                                 {
00123                                         // Optimize the model coefficients
00124                                         model->optimizeModelCoefficients (prev_inliers, new_model_coefficients, new_model_coefficients);
00125                                         inliers_sizes.push_back (prev_inliers.size ());
00126 
00127                                         // Select the new inliers based on the optimized coefficients and new threshold
00128                                         model->selectWithinDistance (new_model_coefficients, error_threshold, new_inliers);
00129                                         UDEBUG("RANSAC refineModel: Number of inliers found (before/after): %d/%d, with an error threshold of %f.",
00130                                                         (int)prev_inliers.size (), (int)new_inliers.size (), error_threshold);
00131 
00132                                         if (new_inliers.empty ())
00133                                         {
00134                                                 ++refine_iterations;
00135                                                 if (refine_iterations >= refineIterations)
00136                                                 {
00137                                                         break;
00138                                                 }
00139                                                 continue;
00140                                         }
00141 
00142                                         // Estimate the variance and the new threshold
00143                                         double variance = model->computeVariance ();
00144                                         error_threshold = std::min (inlierThreshold, refineSigma * sqrt(variance));
00145 
00146                                         UDEBUG ("RANSAC refineModel: New estimated error threshold: %f (variance=%f) on iteration %d out of %d.",
00147                                                   error_threshold, variance, refine_iterations, refineIterations);
00148                                         inlier_changed = false;
00149                                         std::swap (prev_inliers, new_inliers);
00150 
00151                                         // If the number of inliers changed, then we are still optimizing
00152                                         if (new_inliers.size () != prev_inliers.size ())
00153                                         {
00154                                                 // Check if the number of inliers is oscillating in between two values
00155                                                 if (inliers_sizes.size () >= 4)
00156                                                 {
00157                                                         if (inliers_sizes[inliers_sizes.size () - 1] == inliers_sizes[inliers_sizes.size () - 3] &&
00158                                                         inliers_sizes[inliers_sizes.size () - 2] == inliers_sizes[inliers_sizes.size () - 4])
00159                                                         {
00160                                                                 oscillating = true;
00161                                                                 break;
00162                                                         }
00163                                                 }
00164                                                 inlier_changed = true;
00165                                                 continue;
00166                                         }
00167 
00168                                         // Check the values of the inlier set
00169                                         for (size_t i = 0; i < prev_inliers.size (); ++i)
00170                                         {
00171                                                 // If the value of the inliers changed, then we are still optimizing
00172                                                 if (prev_inliers[i] != new_inliers[i])
00173                                                 {
00174                                                         inlier_changed = true;
00175                                                         break;
00176                                                 }
00177                                         }
00178                                 }
00179                                 while (inlier_changed && ++refine_iterations < refineIterations);
00180 
00181                                 // If the new set of inliers is empty, we didn't do a good job refining
00182                                 if (new_inliers.empty ())
00183                                 {
00184                                         UWARN ("RANSAC refineModel: Refinement failed: got an empty set of inliers!");
00185                                 }
00186 
00187                                 if (oscillating)
00188                                 {
00189                                         UDEBUG("RANSAC refineModel: Detected oscillations in the model refinement.");
00190                                 }
00191 
00192                                 std::swap (inliers, new_inliers);
00193                                 model_coefficients = new_model_coefficients;
00194                         }
00195 
00196                         if (inliers.size() >= 3)
00197                         {
00198                                 if(inliersOut)
00199                                 {
00200                                         *inliersOut = inliers;
00201                                 }
00202                                 if(varianceOut)
00203                                 {
00204                                         *varianceOut = model->computeVariance();
00205                                 }
00206 
00207                                 // get best transformation
00208                                 Eigen::Matrix4f bestTransformation;
00209                                 bestTransformation.row (0) = model_coefficients.segment<4>(0);
00210                                 bestTransformation.row (1) = model_coefficients.segment<4>(4);
00211                                 bestTransformation.row (2) = model_coefficients.segment<4>(8);
00212                                 bestTransformation.row (3) = model_coefficients.segment<4>(12);
00213 
00214                                 transform = Transform::fromEigen4f(bestTransformation);
00215                                 UDEBUG("RANSAC inliers=%d/%d tf=%s", (int)inliers.size(), (int)cloud1->size(), transform.prettyPrint().c_str());
00216 
00217                                 return transform.inverse(); // inverse to get actual pose transform (not correspondences transform)
00218                         }
00219                         else
00220                         {
00221                                 UDEBUG("RANSAC: Model with inliers < 3");
00222                         }
00223                 }
00224                 else
00225                 {
00226                         UDEBUG("RANSAC: Failed to find model");
00227                 }
00228         }
00229         else
00230         {
00231                 UDEBUG("Not enough points to compute the transform");
00232         }
00233         return Transform();
00234 }
00235 
00236 void computeVarianceAndCorrespondences(
00237                 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudA,
00238                 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudB,
00239                 double maxCorrespondenceDistance,
00240                 double & variance,
00241                 int & correspondencesOut)
00242 {
00243         variance = 1;
00244         correspondencesOut = 0;
00245         pcl::registration::CorrespondenceEstimation<pcl::PointNormal, pcl::PointNormal>::Ptr est;
00246         est.reset(new pcl::registration::CorrespondenceEstimation<pcl::PointNormal, pcl::PointNormal>);
00247         est->setInputTarget(cloudB);
00248         est->setInputSource(cloudA);
00249         pcl::Correspondences correspondences;
00250         est->determineCorrespondences(correspondences, maxCorrespondenceDistance);
00251 
00252         if(correspondences.size()>=3)
00253         {
00254                 std::vector<double> distances(correspondences.size());
00255                 for(unsigned int i=0; i<correspondences.size(); ++i)
00256                 {
00257                         distances[i] = correspondences[i].distance;
00258                 }
00259 
00260                 //variance
00261                 std::sort(distances.begin (), distances.end ());
00262                 double median_error_sqr = distances[distances.size () >> 1];
00263                 variance = (2.1981 * median_error_sqr);
00264         }
00265 
00266         correspondencesOut = (int)correspondences.size();
00267 }
00268 
00269 void computeVarianceAndCorrespondences(
00270                 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudA,
00271                 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudB,
00272                 double maxCorrespondenceDistance,
00273                 double & variance,
00274                 int & correspondencesOut)
00275 {
00276         variance = 1;
00277         correspondencesOut = 0;
00278         pcl::registration::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ>::Ptr est;
00279         est.reset(new pcl::registration::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ>);
00280         est->setInputTarget(cloudB);
00281         est->setInputSource(cloudA);
00282         pcl::Correspondences correspondences;
00283         est->determineCorrespondences(correspondences, maxCorrespondenceDistance);
00284 
00285         if(correspondences.size()>=3)
00286         {
00287                 std::vector<double> distances(correspondences.size());
00288                 for(unsigned int i=0; i<correspondences.size(); ++i)
00289                 {
00290                         distances[i] = correspondences[i].distance;
00291                 }
00292 
00293                 //variance
00294                 std::sort(distances.begin (), distances.end ());
00295                 double median_error_sqr = distances[distances.size () >> 1];
00296                 variance = (2.1981 * median_error_sqr);
00297         }
00298 
00299         correspondencesOut = (int)correspondences.size();
00300 }
00301 
00302 // return transform from source to target (All points must be finite!!!)
00303 Transform icp(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
00304                           const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
00305                           double maxCorrespondenceDistance,
00306                           int maximumIterations,
00307                           bool & hasConverged,
00308                           pcl::PointCloud<pcl::PointXYZ> & cloud_source_registered,
00309                           float epsilon,
00310                           bool icp2D)
00311 {
00312         pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> icp;
00313         // Set the input source and target
00314         icp.setInputTarget (cloud_target);
00315         icp.setInputSource (cloud_source);
00316 
00317         if(icp2D)
00318         {
00319                 pcl::registration::TransformationEstimation2D<pcl::PointXYZ, pcl::PointXYZ>::Ptr est;
00320                 est.reset(new pcl::registration::TransformationEstimation2D<pcl::PointXYZ, pcl::PointXYZ>);
00321                 icp.setTransformationEstimation(est);
00322         }
00323 
00324         // Set the max correspondence distance to 5cm (e.g., correspondences with higher distances will be ignored)
00325         icp.setMaxCorrespondenceDistance (maxCorrespondenceDistance);
00326         // Set the maximum number of iterations (criterion 1)
00327         icp.setMaximumIterations (maximumIterations);
00328         // Set the transformation epsilon (criterion 2)
00329         icp.setTransformationEpsilon (epsilon);
00330         // Set the euclidean distance difference epsilon (criterion 3)
00331         //icp.setEuclideanFitnessEpsilon (1);
00332         //icp.setRANSACOutlierRejectionThreshold(maxCorrespondenceDistance);
00333 
00334         // Perform the alignment
00335         icp.align (cloud_source_registered);
00336         hasConverged = icp.hasConverged();
00337         return Transform::fromEigen4f(icp.getFinalTransformation());
00338 }
00339 
00340 // return transform from source to target (All points/normals must be finite!!!)
00341 Transform icpPointToPlane(
00342                 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_source,
00343                 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_target,
00344                 double maxCorrespondenceDistance,
00345                 int maximumIterations,
00346                 bool & hasConverged,
00347                 pcl::PointCloud<pcl::PointNormal> & cloud_source_registered,
00348                 float epsilon,
00349                 bool icp2D)
00350 {
00351         pcl::IterativeClosestPoint<pcl::PointNormal, pcl::PointNormal> icp;
00352         // Set the input source and target
00353         icp.setInputTarget (cloud_target);
00354         icp.setInputSource (cloud_source);
00355 
00356         if(icp2D)
00357         {
00358                 pcl::registration::TransformationEstimation2D<pcl::PointNormal, pcl::PointNormal>::Ptr est;
00359                 est.reset(new pcl::registration::TransformationEstimation2D<pcl::PointNormal, pcl::PointNormal>);
00360                 icp.setTransformationEstimation(est);
00361         }
00362 
00363         pcl::registration::TransformationEstimationPointToPlaneLLS<pcl::PointNormal, pcl::PointNormal>::Ptr est;
00364         est.reset(new pcl::registration::TransformationEstimationPointToPlaneLLS<pcl::PointNormal, pcl::PointNormal>);
00365         icp.setTransformationEstimation(est);
00366 
00367         // Set the max correspondence distance to 5cm (e.g., correspondences with higher distances will be ignored)
00368         icp.setMaxCorrespondenceDistance (maxCorrespondenceDistance);
00369         // Set the maximum number of iterations (criterion 1)
00370         icp.setMaximumIterations (maximumIterations);
00371         // Set the transformation epsilon (criterion 2)
00372         icp.setTransformationEpsilon (epsilon);
00373         // Set the euclidean distance difference epsilon (criterion 3)
00374         //icp.setEuclideanFitnessEpsilon (1);
00375         //icp.setRANSACOutlierRejectionThreshold(maxCorrespondenceDistance);
00376 
00377         // Perform the alignment
00378         icp.align (cloud_source_registered);
00379         hasConverged = icp.hasConverged();
00380         return Transform::fromEigen4f(icp.getFinalTransformation());
00381 }
00382 
00383 }
00384 
00385 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:28