Point Cloud Library (PCL)  1.13.1-dev
registration.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  * $Id$
38  *
39  */
40 
41 #pragma once
42 
43 // PCL includes
44 #include <pcl/registration/correspondence_estimation.h>
45 #include <pcl/registration/correspondence_rejection.h>
46 #include <pcl/registration/transformation_estimation.h>
47 #include <pcl/search/kdtree.h>
48 #include <pcl/memory.h>
49 #include <pcl/pcl_base.h>
50 #include <pcl/pcl_macros.h>
51 
52 namespace pcl {
53 /** \brief @b Registration represents the base registration class for general purpose,
54  * ICP-like methods. \author Radu B. Rusu, Michael Dixon \ingroup registration
55  */
56 template <typename PointSource, typename PointTarget, typename Scalar = float>
57 class Registration : public PCLBase<PointSource> {
58 public:
59  using Matrix4 = Eigen::Matrix<Scalar, 4, 4>;
60 
61  // using PCLBase<PointSource>::initCompute;
65 
66  using Ptr = shared_ptr<Registration<PointSource, PointTarget, Scalar>>;
67  using ConstPtr = shared_ptr<const Registration<PointSource, PointTarget, Scalar>>;
68 
71  using KdTreePtr = typename KdTree::Ptr;
72 
75 
79 
83 
85 
86  using TransformationEstimation = typename pcl::registration::
87  TransformationEstimation<PointSource, PointTarget, Scalar>;
88  using TransformationEstimationPtr = typename TransformationEstimation::Ptr;
89  using TransformationEstimationConstPtr = typename TransformationEstimation::ConstPtr;
90 
95 
96  /** \brief The callback signature to the function updating intermediate source point
97  * cloud position during it's registration to the target point cloud. \param[in]
98  * cloud_src - the point cloud which will be updated to match target \param[in]
99  * indices_src - a selector of points in cloud_src \param[in] cloud_tgt - the point
100  * cloud we want to register against \param[in] indices_tgt - a selector of points in
101  * cloud_tgt
102  */
104  const pcl::Indices&,
106  const pcl::Indices&);
107 
108  /** \brief Empty constructor. */
110  : tree_(new KdTree)
112  , nr_iterations_(0)
113  , max_iterations_(10)
114  , ransac_iterations_(0)
115  , target_()
116  , final_transformation_(Matrix4::Identity())
117  , transformation_(Matrix4::Identity())
118  , previous_transformation_(Matrix4::Identity())
121  , euclidean_fitness_epsilon_(-std::numeric_limits<double>::max())
122  , corr_dist_threshold_(std::sqrt(std::numeric_limits<double>::max()))
123  , inlier_threshold_(0.05)
124  , converged_(false)
129  , target_cloud_updated_(true)
130  , source_cloud_updated_(true)
131  , force_no_recompute_(false)
133  , point_representation_()
134  {}
135 
136  /** \brief destructor. */
137  ~Registration() override = default;
138 
139  /** \brief Provide a pointer to the transformation estimation object.
140  * (e.g., SVD, point to plane etc.)
141  *
142  * \param[in] te is the pointer to the corresponding transformation estimation object
143  *
144  * Code example:
145  *
146  * \code
147  * TransformationEstimationPointToPlaneLLS<PointXYZ, PointXYZ>::Ptr trans_lls
148  * (new TransformationEstimationPointToPlaneLLS<PointXYZ, PointXYZ>);
149  * icp.setTransformationEstimation (trans_lls);
150  * // or...
151  * TransformationEstimationSVD<PointXYZ, PointXYZ>::Ptr trans_svd
152  * (new TransformationEstimationSVD<PointXYZ, PointXYZ>);
153  * icp.setTransformationEstimation (trans_svd);
154  * \endcode
155  */
156  void
158  {
160  }
161 
162  /** \brief Provide a pointer to the correspondence estimation object.
163  * (e.g., regular, reciprocal, normal shooting etc.)
164  *
165  * \param[in] ce is the pointer to the corresponding correspondence estimation object
166  *
167  * Code example:
168  *
169  * \code
170  * CorrespondenceEstimation<PointXYZ, PointXYZ>::Ptr
171  * ce (new CorrespondenceEstimation<PointXYZ, PointXYZ>);
172  * ce->setInputSource (source);
173  * ce->setInputTarget (target);
174  * icp.setCorrespondenceEstimation (ce);
175  * // or...
176  * CorrespondenceEstimationNormalShooting<PointNormal, PointNormal, PointNormal>::Ptr
177  * cens (new CorrespondenceEstimationNormalShooting<PointNormal, PointNormal>);
178  * ce->setInputSource (source);
179  * ce->setInputTarget (target);
180  * ce->setSourceNormals (source);
181  * ce->setTargetNormals (target);
182  * icp.setCorrespondenceEstimation (cens);
183  * \endcode
184  */
185  void
187  {
189  }
190 
191  /** \brief Provide a pointer to the input source
192  * (e.g., the point cloud that we want to align to the target)
193  *
194  * \param[in] cloud the input point cloud source
195  */
196  virtual void
198 
199  /** \brief Get a pointer to the input point cloud dataset target. */
200  inline PointCloudSourceConstPtr const
202  {
203  return (input_);
204  }
205 
206  /** \brief Provide a pointer to the input target (e.g., the point cloud that we want
207  * to align the input source to) \param[in] cloud the input point cloud target
208  */
209  virtual inline void
211 
212  /** \brief Get a pointer to the input point cloud dataset target. */
213  inline PointCloudTargetConstPtr const
215  {
216  return (target_);
217  }
218 
219  /** \brief Provide a pointer to the search object used to find correspondences in
220  * the target cloud.
221  * \param[in] tree a pointer to the spatial search object.
222  * \param[in] force_no_recompute If set to true, this tree will NEVER be
223  * recomputed, regardless of calls to setInputTarget. Only use if you are
224  * confident that the tree will be set correctly.
225  */
226  inline void
227  setSearchMethodTarget(const KdTreePtr& tree, bool force_no_recompute = false)
228  {
229  tree_ = tree;
230  force_no_recompute_ = force_no_recompute;
231  // Since we just set a new tree, we need to check for updates
232  target_cloud_updated_ = true;
233  }
234 
235  /** \brief Get a pointer to the search method used to find correspondences in the
236  * target cloud. */
237  inline KdTreePtr
239  {
240  return (tree_);
241  }
242 
243  /** \brief Provide a pointer to the search object used to find correspondences in
244  * the source cloud (usually used by reciprocal correspondence finding).
245  * \param[in] tree a pointer to the spatial search object.
246  * \param[in] force_no_recompute If set to true, this tree will NEVER be
247  * recomputed, regardless of calls to setInputSource. Only use if you are
248  * extremely confident that the tree will be set correctly.
249  */
250  inline void
252  bool force_no_recompute = false)
253  {
254  tree_reciprocal_ = tree;
255  force_no_recompute_reciprocal_ = force_no_recompute;
256  // Since we just set a new tree, we need to check for updates
257  source_cloud_updated_ = true;
258  }
259 
260  /** \brief Get a pointer to the search method used to find correspondences in the
261  * source cloud. */
262  inline KdTreeReciprocalPtr
264  {
265  return (tree_reciprocal_);
266  }
267 
268  /** \brief Get the final transformation matrix estimated by the registration method.
269  */
270  inline Matrix4
272  {
273  return (final_transformation_);
274  }
275 
276  /** \brief Get the last incremental transformation matrix estimated by the
277  * registration method. */
278  inline Matrix4
280  {
281  return (transformation_);
282  }
283 
284  /** \brief Set the maximum number of iterations the internal optimization should run
285  * for. \param[in] nr_iterations the maximum number of iterations the internal
286  * optimization should run for
287  */
288  inline void
289  setMaximumIterations(int nr_iterations)
290  {
291  max_iterations_ = nr_iterations;
292  }
293 
294  /** \brief Get the maximum number of iterations the internal optimization should run
295  * for, as set by the user. */
296  inline int
298  {
299  return (max_iterations_);
300  }
301 
302  /** \brief Set the number of iterations RANSAC should run for.
303  * \param[in] ransac_iterations is the number of iterations RANSAC should run for
304  */
305  inline void
306  setRANSACIterations(int ransac_iterations)
307  {
308  ransac_iterations_ = ransac_iterations;
309  }
310 
311  /** \brief Get the number of iterations RANSAC should run for, as set by the user. */
312  inline double
314  {
315  return (ransac_iterations_);
316  }
317 
318  /** \brief Set the inlier distance threshold for the internal RANSAC outlier rejection
319  * loop.
320  *
321  * The method considers a point to be an inlier, if the distance between the target
322  * data index and the transformed source index is smaller than the given inlier
323  * distance threshold. The value is set by default to 0.05m. \param[in]
324  * inlier_threshold the inlier distance threshold for the internal RANSAC outlier
325  * rejection loop
326  */
327  inline void
328  setRANSACOutlierRejectionThreshold(double inlier_threshold)
329  {
330  inlier_threshold_ = inlier_threshold;
331  }
332 
333  /** \brief Get the inlier distance threshold for the internal outlier rejection loop
334  * as set by the user. */
335  inline double
337  {
338  return (inlier_threshold_);
339  }
340 
341  /** \brief Set the maximum distance threshold between two correspondent points in
342  * source <-> target. If the distance is larger than this threshold, the points will
343  * be ignored in the alignment process. \param[in] distance_threshold the maximum
344  * distance threshold between a point and its nearest neighbor correspondent in order
345  * to be considered in the alignment process
346  */
347  inline void
348  setMaxCorrespondenceDistance(double distance_threshold)
349  {
350  corr_dist_threshold_ = distance_threshold;
351  }
352 
353  /** \brief Get the maximum distance threshold between two correspondent points in
354  * source <-> target. If the distance is larger than this threshold, the points will
355  * be ignored in the alignment process.
356  */
357  inline double
359  {
360  return (corr_dist_threshold_);
361  }
362 
363  /** \brief Set the transformation epsilon (maximum allowable translation squared
364  * difference between two consecutive transformations) in order for an optimization to
365  * be considered as having converged to the final solution. \param[in] epsilon the
366  * transformation epsilon in order for an optimization to be considered as having
367  * converged to the final solution.
368  */
369  inline void
370  setTransformationEpsilon(double epsilon)
371  {
372  transformation_epsilon_ = epsilon;
373  }
374 
375  /** \brief Get the transformation epsilon (maximum allowable translation squared
376  * difference between two consecutive transformations) as set by the user.
377  */
378  inline double
380  {
381  return (transformation_epsilon_);
382  }
383 
384  /** \brief Set the transformation rotation epsilon (maximum allowable rotation
385  * difference between two consecutive transformations) in order for an optimization to
386  * be considered as having converged to the final solution. \param[in] epsilon the
387  * transformation rotation epsilon in order for an optimization to be considered as
388  * having converged to the final solution (epsilon is the cos(angle) in a axis-angle
389  * representation).
390  */
391  inline void
393  {
395  }
396 
397  /** \brief Get the transformation rotation epsilon (maximum allowable difference
398  * between two consecutive transformations) as set by the user (epsilon is the
399  * cos(angle) in a axis-angle representation).
400  */
401  inline double
403  {
405  }
406 
407  /** \brief Set the maximum allowed Euclidean error between two consecutive steps in
408  * the ICP loop, before the algorithm is considered to have converged. The error is
409  * estimated as the sum of the differences between correspondences in an Euclidean
410  * sense, divided by the number of correspondences. \param[in] epsilon the maximum
411  * allowed distance error before the algorithm will be considered to have converged
412  */
413  inline void
415  {
416  euclidean_fitness_epsilon_ = epsilon;
417  }
418 
419  /** \brief Get the maximum allowed distance error before the algorithm will be
420  * considered to have converged, as set by the user. See \ref
421  * setEuclideanFitnessEpsilon
422  */
423  inline double
425  {
427  }
428 
429  /** \brief Provide a boost shared pointer to the PointRepresentation to be used when
430  * comparing points \param[in] point_representation the PointRepresentation to be used
431  * by the k-D tree
432  */
433  inline void
435  {
436  point_representation_ = point_representation;
437  }
438 
439  /** \brief Register the user callback function which will be called from registration
440  * thread in order to update point cloud obtained after each iteration \param[in]
441  * visualizerCallback reference of the user callback function
442  */
443  inline bool
445  std::function<UpdateVisualizerCallbackSignature>& visualizerCallback)
446  {
447  if (visualizerCallback) {
448  update_visualizer_ = visualizerCallback;
449  pcl::Indices indices;
450  update_visualizer_(*input_, indices, *target_, indices);
451  return (true);
452  }
453  return (false);
454  }
455 
456  /** \brief Obtain the Euclidean fitness score (e.g., mean of squared distances from
457  * the source to the target) \param[in] max_range maximum allowable distance between a
458  * point and its correspondence in the target (default: double::max)
459  */
460  inline double
461  getFitnessScore(double max_range = std::numeric_limits<double>::max());
462 
463  /** \brief Obtain the Euclidean fitness score (e.g., mean of squared distances from
464  * the source to the target) from two sets of correspondence distances (distances
465  * between source and target points) \param[in] distances_a the first set of distances
466  * between correspondences \param[in] distances_b the second set of distances between
467  * correspondences
468  */
469  inline double
470  getFitnessScore(const std::vector<float>& distances_a,
471  const std::vector<float>& distances_b);
472 
473  /** \brief Return the state of convergence after the last align run */
474  inline bool
475  hasConverged() const
476  {
477  return (converged_);
478  }
479 
480  /** \brief Call the registration algorithm which estimates the transformation and
481  * returns the transformed source (input) as \a output. \param[out] output the
482  * resultant input transformed point cloud dataset
483  */
484  inline void
485  align(PointCloudSource& output);
486 
487  /** \brief Call the registration algorithm which estimates the transformation and
488  * returns the transformed source (input) as \a output. \param[out] output the
489  * resultant input transformed point cloud dataset \param[in] guess the initial gross
490  * estimation of the transformation
491  */
492  inline void
493  align(PointCloudSource& output, const Matrix4& guess);
494 
495  /** \brief Abstract class get name method. */
496  inline const std::string&
497  getClassName() const
498  {
499  return (reg_name_);
500  }
501 
502  /** \brief Internal computation initialization. */
503  bool
504  initCompute();
505 
506  /** \brief Internal computation when reciprocal lookup is needed */
507  bool
509 
510  /** \brief Add a new correspondence rejector to the list
511  * \param[in] rejector the new correspondence rejector to concatenate
512  *
513  * Code example:
514  *
515  * \code
516  * CorrespondenceRejectorDistance rej;
517  * rej.setInputCloud<PointXYZ> (keypoints_src);
518  * rej.setInputTarget<PointXYZ> (keypoints_tgt);
519  * rej.setMaximumDistance (1);
520  * rej.setInputCorrespondences (all_correspondences);
521  *
522  * // or...
523  *
524  * \endcode
525  */
526  inline void
528  {
529  correspondence_rejectors_.push_back(rejector);
530  }
531 
532  /** \brief Get the list of correspondence rejectors. */
533  inline std::vector<CorrespondenceRejectorPtr>
535  {
536  return (correspondence_rejectors_);
537  }
538 
539  /** \brief Remove the i-th correspondence rejector in the list
540  * \param[in] i the position of the correspondence rejector in the list to remove
541  */
542  inline bool
544  {
545  if (i >= correspondence_rejectors_.size())
546  return (false);
548  return (true);
549  }
550 
551  /** \brief Clear the list of correspondence rejectors. */
552  inline void
554  {
556  }
557 
558 protected:
559  /** \brief The registration method name. */
560  std::string reg_name_;
561 
562  /** \brief A pointer to the spatial search object. */
564 
565  /** \brief A pointer to the spatial search object of the source. */
567 
568  /** \brief The number of iterations the internal optimization ran for (used
569  * internally). */
571 
572  /** \brief The maximum number of iterations the internal optimization should run for.
573  * The default value is 10.
574  */
576 
577  /** \brief The number of iterations RANSAC should run for. */
579 
580  /** \brief The input point cloud dataset target. */
582 
583  /** \brief The final transformation matrix estimated by the registration method after
584  * N iterations. */
586 
587  /** \brief The transformation matrix estimated by the registration method. */
589 
590  /** \brief The previous transformation matrix estimated by the registration method
591  * (used internally). */
593 
594  /** \brief The maximum difference between two consecutive transformations in order to
595  * consider convergence (user defined).
596  */
598 
599  /** \brief The maximum rotation difference between two consecutive transformations in
600  * order to consider convergence (user defined).
601  */
603 
604  /** \brief The maximum allowed Euclidean error between two consecutive steps in the
605  * ICP loop, before the algorithm is considered to have converged. The error is
606  * estimated as the sum of the differences between correspondences in an Euclidean
607  * sense, divided by the number of correspondences.
608  */
610 
611  /** \brief The maximum distance threshold between two correspondent points in source
612  * <-> target. If the distance is larger than this threshold, the points will be
613  * ignored in the alignment process.
614  */
616 
617  /** \brief The inlier distance threshold for the internal RANSAC outlier rejection
618  * loop. The method considers a point to be an inlier, if the distance between the
619  * target data index and the transformed source index is smaller than the given inlier
620  * distance threshold. The default value is 0.05.
621  */
623 
624  /** \brief Holds internal convergence state, given user parameters. */
626 
627  /** \brief The minimum number of correspondences that the algorithm needs before
628  * attempting to estimate the transformation. The default value is 3.
629  */
631 
632  /** \brief The set of correspondences determined at this ICP step. */
634 
635  /** \brief A TransformationEstimation object, used to calculate the 4x4 rigid
636  * transformation. */
638 
639  /** \brief A CorrespondenceEstimation object, used to estimate correspondences between
640  * the source and the target cloud. */
642 
643  /** \brief The list of correspondence rejectors to use. */
644  std::vector<CorrespondenceRejectorPtr> correspondence_rejectors_;
645 
646  /** \brief Variable that stores whether we have a new target cloud, meaning we need to
647  * pre-process it again. This way, we avoid rebuilding the kd-tree for the target
648  * cloud every time the determineCorrespondences () method is called. */
650  /** \brief Variable that stores whether we have a new source cloud, meaning we need to
651  * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the
652  * source cloud every time the determineCorrespondences () method is called. */
654  /** \brief A flag which, if set, means the tree operating on the target cloud
655  * will never be recomputed*/
657 
658  /** \brief A flag which, if set, means the tree operating on the source cloud
659  * will never be recomputed*/
661 
662  /** \brief Callback function to update intermediate source point cloud position during
663  * it's registration to the target point cloud.
664  */
665  std::function<UpdateVisualizerCallbackSignature> update_visualizer_;
666 
667  /** \brief Search for the closest nearest neighbor of a given point.
668  * \param cloud the point cloud dataset to use for nearest neighbor search
669  * \param index the index of the query point
670  * \param indices the resultant vector of indices representing the k-nearest neighbors
671  * \param distances the resultant distances from the query point to the k-nearest
672  * neighbors
673  */
674  inline bool
676  int index,
677  pcl::Indices& indices,
678  std::vector<float>& distances)
679  {
680  int k = tree_->nearestKSearch(cloud, index, 1, indices, distances);
681  if (k == 0)
682  return (false);
683  return (true);
684  }
685 
686  /** \brief Abstract transformation computation method with initial guess */
687  virtual void
688  computeTransformation(PointCloudSource& output, const Matrix4& guess) = 0;
689 
690 private:
691  /** \brief The point representation used (internal). */
692  PointRepresentationConstPtr point_representation_;
693 
694  /**
695  * \brief Remove from public API in favor of \ref setInputSource
696  *
697  * Still gives the correct result (with a warning)
698  */
699  void
700  setInputCloud(const PointCloudSourceConstPtr& cloud) override
701  {
702  PCL_WARN("[pcl::registration::Registration] setInputCloud is deprecated."
703  "Please use setInputSource instead.\n");
704  setInputSource(cloud);
705  }
706 
707 public:
709 };
710 } // namespace pcl
711 
712 #include <pcl/registration/impl/registration.hpp>
PCL base class.
Definition: pcl_base.h:70
PointCloudConstPtr input_
The input point cloud dataset.
Definition: pcl_base.h:147
shared_ptr< PointCloud< PointSource > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointSource > > ConstPtr
Definition: point_cloud.h:414
Registration represents the base registration class for general purpose, ICP-like methods.
Definition: registration.h:57
bool target_cloud_updated_
Variable that stores whether we have a new target cloud, meaning we need to pre-process it again.
Definition: registration.h:649
Matrix4 final_transformation_
The final transformation matrix estimated by the registration method after N iterations.
Definition: registration.h:585
typename KdTreeReciprocal::Ptr KdTreeReciprocalPtr
Definition: registration.h:74
bool initCompute()
Internal computation initialization.
std::function< UpdateVisualizerCallbackSignature > update_visualizer_
Callback function to update intermediate source point cloud position during it's registration to the ...
Definition: registration.h:665
virtual void setInputSource(const PointCloudSourceConstPtr &cloud)
Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)
double corr_dist_threshold_
The maximum distance threshold between two correspondent points in source <-> target.
Definition: registration.h:615
void clearCorrespondenceRejectors()
Clear the list of correspondence rejectors.
Definition: registration.h:553
double getTransformationEpsilon()
Get the transformation epsilon (maximum allowable translation squared difference between two consecut...
Definition: registration.h:379
void(const pcl::PointCloud< PointSource > &, const pcl::Indices &, const pcl::PointCloud< PointTarget > &, const pcl::Indices &) UpdateVisualizerCallbackSignature
The callback signature to the function updating intermediate source point cloud position during it's ...
Definition: registration.h:106
std::string reg_name_
The registration method name.
Definition: registration.h:560
Matrix4 getFinalTransformation()
Get the final transformation matrix estimated by the registration method.
Definition: registration.h:271
void setRANSACIterations(int ransac_iterations)
Set the number of iterations RANSAC should run for.
Definition: registration.h:306
const std::string & getClassName() const
Abstract class get name method.
Definition: registration.h:497
shared_ptr< const Registration< PointSource, PointTarget, Scalar > > ConstPtr
Definition: registration.h:67
Matrix4 transformation_
The transformation matrix estimated by the registration method.
Definition: registration.h:588
pcl::PointCloud< PointSource > PointCloudSource
Definition: registration.h:76
KdTreeReciprocalPtr tree_reciprocal_
A pointer to the spatial search object of the source.
Definition: registration.h:566
bool removeCorrespondenceRejector(unsigned int i)
Remove the i-th correspondence rejector in the list.
Definition: registration.h:543
void setCorrespondenceEstimation(const CorrespondenceEstimationPtr &ce)
Provide a pointer to the correspondence estimation object.
Definition: registration.h:186
typename CorrespondenceEstimation::ConstPtr CorrespondenceEstimationConstPtr
Definition: registration.h:94
void setMaximumIterations(int nr_iterations)
Set the maximum number of iterations the internal optimization should run for.
Definition: registration.h:289
void setSearchMethodSource(const KdTreeReciprocalPtr &tree, bool force_no_recompute=false)
Provide a pointer to the search object used to find correspondences in the source cloud (usually used...
Definition: registration.h:251
void setSearchMethodTarget(const KdTreePtr &tree, bool force_no_recompute=false)
Provide a pointer to the search object used to find correspondences in the target cloud.
Definition: registration.h:227
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
Definition: registration.h:78
typename KdTree::Ptr KdTreePtr
Definition: registration.h:71
virtual void setInputTarget(const PointCloudTargetConstPtr &cloud)
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
bool registerVisualizationCallback(std::function< UpdateVisualizerCallbackSignature > &visualizerCallback)
Register the user callback function which will be called from registration thread in order to update ...
Definition: registration.h:444
typename TransformationEstimation::Ptr TransformationEstimationPtr
Definition: registration.h:88
typename PointCloudSource::Ptr PointCloudSourcePtr
Definition: registration.h:77
void setPointRepresentation(const PointRepresentationConstPtr &point_representation)
Provide a boost shared pointer to the PointRepresentation to be used when comparing points.
Definition: registration.h:434
CorrespondenceEstimationPtr correspondence_estimation_
A CorrespondenceEstimation object, used to estimate correspondences between the source and the target...
Definition: registration.h:641
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
Definition: registration.h:82
double getTransformationRotationEpsilon()
Get the transformation rotation epsilon (maximum allowable difference between two consecutive transfo...
Definition: registration.h:402
bool force_no_recompute_
A flag which, if set, means the tree operating on the target cloud will never be recomputed.
Definition: registration.h:656
void setRANSACOutlierRejectionThreshold(double inlier_threshold)
Set the inlier distance threshold for the internal RANSAC outlier rejection loop.
Definition: registration.h:328
void setMaxCorrespondenceDistance(double distance_threshold)
Set the maximum distance threshold between two correspondent points in source <-> target.
Definition: registration.h:348
void addCorrespondenceRejector(const CorrespondenceRejectorPtr &rejector)
Add a new correspondence rejector to the list.
Definition: registration.h:527
int nr_iterations_
The number of iterations the internal optimization ran for (used internally).
Definition: registration.h:570
shared_ptr< Registration< PointSource, PointTarget, Scalar > > Ptr
Definition: registration.h:66
double getRANSACOutlierRejectionThreshold()
Get the inlier distance threshold for the internal outlier rejection loop as set by the user.
Definition: registration.h:336
double getEuclideanFitnessEpsilon()
Get the maximum allowed distance error before the algorithm will be considered to have converged,...
Definition: registration.h:424
double getMaxCorrespondenceDistance()
Get the maximum distance threshold between two correspondent points in source <-> target.
Definition: registration.h:358
KdTreePtr getSearchMethodTarget() const
Get a pointer to the search method used to find correspondences in the target cloud.
Definition: registration.h:238
KdTreePtr tree_
A pointer to the spatial search object.
Definition: registration.h:563
Registration()
Empty constructor.
Definition: registration.h:109
Matrix4 getLastIncrementalTransformation()
Get the last incremental transformation matrix estimated by the registration method.
Definition: registration.h:279
typename PointCloudTarget::Ptr PointCloudTargetPtr
Definition: registration.h:81
Matrix4 previous_transformation_
The previous transformation matrix estimated by the registration method (used internally).
Definition: registration.h:592
bool converged_
Holds internal convergence state, given user parameters.
Definition: registration.h:625
int ransac_iterations_
The number of iterations RANSAC should run for.
Definition: registration.h:578
Eigen::Matrix< Scalar, 4, 4 > Matrix4
Definition: registration.h:59
void align(PointCloudSource &output)
Call the registration algorithm which estimates the transformation and returns the transformed source...
PointCloudTargetConstPtr const getInputTarget()
Get a pointer to the input point cloud dataset target.
Definition: registration.h:214
CorrespondencesPtr correspondences_
The set of correspondences determined at this ICP step.
Definition: registration.h:633
TransformationEstimationPtr transformation_estimation_
A TransformationEstimation object, used to calculate the 4x4 rigid transformation.
Definition: registration.h:637
bool searchForNeighbors(const PointCloudSource &cloud, int index, pcl::Indices &indices, std::vector< float > &distances)
Search for the closest nearest neighbor of a given point.
Definition: registration.h:675
int max_iterations_
The maximum number of iterations the internal optimization should run for.
Definition: registration.h:575
double transformation_rotation_epsilon_
The maximum rotation difference between two consecutive transformations in order to consider converge...
Definition: registration.h:602
unsigned int min_number_correspondences_
The minimum number of correspondences that the algorithm needs before attempting to estimate the tran...
Definition: registration.h:630
double getFitnessScore(double max_range=std::numeric_limits< double >::max())
Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target)
double euclidean_fitness_epsilon_
The maximum allowed Euclidean error between two consecutive steps in the ICP loop,...
Definition: registration.h:609
double inlier_threshold_
The inlier distance threshold for the internal RANSAC outlier rejection loop.
Definition: registration.h:622
pcl::registration::CorrespondenceRejector::Ptr CorrespondenceRejectorPtr
Definition: registration.h:69
std::vector< CorrespondenceRejectorPtr > getCorrespondenceRejectors()
Get the list of correspondence rejectors.
Definition: registration.h:534
PointCloudSourceConstPtr const getInputSource()
Get a pointer to the input point cloud dataset target.
Definition: registration.h:201
typename TransformationEstimation::ConstPtr TransformationEstimationConstPtr
Definition: registration.h:89
typename pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar > TransformationEstimation
Definition: registration.h:87
bool hasConverged() const
Return the state of convergence after the last align run.
Definition: registration.h:475
typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr
Definition: registration.h:84
void setTransformationEstimation(const TransformationEstimationPtr &te)
Provide a pointer to the transformation estimation object.
Definition: registration.h:157
bool force_no_recompute_reciprocal_
A flag which, if set, means the tree operating on the source cloud will never be recomputed.
Definition: registration.h:660
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
Definition: registration.h:597
std::vector< CorrespondenceRejectorPtr > correspondence_rejectors_
The list of correspondence rejectors to use.
Definition: registration.h:644
KdTreeReciprocalPtr getSearchMethodSource() const
Get a pointer to the search method used to find correspondences in the source cloud.
Definition: registration.h:263
~Registration() override=default
destructor.
int getMaximumIterations()
Get the maximum number of iterations the internal optimization should run for, as set by the user.
Definition: registration.h:297
void setTransformationRotationEpsilon(double epsilon)
Set the transformation rotation epsilon (maximum allowable rotation difference between two consecutiv...
Definition: registration.h:392
bool initComputeReciprocal()
Internal computation when reciprocal lookup is needed.
virtual void computeTransformation(PointCloudSource &output, const Matrix4 &guess)=0
Abstract transformation computation method with initial guess.
typename CorrespondenceEstimation::Ptr CorrespondenceEstimationPtr
Definition: registration.h:93
void setEuclideanFitnessEpsilon(double epsilon)
Set the maximum allowed Euclidean error between two consecutive steps in the ICP loop,...
Definition: registration.h:414
void setTransformationEpsilon(double epsilon)
Set the transformation epsilon (maximum allowable translation squared difference between two consecut...
Definition: registration.h:370
bool source_cloud_updated_
Variable that stores whether we have a new source cloud, meaning we need to pre-process it again.
Definition: registration.h:653
PointCloudTargetConstPtr target_
The input point cloud dataset target.
Definition: registration.h:581
double getRANSACIterations()
Get the number of iterations RANSAC should run for, as set by the user.
Definition: registration.h:313
Abstract CorrespondenceEstimationBase class.
shared_ptr< const CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > ConstPtr
shared_ptr< CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > Ptr
shared_ptr< CorrespondenceRejector > Ptr
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
Definition: kdtree.h:62
shared_ptr< KdTree< PointT, Tree > > Ptr
Definition: kdtree.h:75
typename PointRepresentation< PointT >::ConstPtr PointRepresentationConstPtr
Definition: kdtree.h:80
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
Defines functions, macros and traits for allocating and using memory.
shared_ptr< Correspondences > CorrespondencesPtr
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
Defines all the PCL and non-PCL macros used.