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 <pcl/common/common.h>
00040 #include <rtabmap/utilite/ULogger.h>
00041 #include <rtabmap/utilite/UMath.h>
00042 
00043 namespace rtabmap
00044 {
00045 
00046 namespace util3d
00047 {
00048 
00049 // Get transform from cloud2 to cloud1
00050 Transform transformFromXYZCorrespondencesSVD(
00051         const pcl::PointCloud<pcl::PointXYZ> & cloud1,
00052         const pcl::PointCloud<pcl::PointXYZ> & cloud2)
00053 {
00054         pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ> svd;
00055 
00056         // Perform the alignment
00057         Eigen::Matrix4f matrix;
00058         svd.estimateRigidTransformation(cloud1, cloud2, matrix);
00059         return Transform::fromEigen4f(matrix);
00060 }
00061 
00062 // Get transform from cloud2 to cloud1
00063 Transform transformFromXYZCorrespondences(
00064                 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud1,
00065                 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud2,
00066                 double inlierThreshold,
00067                 int iterations,
00068                 int refineIterations,
00069                 double refineSigma,
00070                 std::vector<int> * inliersOut,
00071                 cv::Mat * covariance)
00072 {
00073         //NOTE: this method is a mix of two methods:
00074         //  - getRemainingCorrespondences() in pcl/registration/impl/correspondence_rejection_sample_consensus.hpp
00075         //  - refineModel() in pcl/sample_consensus/sac.h
00076 
00077         if(covariance)
00078         {
00079                 *covariance = cv::Mat::eye(6,6,CV_64FC1);
00080         }
00081         Transform transform;
00082         if(cloud1->size() >=3 && cloud1->size() == cloud2->size())
00083         {
00084                 // RANSAC
00085                 UDEBUG("iterations=%d inlierThreshold=%f", iterations, inlierThreshold);
00086                 std::vector<int> source_indices (cloud2->size());
00087                 std::vector<int> target_indices (cloud1->size());
00088 
00089                 // Copy the query-match indices
00090                 for (int i = 0; i < (int)cloud1->size(); ++i)
00091                 {
00092                         source_indices[i] = i;
00093                         target_indices[i] = i;
00094                 }
00095 
00096                 // From the set of correspondences found, attempt to remove outliers
00097                 // Create the registration model
00098                 pcl::SampleConsensusModelRegistration<pcl::PointXYZ>::Ptr model;
00099                 model.reset(new pcl::SampleConsensusModelRegistration<pcl::PointXYZ>(cloud2, source_indices));
00100                 // Pass the target_indices
00101                 model->setInputTarget (cloud1, target_indices);
00102                 // Create a RANSAC model
00103                 pcl::RandomSampleConsensus<pcl::PointXYZ> sac (model, inlierThreshold);
00104                 sac.setMaxIterations(iterations);
00105 
00106                 // Compute the set of inliers
00107                 if(sac.computeModel())
00108                 {
00109                         std::vector<int> inliers;
00110                         Eigen::VectorXf model_coefficients;
00111 
00112                         sac.getInliers(inliers);
00113                         sac.getModelCoefficients (model_coefficients);
00114 
00115                         if (refineIterations>0)
00116                         {
00117                                 double error_threshold = inlierThreshold;
00118                                 int refine_iterations = 0;
00119                                 bool inlier_changed = false, oscillating = false;
00120                                 std::vector<int> new_inliers, prev_inliers = inliers;
00121                                 std::vector<size_t> inliers_sizes;
00122                                 Eigen::VectorXf new_model_coefficients = model_coefficients;
00123                                 do
00124                                 {
00125                                         // Optimize the model coefficients
00126                                         model->optimizeModelCoefficients (prev_inliers, new_model_coefficients, new_model_coefficients);
00127                                         inliers_sizes.push_back (prev_inliers.size ());
00128 
00129                                         // Select the new inliers based on the optimized coefficients and new threshold
00130                                         model->selectWithinDistance (new_model_coefficients, error_threshold, new_inliers);
00131                                         UDEBUG("RANSAC refineModel: Number of inliers found (before/after): %d/%d, with an error threshold of %f.",
00132                                                         (int)prev_inliers.size (), (int)new_inliers.size (), error_threshold);
00133 
00134                                         if (new_inliers.empty ())
00135                                         {
00136                                                 ++refine_iterations;
00137                                                 if (refine_iterations >= refineIterations)
00138                                                 {
00139                                                         break;
00140                                                 }
00141                                                 continue;
00142                                         }
00143 
00144                                         // Estimate the variance and the new threshold
00145                                         double variance = model->computeVariance ();
00146                                         error_threshold = std::min (inlierThreshold, refineSigma * sqrt(variance));
00147 
00148                                         UDEBUG ("RANSAC refineModel: New estimated error threshold: %f (variance=%f) on iteration %d out of %d.",
00149                                                   error_threshold, variance, refine_iterations, refineIterations);
00150                                         inlier_changed = false;
00151                                         std::swap (prev_inliers, new_inliers);
00152 
00153                                         // If the number of inliers changed, then we are still optimizing
00154                                         if (new_inliers.size () != prev_inliers.size ())
00155                                         {
00156                                                 // Check if the number of inliers is oscillating in between two values
00157                                                 if (inliers_sizes.size () >= 4)
00158                                                 {
00159                                                         if (inliers_sizes[inliers_sizes.size () - 1] == inliers_sizes[inliers_sizes.size () - 3] &&
00160                                                         inliers_sizes[inliers_sizes.size () - 2] == inliers_sizes[inliers_sizes.size () - 4])
00161                                                         {
00162                                                                 oscillating = true;
00163                                                                 break;
00164                                                         }
00165                                                 }
00166                                                 inlier_changed = true;
00167                                                 continue;
00168                                         }
00169 
00170                                         // Check the values of the inlier set
00171                                         for (size_t i = 0; i < prev_inliers.size (); ++i)
00172                                         {
00173                                                 // If the value of the inliers changed, then we are still optimizing
00174                                                 if (prev_inliers[i] != new_inliers[i])
00175                                                 {
00176                                                         inlier_changed = true;
00177                                                         break;
00178                                                 }
00179                                         }
00180                                 }
00181                                 while (inlier_changed && ++refine_iterations < refineIterations);
00182 
00183                                 // If the new set of inliers is empty, we didn't do a good job refining
00184                                 if (new_inliers.empty ())
00185                                 {
00186                                         UWARN ("RANSAC refineModel: Refinement failed: got an empty set of inliers!");
00187                                 }
00188 
00189                                 if (oscillating)
00190                                 {
00191                                         UDEBUG("RANSAC refineModel: Detected oscillations in the model refinement.");
00192                                 }
00193 
00194                                 std::swap (inliers, new_inliers);
00195                                 model_coefficients = new_model_coefficients;
00196                         }
00197 
00198                         if (inliers.size() >= 3)
00199                         {
00200                                 if(inliersOut)
00201                                 {
00202                                         *inliersOut = inliers;
00203                                 }
00204                                 if(covariance)
00205                                 {
00206                                         double variance =  model->computeVariance();
00207                                         UASSERT(uIsFinite(variance));
00208                                         *covariance *= variance;
00209                                 }
00210 
00211                                 // get best transformation
00212                                 Eigen::Matrix4f bestTransformation;
00213                                 bestTransformation.row (0) = model_coefficients.segment<4>(0);
00214                                 bestTransformation.row (1) = model_coefficients.segment<4>(4);
00215                                 bestTransformation.row (2) = model_coefficients.segment<4>(8);
00216                                 bestTransformation.row (3) = model_coefficients.segment<4>(12);
00217 
00218                                 transform = Transform::fromEigen4f(bestTransformation);
00219                                 UDEBUG("RANSAC inliers=%d/%d tf=%s", (int)inliers.size(), (int)cloud1->size(), transform.prettyPrint().c_str());
00220 
00221                                 return transform.inverse(); // inverse to get actual pose transform (not correspondences transform)
00222                         }
00223                         else
00224                         {
00225                                 UDEBUG("RANSAC: Model with inliers < 3");
00226                         }
00227                 }
00228                 else
00229                 {
00230                         UDEBUG("RANSAC: Failed to find model");
00231                 }
00232         }
00233         else
00234         {
00235                 UDEBUG("Not enough points to compute the transform");
00236         }
00237         return Transform();
00238 }
00239 
00240 void computeVarianceAndCorrespondences(
00241                 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudA,
00242                 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudB,
00243                 double maxCorrespondenceDistance,
00244                 double maxCorrespondenceAngle,
00245                 double & variance,
00246                 int & correspondencesOut)
00247 {
00248         variance = 1;
00249         correspondencesOut = 0;
00250         pcl::registration::CorrespondenceEstimation<pcl::PointNormal, pcl::PointNormal>::Ptr est;
00251         est.reset(new pcl::registration::CorrespondenceEstimation<pcl::PointNormal, pcl::PointNormal>);
00252         const pcl::PointCloud<pcl::PointNormal>::ConstPtr & target = cloudA->size()>cloudB->size()?cloudA:cloudB;
00253         const pcl::PointCloud<pcl::PointNormal>::ConstPtr & source = cloudA->size()>cloudB->size()?cloudB:cloudA;
00254         est->setInputTarget(target);
00255         est->setInputSource(source);
00256         pcl::Correspondences correspondences;
00257         est->determineCorrespondences(correspondences, maxCorrespondenceDistance);
00258 
00259         if(correspondences.size())
00260         {
00261                 std::vector<double> distances(correspondences.size());
00262                 correspondencesOut = 0;
00263                 for(unsigned int i=0; i<correspondences.size(); ++i)
00264                 {
00265                         distances[i] = correspondences[i].distance;
00266                         if(maxCorrespondenceAngle <= 0.0)
00267                         {
00268                                 ++correspondencesOut;
00269                         }
00270                         else
00271                         {
00272                                 Eigen::Vector4f v1(
00273                                                 target->at(correspondences[i].index_match).normal_x,
00274                                                 target->at(correspondences[i].index_match).normal_y,
00275                                                 target->at(correspondences[i].index_match).normal_z,
00276                                                 0);
00277                                 Eigen::Vector4f v2(
00278                                                 source->at(correspondences[i].index_query).normal_x,
00279                                                 source->at(correspondences[i].index_query).normal_y,
00280                                                 source->at(correspondences[i].index_query).normal_z,
00281                                                 0);
00282                                 float angle = pcl::getAngle3D(v1, v2);
00283                                 if(angle < maxCorrespondenceAngle)
00284                                 {
00285                                         ++correspondencesOut;
00286                                 }
00287                         }
00288                 }
00289                 if(correspondencesOut)
00290                 {
00291                         distances.resize(correspondencesOut);
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 }
00300 
00301 void computeVarianceAndCorrespondences(
00302                 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudA,
00303                 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudB,
00304                 double maxCorrespondenceDistance,
00305                 double & variance,
00306                 int & correspondencesOut)
00307 {
00308         variance = 1;
00309         correspondencesOut = 0;
00310         pcl::registration::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ>::Ptr est;
00311         est.reset(new pcl::registration::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ>);
00312         est->setInputTarget(cloudA->size()>cloudB->size()?cloudA:cloudB);
00313         est->setInputSource(cloudA->size()>cloudB->size()?cloudB:cloudA);
00314         pcl::Correspondences correspondences;
00315         est->determineCorrespondences(correspondences, maxCorrespondenceDistance);
00316 
00317         if(correspondences.size()>=3)
00318         {
00319                 std::vector<double> distances(correspondences.size());
00320                 for(unsigned int i=0; i<correspondences.size(); ++i)
00321                 {
00322                         distances[i] = correspondences[i].distance;
00323                 }
00324 
00325                 //variance
00326                 std::sort(distances.begin (), distances.end ());
00327                 double median_error_sqr = distances[distances.size () >> 1];
00328                 variance = (2.1981 * median_error_sqr);
00329         }
00330 
00331         correspondencesOut = (int)correspondences.size();
00332 }
00333 
00334 // return transform from source to target (All points must be finite!!!)
00335 Transform icp(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
00336                           const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
00337                           double maxCorrespondenceDistance,
00338                           int maximumIterations,
00339                           bool & hasConverged,
00340                           pcl::PointCloud<pcl::PointXYZ> & cloud_source_registered,
00341                           float epsilon,
00342                           bool icp2D)
00343 {
00344         pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> icp;
00345         // Set the input source and target
00346         icp.setInputTarget (cloud_target);
00347         icp.setInputSource (cloud_source);
00348 
00349         if(icp2D)
00350         {
00351                 pcl::registration::TransformationEstimation2D<pcl::PointXYZ, pcl::PointXYZ>::Ptr est;
00352                 est.reset(new pcl::registration::TransformationEstimation2D<pcl::PointXYZ, pcl::PointXYZ>);
00353                 icp.setTransformationEstimation(est);
00354         }
00355 
00356         // Set the max correspondence distance to 5cm (e.g., correspondences with higher distances will be ignored)
00357         icp.setMaxCorrespondenceDistance (maxCorrespondenceDistance);
00358         // Set the maximum number of iterations (criterion 1)
00359         icp.setMaximumIterations (maximumIterations);
00360         // Set the transformation epsilon (criterion 2)
00361         icp.setTransformationEpsilon (epsilon*epsilon);
00362         // Set the euclidean distance difference epsilon (criterion 3)
00363         //icp.setEuclideanFitnessEpsilon (1);
00364         //icp.setRANSACOutlierRejectionThreshold(maxCorrespondenceDistance);
00365 
00366         // Perform the alignment
00367         icp.align (cloud_source_registered);
00368         hasConverged = icp.hasConverged();
00369         return Transform::fromEigen4f(icp.getFinalTransformation());
00370 }
00371 
00372 // return transform from source to target (All points/normals must be finite!!!)
00373 Transform icpPointToPlane(
00374                 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_source,
00375                 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_target,
00376                 double maxCorrespondenceDistance,
00377                 int maximumIterations,
00378                 bool & hasConverged,
00379                 pcl::PointCloud<pcl::PointNormal> & cloud_source_registered,
00380                 float epsilon,
00381                 bool icp2D)
00382 {
00383         pcl::IterativeClosestPoint<pcl::PointNormal, pcl::PointNormal> icp;
00384         // Set the input source and target
00385         icp.setInputTarget (cloud_target);
00386         icp.setInputSource (cloud_source);
00387 
00388         pcl::registration::TransformationEstimationPointToPlaneLLS<pcl::PointNormal, pcl::PointNormal>::Ptr est;
00389         est.reset(new pcl::registration::TransformationEstimationPointToPlaneLLS<pcl::PointNormal, pcl::PointNormal>);
00390         icp.setTransformationEstimation(est);
00391 
00392         // Set the max correspondence distance to 5cm (e.g., correspondences with higher distances will be ignored)
00393         icp.setMaxCorrespondenceDistance (maxCorrespondenceDistance);
00394         // Set the maximum number of iterations (criterion 1)
00395         icp.setMaximumIterations (maximumIterations);
00396         // Set the transformation epsilon (criterion 2)
00397         icp.setTransformationEpsilon (epsilon*epsilon);
00398         // Set the euclidean distance difference epsilon (criterion 3)
00399         //icp.setEuclideanFitnessEpsilon (1);
00400         //icp.setRANSACOutlierRejectionThreshold(maxCorrespondenceDistance);
00401 
00402         // Perform the alignment
00403         icp.align (cloud_source_registered);
00404         hasConverged = icp.hasConverged();
00405         Transform t = Transform::fromEigen4f(icp.getFinalTransformation());
00406 
00407         if(icp2D)
00408         {
00409                 // FIXME probably an estimation approach already 2D like in icp() version above exists.
00410                 t = t.to3DoF();
00411         }
00412 
00413         return t;
00414 }
00415 
00416 }
00417 
00418 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:32