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;
62   using PCLBase<PointSource>::deinitCompute;
63   using PCLBase<PointSource>::input_;
64   using PCLBase<PointSource>::indices_;
65 
66   using Ptr = shared_ptr<Registration<PointSource, PointTarget, Scalar>>;
67   using ConstPtr = shared_ptr<const Registration<PointSource, PointTarget, Scalar>>;
68 
69   using CorrespondenceRejectorPtr = pcl::registration::CorrespondenceRejector::Ptr;
70   using KdTree = pcl::search::KdTree<PointTarget>;
71   using KdTreePtr = typename KdTree::Ptr;
72 
73   using KdTreeReciprocal = pcl::search::KdTree<PointSource>;
74   using KdTreeReciprocalPtr = typename KdTreeReciprocal::Ptr;
75 
76   using PointCloudSource = pcl::PointCloud<PointSource>;
77   using PointCloudSourcePtr = typename PointCloudSource::Ptr;
78   using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;
79 
80   using PointCloudTarget = pcl::PointCloud<PointTarget>;
81   using PointCloudTargetPtr = typename PointCloudTarget::Ptr;
82   using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;
83 
84   using PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr;
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 
91   using CorrespondenceEstimation =
92       pcl::registration::CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>;
93   using CorrespondenceEstimationPtr = typename CorrespondenceEstimation::Ptr;
94   using CorrespondenceEstimationConstPtr = typename CorrespondenceEstimation::ConstPtr;
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    */
103   using UpdateVisualizerCallbackSignature = void(const pcl::PointCloud<PointSource>&,
104                                                  const pcl::Indices&,
105                                                  const pcl::PointCloud<PointTarget>&,
106                                                  const pcl::Indices&);
107 
108   /** \brief Empty constructor. */
Registration()109   Registration()
110   : tree_(new KdTree)
111   , tree_reciprocal_(new KdTreeReciprocal)
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())
119   , transformation_epsilon_(0.0)
120   , transformation_rotation_epsilon_(0.0)
121   , euclidean_fitness_epsilon_(-std::numeric_limits<double>::max())
122   , corr_dist_threshold_(::sqrt(std::numeric_limits<double>::max()))
123   , inlier_threshold_(0.05)
124   , converged_(false)
125   , min_number_correspondences_(3)
126   , correspondences_(new Correspondences)
127   , transformation_estimation_()
128   , correspondence_estimation_()
129   , target_cloud_updated_(true)
130   , source_cloud_updated_(true)
131   , force_no_recompute_(false)
132   , force_no_recompute_reciprocal_(false)
133   , point_representation_()
134   {}
135 
136   /** \brief destructor. */
~Registration()137   ~Registration() {}
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
setTransformationEstimation(const TransformationEstimationPtr & te)157   setTransformationEstimation(const TransformationEstimationPtr& te)
158   {
159     transformation_estimation_ = te;
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
setCorrespondenceEstimation(const CorrespondenceEstimationPtr & ce)186   setCorrespondenceEstimation(const CorrespondenceEstimationPtr& ce)
187   {
188     correspondence_estimation_ = ce;
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
197   setInputSource(const PointCloudSourceConstPtr& cloud);
198 
199   /** \brief Get a pointer to the input point cloud dataset target. */
200   inline PointCloudSourceConstPtr const
getInputSource()201   getInputSource()
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
210   setInputTarget(const PointCloudTargetConstPtr& cloud);
211 
212   /** \brief Get a pointer to the input point cloud dataset target. */
213   inline PointCloudTargetConstPtr const
getInputTarget()214   getInputTarget()
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
getSearchMethodTarget()238   getSearchMethodTarget() const
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
251   setSearchMethodSource(const KdTreeReciprocalPtr& tree,
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
getSearchMethodSource()263   getSearchMethodSource() const
264   {
265     return (tree_reciprocal_);
266   }
267 
268   /** \brief Get the final transformation matrix estimated by the registration method.
269    */
270   inline Matrix4
getFinalTransformation()271   getFinalTransformation()
272   {
273     return (final_transformation_);
274   }
275 
276   /** \brief Get the last incremental transformation matrix estimated by the
277    * registration method. */
278   inline Matrix4
getLastIncrementalTransformation()279   getLastIncrementalTransformation()
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
setMaximumIterations(int nr_iterations)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
getMaximumIterations()297   getMaximumIterations()
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
setRANSACIterations(int ransac_iterations)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
getRANSACIterations()313   getRANSACIterations()
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
setRANSACOutlierRejectionThreshold(double inlier_threshold)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
getRANSACOutlierRejectionThreshold()336   getRANSACOutlierRejectionThreshold()
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
setMaxCorrespondenceDistance(double distance_threshold)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
getMaxCorrespondenceDistance()358   getMaxCorrespondenceDistance()
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
setTransformationEpsilon(double epsilon)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
getTransformationEpsilon()379   getTransformationEpsilon()
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
setTransformationRotationEpsilon(double epsilon)392   setTransformationRotationEpsilon(double epsilon)
393   {
394     transformation_rotation_epsilon_ = epsilon;
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
getTransformationRotationEpsilon()402   getTransformationRotationEpsilon()
403   {
404     return (transformation_rotation_epsilon_);
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
setEuclideanFitnessEpsilon(double epsilon)414   setEuclideanFitnessEpsilon(double epsilon)
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
getEuclideanFitnessEpsilon()424   getEuclideanFitnessEpsilon()
425   {
426     return (euclidean_fitness_epsilon_);
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
setPointRepresentation(const PointRepresentationConstPtr & point_representation)434   setPointRepresentation(const PointRepresentationConstPtr& point_representation)
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
registerVisualizationCallback(std::function<UpdateVisualizerCallbackSignature> & visualizerCallback)444   registerVisualizationCallback(
445       std::function<UpdateVisualizerCallbackSignature>& visualizerCallback)
446   {
447     if (visualizerCallback) {
448       update_visualizer_ = visualizerCallback;
449       return (true);
450     }
451     return (false);
452   }
453 
454   /** \brief Obtain the Euclidean fitness score (e.g., mean of squared distances from
455    * the source to the target) \param[in] max_range maximum allowable distance between a
456    * point and its correspondence in the target (default: double::max)
457    */
458   inline double
459   getFitnessScore(double max_range = std::numeric_limits<double>::max());
460 
461   /** \brief Obtain the Euclidean fitness score (e.g., mean of squared distances from
462    * the source to the target) from two sets of correspondence distances (distances
463    * between source and target points) \param[in] distances_a the first set of distances
464    * between correspondences \param[in] distances_b the second set of distances between
465    * correspondences
466    */
467   inline double
468   getFitnessScore(const std::vector<float>& distances_a,
469                   const std::vector<float>& distances_b);
470 
471   /** \brief Return the state of convergence after the last align run */
472   inline bool
hasConverged()473   hasConverged() const
474   {
475     return (converged_);
476   }
477 
478   /** \brief Call the registration algorithm which estimates the transformation and
479    * returns the transformed source (input) as \a output. \param[out] output the
480    * resultant input transformed point cloud dataset
481    */
482   inline void
483   align(PointCloudSource& output);
484 
485   /** \brief Call the registration algorithm which estimates the transformation and
486    * returns the transformed source (input) as \a output. \param[out] output the
487    * resultant input transformed point cloud dataset \param[in] guess the initial gross
488    * estimation of the transformation
489    */
490   inline void
491   align(PointCloudSource& output, const Matrix4& guess);
492 
493   /** \brief Abstract class get name method. */
494   inline const std::string&
getClassName()495   getClassName() const
496   {
497     return (reg_name_);
498   }
499 
500   /** \brief Internal computation initialization. */
501   bool
502   initCompute();
503 
504   /** \brief Internal computation when reciprocal lookup is needed */
505   bool
506   initComputeReciprocal();
507 
508   /** \brief Add a new correspondence rejector to the list
509    * \param[in] rejector the new correspondence rejector to concatenate
510    *
511    * Code example:
512    *
513    * \code
514    * CorrespondenceRejectorDistance rej;
515    * rej.setInputCloud<PointXYZ> (keypoints_src);
516    * rej.setInputTarget<PointXYZ> (keypoints_tgt);
517    * rej.setMaximumDistance (1);
518    * rej.setInputCorrespondences (all_correspondences);
519    *
520    * // or...
521    *
522    * \endcode
523    */
524   inline void
addCorrespondenceRejector(const CorrespondenceRejectorPtr & rejector)525   addCorrespondenceRejector(const CorrespondenceRejectorPtr& rejector)
526   {
527     correspondence_rejectors_.push_back(rejector);
528   }
529 
530   /** \brief Get the list of correspondence rejectors. */
531   inline std::vector<CorrespondenceRejectorPtr>
getCorrespondenceRejectors()532   getCorrespondenceRejectors()
533   {
534     return (correspondence_rejectors_);
535   }
536 
537   /** \brief Remove the i-th correspondence rejector in the list
538    * \param[in] i the position of the correspondence rejector in the list to remove
539    */
540   inline bool
removeCorrespondenceRejector(unsigned int i)541   removeCorrespondenceRejector(unsigned int i)
542   {
543     if (i >= correspondence_rejectors_.size())
544       return (false);
545     correspondence_rejectors_.erase(correspondence_rejectors_.begin() + i);
546     return (true);
547   }
548 
549   /** \brief Clear the list of correspondence rejectors. */
550   inline void
clearCorrespondenceRejectors()551   clearCorrespondenceRejectors()
552   {
553     correspondence_rejectors_.clear();
554   }
555 
556 protected:
557   /** \brief The registration method name. */
558   std::string reg_name_;
559 
560   /** \brief A pointer to the spatial search object. */
561   KdTreePtr tree_;
562 
563   /** \brief A pointer to the spatial search object of the source. */
564   KdTreeReciprocalPtr tree_reciprocal_;
565 
566   /** \brief The number of iterations the internal optimization ran for (used
567    * internally). */
568   int nr_iterations_;
569 
570   /** \brief The maximum number of iterations the internal optimization should run for.
571    * The default value is 10.
572    */
573   int max_iterations_;
574 
575   /** \brief The number of iterations RANSAC should run for. */
576   int ransac_iterations_;
577 
578   /** \brief The input point cloud dataset target. */
579   PointCloudTargetConstPtr target_;
580 
581   /** \brief The final transformation matrix estimated by the registration method after
582    * N iterations. */
583   Matrix4 final_transformation_;
584 
585   /** \brief The transformation matrix estimated by the registration method. */
586   Matrix4 transformation_;
587 
588   /** \brief The previous transformation matrix estimated by the registration method
589    * (used internally). */
590   Matrix4 previous_transformation_;
591 
592   /** \brief The maximum difference between two consecutive transformations in order to
593    * consider convergence (user defined).
594    */
595   double transformation_epsilon_;
596 
597   /** \brief The maximum rotation difference between two consecutive transformations in
598    * order to consider convergence (user defined).
599    */
600   double transformation_rotation_epsilon_;
601 
602   /** \brief The maximum allowed Euclidean error between two consecutive steps in the
603    * ICP loop, before the algorithm is considered to have converged. The error is
604    * estimated as the sum of the differences between correspondences in an Euclidean
605    * sense, divided by the number of correspondences.
606    */
607   double euclidean_fitness_epsilon_;
608 
609   /** \brief The maximum distance threshold between two correspondent points in source
610    * <-> target. If the distance is larger than this threshold, the points will be
611    * ignored in the alignment process.
612    */
613   double corr_dist_threshold_;
614 
615   /** \brief The inlier distance threshold for the internal RANSAC outlier rejection
616    * loop. The method considers a point to be an inlier, if the distance between the
617    * target data index and the transformed source index is smaller than the given inlier
618    * distance threshold. The default value is 0.05.
619    */
620   double inlier_threshold_;
621 
622   /** \brief Holds internal convergence state, given user parameters. */
623   bool converged_;
624 
625   /** \brief The minimum number of correspondences that the algorithm needs before
626    * attempting to estimate the transformation. The default value is 3.
627    */
628   int min_number_correspondences_;
629 
630   /** \brief The set of correspondences determined at this ICP step. */
631   CorrespondencesPtr correspondences_;
632 
633   /** \brief A TransformationEstimation object, used to calculate the 4x4 rigid
634    * transformation. */
635   TransformationEstimationPtr transformation_estimation_;
636 
637   /** \brief A CorrespondenceEstimation object, used to estimate correspondences between
638    * the source and the target cloud. */
639   CorrespondenceEstimationPtr correspondence_estimation_;
640 
641   /** \brief The list of correspondence rejectors to use. */
642   std::vector<CorrespondenceRejectorPtr> correspondence_rejectors_;
643 
644   /** \brief Variable that stores whether we have a new target cloud, meaning we need to
645    * pre-process it again. This way, we avoid rebuilding the kd-tree for the target
646    * cloud every time the determineCorrespondences () method is called. */
647   bool target_cloud_updated_;
648   /** \brief Variable that stores whether we have a new source cloud, meaning we need to
649    * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the
650    * source cloud every time the determineCorrespondences () method is called. */
651   bool source_cloud_updated_;
652   /** \brief A flag which, if set, means the tree operating on the target cloud
653    * will never be recomputed*/
654   bool force_no_recompute_;
655 
656   /** \brief A flag which, if set, means the tree operating on the source cloud
657    * will never be recomputed*/
658   bool force_no_recompute_reciprocal_;
659 
660   /** \brief Callback function to update intermediate source point cloud position during
661    * it's registration to the target point cloud.
662    */
663   std::function<UpdateVisualizerCallbackSignature> update_visualizer_;
664 
665   /** \brief Search for the closest nearest neighbor of a given point.
666    * \param cloud the point cloud dataset to use for nearest neighbor search
667    * \param index the index of the query point
668    * \param indices the resultant vector of indices representing the k-nearest neighbors
669    * \param distances the resultant distances from the query point to the k-nearest
670    * neighbors
671    */
672   inline bool
searchForNeighbors(const PointCloudSource & cloud,int index,pcl::Indices & indices,std::vector<float> & distances)673   searchForNeighbors(const PointCloudSource& cloud,
674                      int index,
675                      pcl::Indices& indices,
676                      std::vector<float>& distances)
677   {
678     int k = tree_->nearestKSearch(cloud, index, 1, indices, distances);
679     if (k == 0)
680       return (false);
681     return (true);
682   }
683 
684   /** \brief Abstract transformation computation method with initial guess */
685   virtual void
686   computeTransformation(PointCloudSource& output, const Matrix4& guess) = 0;
687 
688 private:
689   /** \brief The point representation used (internal). */
690   PointRepresentationConstPtr point_representation_;
691 
692   /**
693    * \brief Remove from public API in favor of \ref setInputSource
694    *
695    * Still gives the correct result (with a warning)
696    */
697   void
setInputCloud(const PointCloudSourceConstPtr & cloud)698   setInputCloud(const PointCloudSourceConstPtr& cloud) override
699   {
700     PCL_WARN("[pcl::registration::Registration] setInputCloud is deprecated."
701              "Please use setInputSource instead.\n");
702     setInputSource(cloud);
703   }
704 
705 public:
706   PCL_MAKE_ALIGNED_OPERATOR_NEW
707 };
708 } // namespace pcl
709 
710 #include <pcl/registration/impl/registration.hpp>
711