Point Cloud Library (PCL)  1.11.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 std::vector<int>&,
106  const std::vector<int>&);
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. */
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 (new
148  * TransformationEstimationPointToPlaneLLS<PointXYZ, PointXYZ>);
149  * icp.setTransformationEstimation (trans_lls);
150  * // or...
151  * TransformationEstimationSVD<PointXYZ, PointXYZ>::Ptr trans_svd (new
152  * TransformationEstimationSVD<PointXYZ, PointXYZ>); icp.setTransformationEstimation
153  * (trans_svd); \endcode
154  */
155  void
157  {
159  }
160 
161  /** \brief Provide a pointer to the correspondence estimation object.
162  * (e.g., regular, reciprocal, normal shooting etc.)
163  *
164  * \param[in] ce is the pointer to the corresponding correspondence estimation object
165  *
166  * Code example:
167  *
168  * \code
169  * CorrespondenceEstimation<PointXYZ, PointXYZ>::Ptr ce (new
170  * CorrespondenceEstimation<PointXYZ, PointXYZ>); ce->setInputSource (source);
171  * ce->setInputTarget (target);
172  * icp.setCorrespondenceEstimation (ce);
173  * // or...
174  * CorrespondenceEstimationNormalShooting<PointNormal, PointNormal, PointNormal>::Ptr
175  * cens (new CorrespondenceEstimationNormalShooting<PointNormal, PointNormal>);
176  * ce->setInputSource (source);
177  * ce->setInputTarget (target);
178  * ce->setSourceNormals (source);
179  * ce->setTargetNormals (target);
180  * icp.setCorrespondenceEstimation (cens);
181  * \endcode
182  */
183  void
185  {
187  }
188 
189  /** \brief Provide a pointer to the input source
190  * (e.g., the point cloud that we want to align to the target)
191  *
192  * \param[in] cloud the input point cloud source
193  */
194  virtual void
196 
197  /** \brief Get a pointer to the input point cloud dataset target. */
198  inline PointCloudSourceConstPtr const
200  {
201  return (input_);
202  }
203 
204  /** \brief Provide a pointer to the input target (e.g., the point cloud that we want
205  * to align the input source to) \param[in] cloud the input point cloud target
206  */
207  virtual inline void
209 
210  /** \brief Get a pointer to the input point cloud dataset target. */
211  inline PointCloudTargetConstPtr const
213  {
214  return (target_);
215  }
216 
217  /** \brief Provide a pointer to the search object used to find correspondences in
218  * the target cloud.
219  * \param[in] tree a pointer to the spatial search object.
220  * \param[in] force_no_recompute If set to true, this tree will NEVER be
221  * recomputed, regardless of calls to setInputTarget. Only use if you are
222  * confident that the tree will be set correctly.
223  */
224  inline void
225  setSearchMethodTarget(const KdTreePtr& tree, bool force_no_recompute = false)
226  {
227  tree_ = tree;
228  force_no_recompute_ = force_no_recompute;
229  // Since we just set a new tree, we need to check for updates
230  target_cloud_updated_ = true;
231  }
232 
233  /** \brief Get a pointer to the search method used to find correspondences in the
234  * target cloud. */
235  inline KdTreePtr
237  {
238  return (tree_);
239  }
240 
241  /** \brief Provide a pointer to the search object used to find correspondences in
242  * the source cloud (usually used by reciprocal correspondence finding).
243  * \param[in] tree a pointer to the spatial search object.
244  * \param[in] force_no_recompute If set to true, this tree will NEVER be
245  * recomputed, regardless of calls to setInputSource. Only use if you are
246  * extremely confident that the tree will be set correctly.
247  */
248  inline void
250  bool force_no_recompute = false)
251  {
252  tree_reciprocal_ = tree;
253  force_no_recompute_reciprocal_ = force_no_recompute;
254  // Since we just set a new tree, we need to check for updates
255  source_cloud_updated_ = true;
256  }
257 
258  /** \brief Get a pointer to the search method used to find correspondences in the
259  * source cloud. */
260  inline KdTreeReciprocalPtr
262  {
263  return (tree_reciprocal_);
264  }
265 
266  /** \brief Get the final transformation matrix estimated by the registration method.
267  */
268  inline Matrix4
270  {
271  return (final_transformation_);
272  }
273 
274  /** \brief Get the last incremental transformation matrix estimated by the
275  * registration method. */
276  inline Matrix4
278  {
279  return (transformation_);
280  }
281 
282  /** \brief Set the maximum number of iterations the internal optimization should run
283  * for. \param[in] nr_iterations the maximum number of iterations the internal
284  * optimization should run for
285  */
286  inline void
287  setMaximumIterations(int nr_iterations)
288  {
289  max_iterations_ = nr_iterations;
290  }
291 
292  /** \brief Get the maximum number of iterations the internal optimization should run
293  * for, as set by the user. */
294  inline int
296  {
297  return (max_iterations_);
298  }
299 
300  /** \brief Set the number of iterations RANSAC should run for.
301  * \param[in] ransac_iterations is the number of iterations RANSAC should run for
302  */
303  inline void
304  setRANSACIterations(int ransac_iterations)
305  {
306  ransac_iterations_ = ransac_iterations;
307  }
308 
309  /** \brief Get the number of iterations RANSAC should run for, as set by the user. */
310  inline double
312  {
313  return (ransac_iterations_);
314  }
315 
316  /** \brief Set the inlier distance threshold for the internal RANSAC outlier rejection
317  * loop.
318  *
319  * The method considers a point to be an inlier, if the distance between the target
320  * data index and the transformed source index is smaller than the given inlier
321  * distance threshold. The value is set by default to 0.05m. \param[in]
322  * inlier_threshold the inlier distance threshold for the internal RANSAC outlier
323  * rejection loop
324  */
325  inline void
326  setRANSACOutlierRejectionThreshold(double inlier_threshold)
327  {
328  inlier_threshold_ = inlier_threshold;
329  }
330 
331  /** \brief Get the inlier distance threshold for the internal outlier rejection loop
332  * as set by the user. */
333  inline double
335  {
336  return (inlier_threshold_);
337  }
338 
339  /** \brief Set the maximum distance threshold between two correspondent points in
340  * source <-> target. If the distance is larger than this threshold, the points will
341  * be ignored in the alignment process. \param[in] distance_threshold the maximum
342  * distance threshold between a point and its nearest neighbor correspondent in order
343  * to be considered in the alignment process
344  */
345  inline void
346  setMaxCorrespondenceDistance(double distance_threshold)
347  {
348  corr_dist_threshold_ = distance_threshold;
349  }
350 
351  /** \brief Get the maximum distance threshold between two correspondent points in
352  * source <-> target. If the distance is larger than this threshold, the points will
353  * be ignored in the alignment process.
354  */
355  inline double
357  {
358  return (corr_dist_threshold_);
359  }
360 
361  /** \brief Set the transformation epsilon (maximum allowable translation squared
362  * difference between two consecutive transformations) in order for an optimization to
363  * be considered as having converged to the final solution. \param[in] epsilon the
364  * transformation epsilon in order for an optimization to be considered as having
365  * converged to the final solution.
366  */
367  inline void
368  setTransformationEpsilon(double epsilon)
369  {
370  transformation_epsilon_ = epsilon;
371  }
372 
373  /** \brief Get the transformation epsilon (maximum allowable translation squared
374  * difference between two consecutive transformations) as set by the user.
375  */
376  inline double
378  {
379  return (transformation_epsilon_);
380  }
381 
382  /** \brief Set the transformation rotation epsilon (maximum allowable rotation
383  * difference between two consecutive transformations) in order for an optimization to
384  * be considered as having converged to the final solution. \param[in] epsilon the
385  * transformation rotation epsilon in order for an optimization to be considered as
386  * having converged to the final solution (epsilon is the cos(angle) in a axis-angle
387  * representation).
388  */
389  inline void
391  {
393  }
394 
395  /** \brief Get the transformation rotation epsilon (maximum allowable difference
396  * between two consecutive transformations) as set by the user (epsilon is the
397  * cos(angle) in a axis-angle representation).
398  */
399  inline double
401  {
403  }
404 
405  /** \brief Set the maximum allowed Euclidean error between two consecutive steps in
406  * the ICP loop, before the algorithm is considered to have converged. The error is
407  * estimated as the sum of the differences between correspondences in an Euclidean
408  * sense, divided by the number of correspondences. \param[in] epsilon the maximum
409  * allowed distance error before the algorithm will be considered to have converged
410  */
411  inline void
413  {
414  euclidean_fitness_epsilon_ = epsilon;
415  }
416 
417  /** \brief Get the maximum allowed distance error before the algorithm will be
418  * considered to have converged, as set by the user. See \ref
419  * setEuclideanFitnessEpsilon
420  */
421  inline double
423  {
425  }
426 
427  /** \brief Provide a boost shared pointer to the PointRepresentation to be used when
428  * comparing points \param[in] point_representation the PointRepresentation to be used
429  * by the k-D tree
430  */
431  inline void
433  {
434  point_representation_ = point_representation;
435  }
436 
437  /** \brief Register the user callback function which will be called from registration
438  * thread in order to update point cloud obtained after each iteration \param[in]
439  * visualizerCallback reference of the user callback function
440  */
441  inline bool
443  std::function<UpdateVisualizerCallbackSignature>& visualizerCallback)
444  {
445  if (visualizerCallback) {
446  update_visualizer_ = visualizerCallback;
447  return (true);
448  }
449  return (false);
450  }
451 
452  /** \brief Obtain the Euclidean fitness score (e.g., mean of squared distances from
453  * the source to the target) \param[in] max_range maximum allowable distance between a
454  * point and its correspondence in the target (default: double::max)
455  */
456  inline double
457  getFitnessScore(double max_range = std::numeric_limits<double>::max());
458 
459  /** \brief Obtain the Euclidean fitness score (e.g., mean of squared distances from
460  * the source to the target) from two sets of correspondence distances (distances
461  * between source and target points) \param[in] distances_a the first set of distances
462  * between correspondences \param[in] distances_b the second set of distances between
463  * correspondences
464  */
465  inline double
466  getFitnessScore(const std::vector<float>& distances_a,
467  const std::vector<float>& distances_b);
468 
469  /** \brief Return the state of convergence after the last align run */
470  inline bool
471  hasConverged() const
472  {
473  return (converged_);
474  }
475 
476  /** \brief Call the registration algorithm which estimates the transformation and
477  * returns the transformed source (input) as \a output. \param[out] output the
478  * resultant input transformed point cloud dataset
479  */
480  inline void
481  align(PointCloudSource& output);
482 
483  /** \brief Call the registration algorithm which estimates the transformation and
484  * returns the transformed source (input) as \a output. \param[out] output the
485  * resultant input transformed point cloud dataset \param[in] guess the initial gross
486  * estimation of the transformation
487  */
488  inline void
489  align(PointCloudSource& output, const Matrix4& guess);
490 
491  /** \brief Abstract class get name method. */
492  inline const std::string&
493  getClassName() const
494  {
495  return (reg_name_);
496  }
497 
498  /** \brief Internal computation initialization. */
499  bool
500  initCompute();
501 
502  /** \brief Internal computation when reciprocal lookup is needed */
503  bool
505 
506  /** \brief Add a new correspondence rejector to the list
507  * \param[in] rejector the new correspondence rejector to concatenate
508  *
509  * Code example:
510  *
511  * \code
512  * CorrespondenceRejectorDistance rej;
513  * rej.setInputCloud<PointXYZ> (keypoints_src);
514  * rej.setInputTarget<PointXYZ> (keypoints_tgt);
515  * rej.setMaximumDistance (1);
516  * rej.setInputCorrespondences (all_correspondences);
517  *
518  * // or...
519  *
520  * \endcode
521  */
522  inline void
524  {
525  correspondence_rejectors_.push_back(rejector);
526  }
527 
528  /** \brief Get the list of correspondence rejectors. */
529  inline std::vector<CorrespondenceRejectorPtr>
531  {
532  return (correspondence_rejectors_);
533  }
534 
535  /** \brief Remove the i-th correspondence rejector in the list
536  * \param[in] i the position of the correspondence rejector in the list to remove
537  */
538  inline bool
540  {
541  if (i >= correspondence_rejectors_.size())
542  return (false);
544  return (true);
545  }
546 
547  /** \brief Clear the list of correspondence rejectors. */
548  inline void
550  {
552  }
553 
554 protected:
555  /** \brief The registration method name. */
556  std::string reg_name_;
557 
558  /** \brief A pointer to the spatial search object. */
560 
561  /** \brief A pointer to the spatial search object of the source. */
563 
564  /** \brief The number of iterations the internal optimization ran for (used
565  * internally). */
567 
568  /** \brief The maximum number of iterations the internal optimization should run for.
569  * The default value is 10.
570  */
572 
573  /** \brief The number of iterations RANSAC should run for. */
575 
576  /** \brief The input point cloud dataset target. */
578 
579  /** \brief The final transformation matrix estimated by the registration method after
580  * N iterations. */
582 
583  /** \brief The transformation matrix estimated by the registration method. */
585 
586  /** \brief The previous transformation matrix estimated by the registration method
587  * (used internally). */
589 
590  /** \brief The maximum difference between two consecutive transformations in order to
591  * consider convergence (user defined).
592  */
594 
595  /** \brief The maximum rotation difference between two consecutive transformations in
596  * order to consider convergence (user defined).
597  */
599 
600  /** \brief The maximum allowed Euclidean error between two consecutive steps in the
601  * ICP loop, before the algorithm is considered to have converged. The error is
602  * estimated as the sum of the differences between correspondences in an Euclidean
603  * sense, divided by the number of correspondences.
604  */
606 
607  /** \brief The maximum distance threshold between two correspondent points in source
608  * <-> target. If the distance is larger than this threshold, the points will be
609  * ignored in the alignment process.
610  */
612 
613  /** \brief The inlier distance threshold for the internal RANSAC outlier rejection
614  * loop. The method considers a point to be an inlier, if the distance between the
615  * target data index and the transformed source index is smaller than the given inlier
616  * distance threshold. The default value is 0.05.
617  */
619 
620  /** \brief Holds internal convergence state, given user parameters. */
622 
623  /** \brief The minimum number of correspondences that the algorithm needs before
624  * attempting to estimate the transformation. The default value is 3.
625  */
627 
628  /** \brief The set of correspondences determined at this ICP step. */
630 
631  /** \brief A TransformationEstimation object, used to calculate the 4x4 rigid
632  * transformation. */
634 
635  /** \brief A CorrespondenceEstimation object, used to estimate correspondences between
636  * the source and the target cloud. */
638 
639  /** \brief The list of correspondence rejectors to use. */
640  std::vector<CorrespondenceRejectorPtr> correspondence_rejectors_;
641 
642  /** \brief Variable that stores whether we have a new target cloud, meaning we need to
643  * pre-process it again. This way, we avoid rebuilding the kd-tree for the target
644  * cloud every time the determineCorrespondences () method is called. */
646  /** \brief Variable that stores whether we have a new source cloud, meaning we need to
647  * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the
648  * source cloud every time the determineCorrespondences () method is called. */
650  /** \brief A flag which, if set, means the tree operating on the target cloud
651  * will never be recomputed*/
653 
654  /** \brief A flag which, if set, means the tree operating on the source cloud
655  * will never be recomputed*/
657 
658  /** \brief Callback function to update intermediate source point cloud position during
659  * it's registration to the target point cloud.
660  */
661  std::function<UpdateVisualizerCallbackSignature> update_visualizer_;
662 
663  /** \brief Search for the closest nearest neighbor of a given point.
664  * \param cloud the point cloud dataset to use for nearest neighbor search
665  * \param index the index of the query point
666  * \param indices the resultant vector of indices representing the k-nearest neighbors
667  * \param distances the resultant distances from the query point to the k-nearest
668  * neighbors
669  */
670  inline bool
672  int index,
673  std::vector<int>& indices,
674  std::vector<float>& distances)
675  {
676  int k = tree_->nearestKSearch(cloud, index, 1, indices, distances);
677  if (k == 0)
678  return (false);
679  return (true);
680  }
681 
682  /** \brief Abstract transformation computation method with initial guess */
683  virtual void
684  computeTransformation(PointCloudSource& output, const Matrix4& guess) = 0;
685 
686 private:
687  /** \brief The point representation used (internal). */
688  PointRepresentationConstPtr point_representation_;
689 
690  /**
691  * \brief Remove from public API in favor of \ref setInputSource
692  *
693  * Still gives the correct result (with a warning)
694  */
695  void
696  setInputCloud(const PointCloudSourceConstPtr& cloud) override
697  {
698  PCL_WARN("[pcl::registration::Registration] setInputCloud is deprecated."
699  "Please use setInputSource instead.\n");
700  setInputSource(cloud);
701  }
702 
703 public:
705 };
706 } // namespace pcl
707 
708 #include <pcl/registration/impl/registration.hpp>
pcl::registration::CorrespondenceRejector::Ptr
shared_ptr< CorrespondenceRejector > Ptr
Definition: correspondence_rejection.h:56
pcl::Registration::hasConverged
bool hasConverged() const
Return the state of convergence after the last align run.
Definition: registration.h:471
pcl_macros.h
Defines all the PCL and non-PCL macros used.
pcl::Registration::target_
PointCloudTargetConstPtr target_
The input point cloud dataset target.
Definition: registration.h:577
pcl::Registration::setCorrespondenceEstimation
void setCorrespondenceEstimation(const CorrespondenceEstimationPtr &ce)
Provide a pointer to the correspondence estimation object.
Definition: registration.h:184
pcl::Registration::target_cloud_updated_
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:645
pcl::Registration::correspondences_
CorrespondencesPtr correspondences_
The set of correspondences determined at this ICP step.
Definition: registration.h:629
pcl
Definition: convolution.h:46
pcl::Registration::setTransformationEstimation
void setTransformationEstimation(const TransformationEstimationPtr &te)
Provide a pointer to the transformation estimation object.
Definition: registration.h:156
pcl::Registration::computeTransformation
virtual void computeTransformation(PointCloudSource &output, const Matrix4 &guess)=0
Abstract transformation computation method with initial guess.
pcl::Registration::ransac_iterations_
int ransac_iterations_
The number of iterations RANSAC should run for.
Definition: registration.h:574
pcl::Registration::getCorrespondenceRejectors
std::vector< CorrespondenceRejectorPtr > getCorrespondenceRejectors()
Get the list of correspondence rejectors.
Definition: registration.h:530
pcl::Registration::setInputSource
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)
Definition: registration.hpp:47
pcl::Registration::addCorrespondenceRejector
void addCorrespondenceRejector(const CorrespondenceRejectorPtr &rejector)
Add a new correspondence rejector to the list.
Definition: registration.h:523
pcl::Registration< PointSource, PointTarget >::CorrespondenceEstimationConstPtr
typename CorrespondenceEstimation::ConstPtr CorrespondenceEstimationConstPtr
Definition: registration.h:94
pcl::Registration::setInputTarget
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...
Definition: registration.hpp:61
pcl::Registration
Registration represents the base registration class for general purpose, ICP-like methods.
Definition: registration.h:57
pcl::Registration::align
void align(PointCloudSource &output)
Call the registration algorithm which estimates the transformation and returns the transformed source...
Definition: registration.hpp:166
pcl::PCLBase< PointSource >::input_
PointCloudConstPtr input_
The input point cloud dataset.
Definition: pcl_base.h:147
pcl::Registration< PointSource, PointTarget >::TransformationEstimationPtr
typename TransformationEstimation::Ptr TransformationEstimationPtr
Definition: registration.h:88
pcl::Registration::getInputSource
const PointCloudSourceConstPtr getInputSource()
Get a pointer to the input point cloud dataset target.
Definition: registration.h:199
pcl::Registration::source_cloud_updated_
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:649
pcl::Registration::euclidean_fitness_epsilon_
double euclidean_fitness_epsilon_
The maximum allowed Euclidean error between two consecutive steps in the ICP loop,...
Definition: registration.h:605
pcl::Registration< PointSource, PointTarget >::PointCloudSourceConstPtr
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
Definition: registration.h:78
pcl::Registration::corr_dist_threshold_
double corr_dist_threshold_
The maximum distance threshold between two correspondent points in source <-> target.
Definition: registration.h:611
pcl::Registration::transformation_rotation_epsilon_
double transformation_rotation_epsilon_
The maximum rotation difference between two consecutive transformations in order to consider converge...
Definition: registration.h:598
pcl::Registration::getMaximumIterations
int getMaximumIterations()
Get the maximum number of iterations the internal optimization should run for, as set by the user.
Definition: registration.h:295
pcl::Registration::getRANSACOutlierRejectionThreshold
double getRANSACOutlierRejectionThreshold()
Get the inlier distance threshold for the internal outlier rejection loop as set by the user.
Definition: registration.h:334
pcl::Registration::getSearchMethodSource
KdTreeReciprocalPtr getSearchMethodSource() const
Get a pointer to the search method used to find correspondences in the source cloud.
Definition: registration.h:261
pcl::Registration::previous_transformation_
Matrix4 previous_transformation_
The previous transformation matrix estimated by the registration method (used internally).
Definition: registration.h:588
pcl::Registration::tree_
KdTreePtr tree_
A pointer to the spatial search object.
Definition: registration.h:559
pcl::Registration::converged_
bool converged_
Holds internal convergence state, given user parameters.
Definition: registration.h:621
pcl::Registration::transformation_
Matrix4 transformation_
The transformation matrix estimated by the registration method.
Definition: registration.h:584
pcl::Registration::getClassName
const std::string & getClassName() const
Abstract class get name method.
Definition: registration.h:493
pcl::Registration::max_iterations_
int max_iterations_
The maximum number of iterations the internal optimization should run for.
Definition: registration.h:571
pcl::PCLBase
PCL base class.
Definition: pcl_base.h:69
pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >
pcl::Registration::min_number_correspondences_
int min_number_correspondences_
The minimum number of correspondences that the algorithm needs before attempting to estimate the tran...
Definition: registration.h:626
pcl::Registration::initComputeReciprocal
bool initComputeReciprocal()
Internal computation when reciprocal lookup is needed.
Definition: registration.hpp:105
pcl::PointCloud< PointSource >
pcl::Registration::getEuclideanFitnessEpsilon
double getEuclideanFitnessEpsilon()
Get the maximum allowed distance error before the algorithm will be considered to have converged,...
Definition: registration.h:422
pcl::Registration< PointSource, PointTarget >::Matrix4
Eigen::Matrix< float, 4, 4 > Matrix4
Definition: registration.h:59
pcl::Registration::removeCorrespondenceRejector
bool removeCorrespondenceRejector(unsigned int i)
Remove the i-th correspondence rejector in the list.
Definition: registration.h:539
pcl::Registration< PointSource, PointTarget >::Ptr
shared_ptr< Registration< PointSource, PointTarget, float > > Ptr
Definition: registration.h:66
pcl::Registration::final_transformation_
Matrix4 final_transformation_
The final transformation matrix estimated by the registration method after N iterations.
Definition: registration.h:581
pcl::search::KdTree::Ptr
shared_ptr< KdTree< PointT, Tree > > Ptr
Definition: kdtree.h:75
pcl::Registration::setRANSACOutlierRejectionThreshold
void setRANSACOutlierRejectionThreshold(double inlier_threshold)
Set the inlier distance threshold for the internal RANSAC outlier rejection loop.
Definition: registration.h:326
pcl::Registration< PointSource, PointTarget >::CorrespondenceEstimationPtr
typename CorrespondenceEstimation::Ptr CorrespondenceEstimationPtr
Definition: registration.h:93
pcl::Registration::Registration
Registration()
Empty constructor.
Definition: registration.h:109
pcl::Registration< PointSource, PointTarget >::PointCloudSourcePtr
typename PointCloudSource::Ptr PointCloudSourcePtr
Definition: registration.h:77
pcl::Registration::getFinalTransformation
Matrix4 getFinalTransformation()
Get the final transformation matrix estimated by the registration method.
Definition: registration.h:269
pcl::Registration::registerVisualizationCallback
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:442
pcl::Registration::transformation_epsilon_
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
Definition: registration.h:593
pcl::Registration::update_visualizer_
std::function< UpdateVisualizerCallbackSignature > update_visualizer_
Callback function to update intermediate source point cloud position during it's registration to the ...
Definition: registration.h:661
pcl::Registration::setPointRepresentation
void setPointRepresentation(const PointRepresentationConstPtr &point_representation)
Provide a boost shared pointer to the PointRepresentation to be used when comparing points.
Definition: registration.h:432
pcl::Registration< PointSource, PointTarget >::PointCloudTargetPtr
typename PointCloudTarget::Ptr PointCloudTargetPtr
Definition: registration.h:81
pcl::Registration::getSearchMethodTarget
KdTreePtr getSearchMethodTarget() const
Get a pointer to the search method used to find correspondences in the target cloud.
Definition: registration.h:236
pcl::Registration::getTransformationEpsilon
double getTransformationEpsilon()
Get the transformation epsilon (maximum allowable translation squared difference between two consecut...
Definition: registration.h:377
pcl::Registration::force_no_recompute_
bool force_no_recompute_
A flag which, if set, means the tree operating on the target cloud will never be recomputed.
Definition: registration.h:652
pcl::registration::CorrespondenceEstimationBase::Ptr
shared_ptr< CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > Ptr
Definition: correspondence_estimation.h:63
pcl::registration::CorrespondenceEstimationBase::ConstPtr
shared_ptr< const CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > ConstPtr
Definition: correspondence_estimation.h:65
pcl::Registration< PointSource, PointTarget >::TransformationEstimation
typename pcl::registration::TransformationEstimation< PointSource, PointTarget, float > TransformationEstimation
Definition: registration.h:87
pcl::search::KdTree::PointRepresentationConstPtr
typename PointRepresentation< PointT >::ConstPtr PointRepresentationConstPtr
Definition: kdtree.h:80
pcl::Registration::tree_reciprocal_
KdTreeReciprocalPtr tree_reciprocal_
A pointer to the spatial search object of the source.
Definition: registration.h:562
pcl::Registration< PointSource, PointTarget >::UpdateVisualizerCallbackSignature
void(const pcl::PointCloud< PointSource > &, const std::vector< int > &, const pcl::PointCloud< PointTarget > &, const std::vector< int > &) UpdateVisualizerCallbackSignature
The callback signature to the function updating intermediate source point cloud position during it's ...
Definition: registration.h:106
pcl::Registration::initCompute
bool initCompute()
Internal computation initialization.
Definition: registration.hpp:75
pcl::search::KdTree
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
Definition: kdtree.h:61
pcl::Registration::~Registration
~Registration()
destructor.
Definition: registration.h:137
pcl::Registration::setTransformationRotationEpsilon
void setTransformationRotationEpsilon(double epsilon)
Set the transformation rotation epsilon (maximum allowable rotation difference between two consecutiv...
Definition: registration.h:390
pcl::Registration::setMaximumIterations
void setMaximumIterations(int nr_iterations)
Set the maximum number of iterations the internal optimization should run for.
Definition: registration.h:287
PCL_MAKE_ALIGNED_OPERATOR_NEW
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
pcl::Registration< PointSource, PointTarget >::CorrespondenceRejectorPtr
pcl::registration::CorrespondenceRejector::Ptr CorrespondenceRejectorPtr
Definition: registration.h:69
pcl::Registration< PointSource, PointTarget >::TransformationEstimationConstPtr
typename TransformationEstimation::ConstPtr TransformationEstimationConstPtr
Definition: registration.h:89
pcl::Registration::correspondence_rejectors_
std::vector< CorrespondenceRejectorPtr > correspondence_rejectors_
The list of correspondence rejectors to use.
Definition: registration.h:640
pcl::Registration::getTransformationRotationEpsilon
double getTransformationRotationEpsilon()
Get the transformation rotation epsilon (maximum allowable difference between two consecutive transfo...
Definition: registration.h:400
pcl::Registration::PointCloudSource
pcl::PointCloud< PointSource > PointCloudSource
Definition: registration.h:76
pcl::Registration::getRANSACIterations
double getRANSACIterations()
Get the number of iterations RANSAC should run for, as set by the user.
Definition: registration.h:311
pcl::Registration::getInputTarget
const PointCloudTargetConstPtr getInputTarget()
Get a pointer to the input point cloud dataset target.
Definition: registration.h:212
pcl::Registration::searchForNeighbors
bool searchForNeighbors(const PointCloudSource &cloud, int index, std::vector< int > &indices, std::vector< float > &distances)
Search for the closest nearest neighbor of a given point.
Definition: registration.h:671
pcl::Registration< PointSource, PointTarget >::KdTreeReciprocalPtr
typename KdTreeReciprocal::Ptr KdTreeReciprocalPtr
Definition: registration.h:74
pcl::PointCloud< PointSource >::Ptr
shared_ptr< PointCloud< PointSource > > Ptr
Definition: point_cloud.h:406
pcl::Registration< PointSource, PointTarget >::KdTreePtr
typename KdTree::Ptr KdTreePtr
Definition: registration.h:71
pcl::Registration::force_no_recompute_reciprocal_
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:656
pcl::Registration::setSearchMethodTarget
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:225
pcl::Registration::nr_iterations_
int nr_iterations_
The number of iterations the internal optimization ran for (used internally).
Definition: registration.h:566
pcl::Registration::setSearchMethodSource
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:249
pcl::Registration::getFitnessScore
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)
Definition: registration.hpp:134
pcl::PointCloud< PointSource >::ConstPtr
shared_ptr< const PointCloud< PointSource > > ConstPtr
Definition: point_cloud.h:407
pcl::Registration< PointSource, PointTarget >::PointCloudTargetConstPtr
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
Definition: registration.h:82
pcl::Correspondences
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
Definition: correspondence.h:89
pcl::Registration::transformation_estimation_
TransformationEstimationPtr transformation_estimation_
A TransformationEstimation object, used to calculate the 4x4 rigid transformation.
Definition: registration.h:633
pcl::Registration::setRANSACIterations
void setRANSACIterations(int ransac_iterations)
Set the number of iterations RANSAC should run for.
Definition: registration.h:304
pcl::CorrespondencesPtr
shared_ptr< Correspondences > CorrespondencesPtr
Definition: correspondence.h:90
pcl::Registration::clearCorrespondenceRejectors
void clearCorrespondenceRejectors()
Clear the list of correspondence rejectors.
Definition: registration.h:549
pcl::Registration::setEuclideanFitnessEpsilon
void setEuclideanFitnessEpsilon(double epsilon)
Set the maximum allowed Euclidean error between two consecutive steps in the ICP loop,...
Definition: registration.h:412
pcl::Registration::getLastIncrementalTransformation
Matrix4 getLastIncrementalTransformation()
Get the last incremental transformation matrix estimated by the registration method.
Definition: registration.h:277
pcl::Registration::setMaxCorrespondenceDistance
void setMaxCorrespondenceDistance(double distance_threshold)
Set the maximum distance threshold between two correspondent points in source <-> target.
Definition: registration.h:346
memory.h
Defines functions, macros and traits for allocating and using memory.
pcl::Registration< PointSource, PointTarget >::PointRepresentationConstPtr
typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr
Definition: registration.h:84
pcl::Registration::getMaxCorrespondenceDistance
double getMaxCorrespondenceDistance()
Get the maximum distance threshold between two correspondent points in source <-> target.
Definition: registration.h:356
pcl::Registration::reg_name_
std::string reg_name_
The registration method name.
Definition: registration.h:556
pcl::Registration< PointSource, PointTarget >::ConstPtr
shared_ptr< const Registration< PointSource, PointTarget, float > > ConstPtr
Definition: registration.h:67
pcl::Registration::correspondence_estimation_
CorrespondenceEstimationPtr correspondence_estimation_
A CorrespondenceEstimation object, used to estimate correspondences between the source and the target...
Definition: registration.h:637
pcl::Registration::setTransformationEpsilon
void setTransformationEpsilon(double epsilon)
Set the transformation epsilon (maximum allowable translation squared difference between two consecut...
Definition: registration.h:368
pcl::Registration::inlier_threshold_
double inlier_threshold_
The inlier distance threshold for the internal RANSAC outlier rejection loop.
Definition: registration.h:618