util3d_registration.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 
32 #include "rtabmap/core/util3d.h"
33 
34 #include <pcl/registration/icp.h>
35 #include <pcl/registration/transformation_estimation_2D.h>
36 #include <pcl/registration/transformation_estimation_svd.h>
37 #include <pcl/sample_consensus/sac_model_registration.h>
38 #include <pcl/sample_consensus/ransac.h>
39 #include <pcl/common/common.h>
41 #include <rtabmap/utilite/UMath.h>
42 
43 namespace rtabmap
44 {
45 
46 namespace util3d
47 {
48 
49 // Get transform from cloud2 to cloud1
51  const pcl::PointCloud<pcl::PointXYZ> & cloud1,
52  const pcl::PointCloud<pcl::PointXYZ> & cloud2)
53 {
54  pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ> svd;
55 
56  // Perform the alignment
57  Eigen::Matrix4f matrix;
58  svd.estimateRigidTransformation(cloud1, cloud2, matrix);
59  return Transform::fromEigen4f(matrix);
60 }
61 
62 // Get transform from cloud2 to cloud1
64  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud1,
65  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud2,
66  double inlierThreshold,
67  int iterations,
68  int refineIterations,
69  double refineSigma,
70  std::vector<int> * inliersOut,
71  cv::Mat * covariance)
72 {
73  //NOTE: this method is a mix of two methods:
74  // - getRemainingCorrespondences() in pcl/registration/impl/correspondence_rejection_sample_consensus.hpp
75  // - refineModel() in pcl/sample_consensus/sac.h
76 
77  if(covariance)
78  {
79  *covariance = cv::Mat::eye(6,6,CV_64FC1);
80  }
81  Transform transform;
82  if(cloud1->size() >=3 && cloud1->size() == cloud2->size())
83  {
84  // RANSAC
85  UDEBUG("iterations=%d inlierThreshold=%f", iterations, inlierThreshold);
86  std::vector<int> source_indices (cloud2->size());
87  std::vector<int> target_indices (cloud1->size());
88 
89  // Copy the query-match indices
90  for (int i = 0; i < (int)cloud1->size(); ++i)
91  {
92  source_indices[i] = i;
93  target_indices[i] = i;
94  }
95 
96  // From the set of correspondences found, attempt to remove outliers
97  // Create the registration model
98  pcl::SampleConsensusModelRegistration<pcl::PointXYZ>::Ptr model;
99  model.reset(new pcl::SampleConsensusModelRegistration<pcl::PointXYZ>(cloud2, source_indices));
100  // Pass the target_indices
101  model->setInputTarget (cloud1, target_indices);
102  // Create a RANSAC model
103  pcl::RandomSampleConsensus<pcl::PointXYZ> sac (model, inlierThreshold);
104  sac.setMaxIterations(iterations);
105 
106  // Compute the set of inliers
107  if(sac.computeModel())
108  {
109  std::vector<int> inliers;
110  Eigen::VectorXf model_coefficients;
111 
112  sac.getInliers(inliers);
113  sac.getModelCoefficients (model_coefficients);
114 
115  if (refineIterations>0)
116  {
117  double error_threshold = inlierThreshold;
118  int refine_iterations = 0;
119  bool inlier_changed = false, oscillating = false;
120  std::vector<int> new_inliers, prev_inliers = inliers;
121  std::vector<size_t> inliers_sizes;
122  Eigen::VectorXf new_model_coefficients = model_coefficients;
123  do
124  {
125  // Optimize the model coefficients
126  model->optimizeModelCoefficients (prev_inliers, new_model_coefficients, new_model_coefficients);
127  inliers_sizes.push_back (prev_inliers.size ());
128 
129  // Select the new inliers based on the optimized coefficients and new threshold
130  model->selectWithinDistance (new_model_coefficients, error_threshold, new_inliers);
131  UDEBUG("RANSAC refineModel: Number of inliers found (before/after): %d/%d, with an error threshold of %f.",
132  (int)prev_inliers.size (), (int)new_inliers.size (), error_threshold);
133 
134  if (new_inliers.empty ())
135  {
136  ++refine_iterations;
137  if (refine_iterations >= refineIterations)
138  {
139  break;
140  }
141  continue;
142  }
143 
144  // Estimate the variance and the new threshold
145  double variance = model->computeVariance ();
146  error_threshold = std::min (inlierThreshold, refineSigma * sqrt(variance));
147 
148  UDEBUG ("RANSAC refineModel: New estimated error threshold: %f (variance=%f) on iteration %d out of %d.",
149  error_threshold, variance, refine_iterations, refineIterations);
150  inlier_changed = false;
151  std::swap (prev_inliers, new_inliers);
152 
153  // If the number of inliers changed, then we are still optimizing
154  if (new_inliers.size () != prev_inliers.size ())
155  {
156  // Check if the number of inliers is oscillating in between two values
157  if (inliers_sizes.size () >= 4)
158  {
159  if (inliers_sizes[inliers_sizes.size () - 1] == inliers_sizes[inliers_sizes.size () - 3] &&
160  inliers_sizes[inliers_sizes.size () - 2] == inliers_sizes[inliers_sizes.size () - 4])
161  {
162  oscillating = true;
163  break;
164  }
165  }
166  inlier_changed = true;
167  continue;
168  }
169 
170  // Check the values of the inlier set
171  for (size_t i = 0; i < prev_inliers.size (); ++i)
172  {
173  // If the value of the inliers changed, then we are still optimizing
174  if (prev_inliers[i] != new_inliers[i])
175  {
176  inlier_changed = true;
177  break;
178  }
179  }
180  }
181  while (inlier_changed && ++refine_iterations < refineIterations);
182 
183  // If the new set of inliers is empty, we didn't do a good job refining
184  if (new_inliers.empty ())
185  {
186  UWARN ("RANSAC refineModel: Refinement failed: got an empty set of inliers!");
187  }
188 
189  if (oscillating)
190  {
191  UDEBUG("RANSAC refineModel: Detected oscillations in the model refinement.");
192  }
193 
194  std::swap (inliers, new_inliers);
195  model_coefficients = new_model_coefficients;
196  }
197 
198  if (inliers.size() >= 3)
199  {
200  if(inliersOut)
201  {
202  *inliersOut = inliers;
203  }
204  if(covariance)
205  {
206  double variance = model->computeVariance();
207  UASSERT(uIsFinite(variance));
208  *covariance *= variance;
209  }
210 
211  // get best transformation
212  Eigen::Matrix4f bestTransformation;
213  bestTransformation.row (0) = model_coefficients.segment<4>(0);
214  bestTransformation.row (1) = model_coefficients.segment<4>(4);
215  bestTransformation.row (2) = model_coefficients.segment<4>(8);
216  bestTransformation.row (3) = model_coefficients.segment<4>(12);
217 
218  transform = Transform::fromEigen4f(bestTransformation);
219  UDEBUG("RANSAC inliers=%d/%d tf=%s", (int)inliers.size(), (int)cloud1->size(), transform.prettyPrint().c_str());
220 
221  return transform.inverse(); // inverse to get actual pose transform (not correspondences transform)
222  }
223  else
224  {
225  UDEBUG("RANSAC: Model with inliers < 3");
226  }
227  }
228  else
229  {
230  UDEBUG("RANSAC: Failed to find model");
231  }
232  }
233  else
234  {
235  UDEBUG("Not enough points to compute the transform");
236  }
237  return Transform();
238 }
239 
241  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudA,
242  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudB,
243  double maxCorrespondenceDistance,
244  double maxCorrespondenceAngle,
245  double & variance,
246  int & correspondencesOut)
247 {
248  variance = 1;
249  correspondencesOut = 0;
250  pcl::registration::CorrespondenceEstimation<pcl::PointNormal, pcl::PointNormal>::Ptr est;
251  est.reset(new pcl::registration::CorrespondenceEstimation<pcl::PointNormal, pcl::PointNormal>);
252  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & target = cloudA->size()>cloudB->size()?cloudA:cloudB;
253  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & source = cloudA->size()>cloudB->size()?cloudB:cloudA;
254  est->setInputTarget(target);
255  est->setInputSource(source);
256  pcl::Correspondences correspondences;
257  est->determineCorrespondences(correspondences, maxCorrespondenceDistance);
258 
259  if(correspondences.size())
260  {
261  std::vector<double> distances(correspondences.size());
262  correspondencesOut = 0;
263  for(unsigned int i=0; i<correspondences.size(); ++i)
264  {
265  distances[i] = correspondences[i].distance;
266  if(maxCorrespondenceAngle <= 0.0)
267  {
268  ++correspondencesOut;
269  }
270  else
271  {
272  Eigen::Vector4f v1(
273  target->at(correspondences[i].index_match).normal_x,
274  target->at(correspondences[i].index_match).normal_y,
275  target->at(correspondences[i].index_match).normal_z,
276  0);
277  Eigen::Vector4f v2(
278  source->at(correspondences[i].index_query).normal_x,
279  source->at(correspondences[i].index_query).normal_y,
280  source->at(correspondences[i].index_query).normal_z,
281  0);
282  float angle = pcl::getAngle3D(v1, v2);
283  if(angle < maxCorrespondenceAngle)
284  {
285  ++correspondencesOut;
286  }
287  }
288  }
289  if(correspondencesOut)
290  {
291  distances.resize(correspondencesOut);
292 
293  //variance
294  std::sort(distances.begin (), distances.end ());
295  double median_error_sqr = distances[distances.size () >> 1];
296  variance = (2.1981 * median_error_sqr);
297  }
298  }
299 }
300 
302  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudA,
303  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudB,
304  double maxCorrespondenceDistance,
305  double & variance,
306  int & correspondencesOut)
307 {
308  variance = 1;
309  correspondencesOut = 0;
310  pcl::registration::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ>::Ptr est;
311  est.reset(new pcl::registration::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ>);
312  est->setInputTarget(cloudA->size()>cloudB->size()?cloudA:cloudB);
313  est->setInputSource(cloudA->size()>cloudB->size()?cloudB:cloudA);
314  pcl::Correspondences correspondences;
315  est->determineCorrespondences(correspondences, maxCorrespondenceDistance);
316 
317  if(correspondences.size()>=3)
318  {
319  std::vector<double> distances(correspondences.size());
320  for(unsigned int i=0; i<correspondences.size(); ++i)
321  {
322  distances[i] = correspondences[i].distance;
323  }
324 
325  //variance
326  std::sort(distances.begin (), distances.end ());
327  double median_error_sqr = distances[distances.size () >> 1];
328  variance = (2.1981 * median_error_sqr);
329  }
330 
331  correspondencesOut = (int)correspondences.size();
332 }
333 
334 // return transform from source to target (All points must be finite!!!)
335 Transform icp(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
336  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
337  double maxCorrespondenceDistance,
338  int maximumIterations,
339  bool & hasConverged,
340  pcl::PointCloud<pcl::PointXYZ> & cloud_source_registered,
341  float epsilon,
342  bool icp2D)
343 {
344  pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> icp;
345  // Set the input source and target
346  icp.setInputTarget (cloud_target);
347  icp.setInputSource (cloud_source);
348 
349  if(icp2D)
350  {
351  pcl::registration::TransformationEstimation2D<pcl::PointXYZ, pcl::PointXYZ>::Ptr est;
352  est.reset(new pcl::registration::TransformationEstimation2D<pcl::PointXYZ, pcl::PointXYZ>);
353  icp.setTransformationEstimation(est);
354  }
355 
356  // Set the max correspondence distance to 5cm (e.g., correspondences with higher distances will be ignored)
357  icp.setMaxCorrespondenceDistance (maxCorrespondenceDistance);
358  // Set the maximum number of iterations (criterion 1)
359  icp.setMaximumIterations (maximumIterations);
360  // Set the transformation epsilon (criterion 2)
361  icp.setTransformationEpsilon (epsilon*epsilon);
362  // Set the euclidean distance difference epsilon (criterion 3)
363  //icp.setEuclideanFitnessEpsilon (1);
364  //icp.setRANSACOutlierRejectionThreshold(maxCorrespondenceDistance);
365 
366  // Perform the alignment
367  icp.align (cloud_source_registered);
368  hasConverged = icp.hasConverged();
369  return Transform::fromEigen4f(icp.getFinalTransformation());
370 }
371 
372 // return transform from source to target (All points/normals must be finite!!!)
374  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_source,
375  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_target,
376  double maxCorrespondenceDistance,
377  int maximumIterations,
378  bool & hasConverged,
379  pcl::PointCloud<pcl::PointNormal> & cloud_source_registered,
380  float epsilon,
381  bool icp2D)
382 {
383  pcl::IterativeClosestPoint<pcl::PointNormal, pcl::PointNormal> icp;
384  // Set the input source and target
385  icp.setInputTarget (cloud_target);
386  icp.setInputSource (cloud_source);
387 
388  pcl::registration::TransformationEstimationPointToPlaneLLS<pcl::PointNormal, pcl::PointNormal>::Ptr est;
389  est.reset(new pcl::registration::TransformationEstimationPointToPlaneLLS<pcl::PointNormal, pcl::PointNormal>);
390  icp.setTransformationEstimation(est);
391 
392  // Set the max correspondence distance to 5cm (e.g., correspondences with higher distances will be ignored)
393  icp.setMaxCorrespondenceDistance (maxCorrespondenceDistance);
394  // Set the maximum number of iterations (criterion 1)
395  icp.setMaximumIterations (maximumIterations);
396  // Set the transformation epsilon (criterion 2)
397  icp.setTransformationEpsilon (epsilon*epsilon);
398  // Set the euclidean distance difference epsilon (criterion 3)
399  //icp.setEuclideanFitnessEpsilon (1);
400  //icp.setRANSACOutlierRejectionThreshold(maxCorrespondenceDistance);
401 
402  // Perform the alignment
403  icp.align (cloud_source_registered);
404  hasConverged = icp.hasConverged();
405  Transform t = Transform::fromEigen4f(icp.getFinalTransformation());
406 
407  if(icp2D)
408  {
409  // FIXME probably an estimation approach already 2D like in icp() version above exists.
410  t = t.to3DoF();
411  }
412 
413  return t;
414 }
415 
416 }
417 
418 }
Transform RTABMAP_EXP transformFromXYZCorrespondencesSVD(const pcl::PointCloud< pcl::PointXYZ > &cloud1, const pcl::PointCloud< pcl::PointXYZ > &cloud2)
static Transform fromEigen4f(const Eigen::Matrix4f &matrix)
Definition: Transform.cpp:369
std::string prettyPrint() const
Definition: Transform.cpp:274
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
Transform RTABMAP_EXP icpPointToPlane(const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< pcl::PointNormal > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false)
void RTABMAP_EXP computeVarianceAndCorrespondences(const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudA, const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudB, double maxCorrespondenceDistance, double maxCorrespondenceAngle, double &variance, int &correspondencesOut)
Basic mathematics functions.
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
Transform RTABMAP_EXP transformFromXYZCorrespondences(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud1, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud2, double inlierThreshold=0.02, int iterations=100, int refineModelIterations=10, double refineModelSigma=3.0, std::vector< int > *inliers=0, cv::Mat *variance=0)
bool uIsFinite(const T &value)
Definition: UMath.h:55
#define UASSERT(condition)
Transform RTABMAP_EXP icp(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< pcl::PointXYZ > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false)
const char * source
Definition: lz4hc.h:181
Transform to3DoF() const
Definition: Transform.cpp:189
#define UDEBUG(...)
ULogger class and convenient macros.
#define UWARN(...)
Transform inverse() const
Definition: Transform.cpp:169


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:41