Point Cloud Library (PCL)  1.14.0-dev
List of all members | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::Registration< PointSource, PointTarget, Scalar > Class Template Referenceabstract

Registration represents the base registration class for general purpose, ICP-like methods. More...

#include <pcl/registration/registration.h>

+ Inheritance diagram for pcl::Registration< PointSource, PointTarget, Scalar >:
+ Collaboration diagram for pcl::Registration< PointSource, PointTarget, Scalar >:

Public Types

using Matrix4 = Eigen::Matrix< Scalar, 4, 4 >
 
using Ptr = shared_ptr< Registration< PointSource, PointTarget, Scalar > >
 
using ConstPtr = shared_ptr< const Registration< PointSource, PointTarget, Scalar > >
 
using CorrespondenceRejectorPtr = pcl::registration::CorrespondenceRejector::Ptr
 
using KdTree = pcl::search::KdTree< PointTarget >
 
using KdTreePtr = typename KdTree::Ptr
 
using KdTreeReciprocal = pcl::search::KdTree< PointSource >
 
using KdTreeReciprocalPtr = typename KdTreeReciprocal::Ptr
 
using PointCloudSource = pcl::PointCloud< PointSource >
 
using PointCloudSourcePtr = typename PointCloudSource::Ptr
 
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr
 
using PointCloudTarget = pcl::PointCloud< PointTarget >
 
using PointCloudTargetPtr = typename PointCloudTarget::Ptr
 
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr
 
using PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr
 
using TransformationEstimation = typename pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar >
 
using TransformationEstimationPtr = typename TransformationEstimation::Ptr
 
using TransformationEstimationConstPtr = typename TransformationEstimation::ConstPtr
 
using CorrespondenceEstimation = pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >
 
using CorrespondenceEstimationPtr = typename CorrespondenceEstimation::Ptr
 
using CorrespondenceEstimationConstPtr = typename CorrespondenceEstimation::ConstPtr
 
using UpdateVisualizerCallbackSignature = void(const pcl::PointCloud< PointSource > &, const pcl::Indices &, const pcl::PointCloud< PointTarget > &, const pcl::Indices &)
 The callback signature to the function updating intermediate source point cloud position during it's registration to the target point cloud. More...
 
- Public Types inherited from pcl::PCLBase< PointSource >
using PointCloud = pcl::PointCloud< PointSource >
 
using PointCloudPtr = typename PointCloud::Ptr
 
using PointCloudConstPtr = typename PointCloud::ConstPtr
 
using PointIndicesPtr = PointIndices::Ptr
 
using PointIndicesConstPtr = PointIndices::ConstPtr
 

Public Member Functions

 Registration ()
 Empty constructor. More...
 
 ~Registration () override=default
 destructor. More...
 
void setTransformationEstimation (const TransformationEstimationPtr &te)
 Provide a pointer to the transformation estimation object. More...
 
void setCorrespondenceEstimation (const CorrespondenceEstimationPtr &ce)
 Provide a pointer to the correspondence estimation object. More...
 
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) More...
 
PointCloudSourceConstPtr const getInputSource ()
 Get a pointer to the input point cloud dataset target. More...
 
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 to) More...
 
PointCloudTargetConstPtr const getInputTarget ()
 Get a pointer to the input point cloud dataset target. More...
 
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. More...
 
KdTreePtr getSearchMethodTarget () const
 Get a pointer to the search method used to find correspondences in the target cloud. More...
 
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 by reciprocal correspondence finding). More...
 
KdTreeReciprocalPtr getSearchMethodSource () const
 Get a pointer to the search method used to find correspondences in the source cloud. More...
 
Matrix4 getFinalTransformation ()
 Get the final transformation matrix estimated by the registration method. More...
 
Matrix4 getLastIncrementalTransformation ()
 Get the last incremental transformation matrix estimated by the registration method. More...
 
void setMaximumIterations (int nr_iterations)
 Set the maximum number of iterations the internal optimization should run for. More...
 
int getMaximumIterations ()
 Get the maximum number of iterations the internal optimization should run for, as set by the user. More...
 
void setRANSACIterations (int ransac_iterations)
 Set the number of iterations RANSAC should run for. More...
 
double getRANSACIterations ()
 Get the number of iterations RANSAC should run for, as set by the user. More...
 
void setRANSACOutlierRejectionThreshold (double inlier_threshold)
 Set the inlier distance threshold for the internal RANSAC outlier rejection loop. More...
 
double getRANSACOutlierRejectionThreshold ()
 Get the inlier distance threshold for the internal outlier rejection loop as set by the user. More...
 
void setMaxCorrespondenceDistance (double distance_threshold)
 Set the maximum distance threshold between two correspondent points in source <-> target. More...
 
double getMaxCorrespondenceDistance ()
 Get the maximum distance threshold between two correspondent points in source <-> target. More...
 
void setTransformationEpsilon (double epsilon)
 Set the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution. More...
 
double getTransformationEpsilon ()
 Get the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) as set by the user. More...
 
void setTransformationRotationEpsilon (double epsilon)
 Set the transformation rotation epsilon (maximum allowable rotation difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution. More...
 
double getTransformationRotationEpsilon ()
 Get the transformation rotation epsilon (maximum allowable difference between two consecutive transformations) as set by the user (epsilon is the cos(angle) in a axis-angle representation). More...
 
void setEuclideanFitnessEpsilon (double epsilon)
 Set the maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged. More...
 
double getEuclideanFitnessEpsilon ()
 Get the maximum allowed distance error before the algorithm will be considered to have converged, as set by the user. More...
 
void setPointRepresentation (const PointRepresentationConstPtr &point_representation)
 Provide a boost shared pointer to the PointRepresentation to be used when comparing points. More...
 
bool registerVisualizationCallback (std::function< UpdateVisualizerCallbackSignature > &visualizerCallback)
 Register the user callback function which will be called from registration thread in order to update point cloud obtained after each iteration. More...
 
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) More...
 
double getFitnessScore (const std::vector< float > &distances_a, const std::vector< float > &distances_b)
 Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target) from two sets of correspondence distances (distances between source and target points) More...
 
bool hasConverged () const
 Return the state of convergence after the last align run. More...
 
void align (PointCloudSource &output)
 Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output. More...
 
void align (PointCloudSource &output, const Matrix4 &guess)
 Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output. More...
 
const std::string & getClassName () const
 Abstract class get name method. More...
 
bool initCompute ()
 Internal computation initialization. More...
 
bool initComputeReciprocal ()
 Internal computation when reciprocal lookup is needed. More...
 
void addCorrespondenceRejector (const CorrespondenceRejectorPtr &rejector)
 Add a new correspondence rejector to the list. More...
 
std::vector< CorrespondenceRejectorPtrgetCorrespondenceRejectors ()
 Get the list of correspondence rejectors. More...
 
bool removeCorrespondenceRejector (unsigned int i)
 Remove the i-th correspondence rejector in the list. More...
 
void clearCorrespondenceRejectors ()
 Clear the list of correspondence rejectors. More...
 
- Public Member Functions inherited from pcl::PCLBase< PointSource >
 PCLBase ()
 Empty constructor. More...
 
 PCLBase (const PCLBase &base)
 Copy constructor. More...
 
virtual ~PCLBase ()=default
 Destructor. More...
 
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset. More...
 
PointCloudConstPtr const getInputCloud () const
 Get a pointer to the input point cloud dataset. More...
 
virtual void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud. More...
 
IndicesPtr getIndices ()
 Get a pointer to the vector of indices used. More...
 
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used. More...
 
const PointSource & operator[] (std::size_t pos) const
 Override PointCloud operator[] to shorten code. More...
 

Protected Member Functions

bool searchForNeighbors (const PointCloudSource &cloud, int index, pcl::Indices &indices, std::vector< float > &distances)
 Search for the closest nearest neighbor of a given point. More...
 
virtual void computeTransformation (PointCloudSource &output, const Matrix4 &guess)=0
 Abstract transformation computation method with initial guess. More...
 
- Protected Member Functions inherited from pcl::PCLBase< PointSource >
bool initCompute ()
 This method should get called before starting the actual computation. More...
 
bool deinitCompute ()
 This method should get called after finishing the actual computation. More...
 

Protected Attributes

std::string reg_name_
 The registration method name. More...
 
KdTreePtr tree_
 A pointer to the spatial search object. More...
 
KdTreeReciprocalPtr tree_reciprocal_
 A pointer to the spatial search object of the source. More...
 
int nr_iterations_ {0}
 The number of iterations the internal optimization ran for (used internally). More...
 
int max_iterations_ {10}
 The maximum number of iterations the internal optimization should run for. More...
 
int ransac_iterations_ {0}
 The number of iterations RANSAC should run for. More...
 
PointCloudTargetConstPtr target_
 The input point cloud dataset target. More...
 
Matrix4 final_transformation_
 The final transformation matrix estimated by the registration method after N iterations. More...
 
Matrix4 transformation_
 The transformation matrix estimated by the registration method. More...
 
Matrix4 previous_transformation_
 The previous transformation matrix estimated by the registration method (used internally). More...
 
double transformation_epsilon_ {0.0}
 The maximum difference between two consecutive transformations in order to consider convergence (user defined). More...
 
double transformation_rotation_epsilon_ {0.0}
 The maximum rotation difference between two consecutive transformations in order to consider convergence (user defined). More...
 
double euclidean_fitness_epsilon_
 The maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged. More...
 
double corr_dist_threshold_
 The maximum distance threshold between two correspondent points in source <-> target. More...
 
double inlier_threshold_ {0.05}
 The inlier distance threshold for the internal RANSAC outlier rejection loop. More...
 
bool converged_ {false}
 Holds internal convergence state, given user parameters. More...
 
unsigned int min_number_correspondences_ {3}
 The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation. More...
 
CorrespondencesPtr correspondences_
 The set of correspondences determined at this ICP step. More...
 
TransformationEstimationPtr transformation_estimation_
 A TransformationEstimation object, used to calculate the 4x4 rigid transformation. More...
 
CorrespondenceEstimationPtr correspondence_estimation_
 A CorrespondenceEstimation object, used to estimate correspondences between the source and the target cloud. More...
 
std::vector< CorrespondenceRejectorPtrcorrespondence_rejectors_
 The list of correspondence rejectors to use. More...
 
bool target_cloud_updated_ {true}
 Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. More...
 
bool source_cloud_updated_ {true}
 Variable that stores whether we have a new source cloud, meaning we need to pre-process it again. More...
 
bool force_no_recompute_ {false}
 A flag which, if set, means the tree operating on the target cloud will never be recomputed. More...
 
bool force_no_recompute_reciprocal_ {false}
 A flag which, if set, means the tree operating on the source cloud will never be recomputed. More...
 
std::function< UpdateVisualizerCallbackSignatureupdate_visualizer_
 Callback function to update intermediate source point cloud position during it's registration to the target point cloud. More...
 
- Protected Attributes inherited from pcl::PCLBase< PointSource >
PointCloudConstPtr input_
 The input point cloud dataset. More...
 
IndicesPtr indices_
 A pointer to the vector of point indices to use. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More...
 

Detailed Description

template<typename PointSource, typename PointTarget, typename Scalar = float>
class pcl::Registration< PointSource, PointTarget, Scalar >

Registration represents the base registration class for general purpose, ICP-like methods.

Author
Radu B. Rusu, Michael Dixon

Definition at line 57 of file registration.h.

Member Typedef Documentation

◆ ConstPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::ConstPtr = shared_ptr<const Registration<PointSource, PointTarget, Scalar> >

Definition at line 67 of file registration.h.

◆ CorrespondenceEstimation

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimation = pcl::registration::CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>

Definition at line 91 of file registration.h.

◆ CorrespondenceEstimationConstPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimationConstPtr = typename CorrespondenceEstimation::ConstPtr

Definition at line 94 of file registration.h.

◆ CorrespondenceEstimationPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimationPtr = typename CorrespondenceEstimation::Ptr

Definition at line 93 of file registration.h.

◆ CorrespondenceRejectorPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceRejectorPtr = pcl::registration::CorrespondenceRejector::Ptr

Definition at line 69 of file registration.h.

◆ KdTree

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::KdTree = pcl::search::KdTree<PointTarget>

Definition at line 70 of file registration.h.

◆ KdTreePtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::KdTreePtr = typename KdTree::Ptr

Definition at line 71 of file registration.h.

◆ KdTreeReciprocal

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::KdTreeReciprocal = pcl::search::KdTree<PointSource>

Definition at line 73 of file registration.h.

◆ KdTreeReciprocalPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::KdTreeReciprocalPtr = typename KdTreeReciprocal::Ptr

Definition at line 74 of file registration.h.

◆ Matrix4

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::Matrix4 = Eigen::Matrix<Scalar, 4, 4>

Definition at line 59 of file registration.h.

◆ PointCloudSource

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSource = pcl::PointCloud<PointSource>

Definition at line 76 of file registration.h.

◆ PointCloudSourceConstPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr

Definition at line 78 of file registration.h.

◆ PointCloudSourcePtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSourcePtr = typename PointCloudSource::Ptr

Definition at line 77 of file registration.h.

◆ PointCloudTarget

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTarget = pcl::PointCloud<PointTarget>

Definition at line 80 of file registration.h.

◆ PointCloudTargetConstPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr

Definition at line 82 of file registration.h.

◆ PointCloudTargetPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTargetPtr = typename PointCloudTarget::Ptr

Definition at line 81 of file registration.h.

◆ PointRepresentationConstPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr

Definition at line 84 of file registration.h.

◆ Ptr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::Ptr = shared_ptr<Registration<PointSource, PointTarget, Scalar> >

Definition at line 66 of file registration.h.

◆ TransformationEstimation

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimation = typename pcl::registration:: TransformationEstimation<PointSource, PointTarget, Scalar>

Definition at line 86 of file registration.h.

◆ TransformationEstimationConstPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimationConstPtr = typename TransformationEstimation::ConstPtr

Definition at line 89 of file registration.h.

◆ TransformationEstimationPtr

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimationPtr = typename TransformationEstimation::Ptr

Definition at line 88 of file registration.h.

◆ UpdateVisualizerCallbackSignature

template<typename PointSource , typename PointTarget , typename Scalar = float>
using pcl::Registration< PointSource, PointTarget, Scalar >::UpdateVisualizerCallbackSignature = void(const pcl::PointCloud<PointSource>&, const pcl::Indices&, const pcl::PointCloud<PointTarget>&, const pcl::Indices&)

The callback signature to the function updating intermediate source point cloud position during it's registration to the target point cloud.

Parameters
[in]cloud_src- the point cloud which will be updated to match target
[in]indices_src- a selector of points in cloud_src
[in]cloud_tgt- the point cloud we want to register against
[in]indices_tgt- a selector of points in cloud_tgt

Definition at line 103 of file registration.h.

Constructor & Destructor Documentation

◆ Registration()

template<typename PointSource , typename PointTarget , typename Scalar = float>
pcl::Registration< PointSource, PointTarget, Scalar >::Registration ( )
inline

Empty constructor.

Definition at line 109 of file registration.h.

◆ ~Registration()

template<typename PointSource , typename PointTarget , typename Scalar = float>
pcl::Registration< PointSource, PointTarget, Scalar >::~Registration ( )
overridedefault

destructor.

Member Function Documentation

◆ addCorrespondenceRejector()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::addCorrespondenceRejector ( const CorrespondenceRejectorPtr rejector)
inline

Add a new correspondence rejector to the list.

Parameters
[in]rejectorthe new correspondence rejector to concatenate

Code example:

CorrespondenceRejectorDistance rej;
rej.setInputCloud<PointXYZ> (keypoints_src);
rej.setInputTarget<PointXYZ> (keypoints_tgt);
rej.setMaximumDistance (1);
rej.setInputCorrespondences (all_correspondences);
// or...

Definition at line 515 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_rejectors_.

◆ align() [1/2]

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::Registration< PointSource, PointTarget, Scalar >::align ( PointCloudSource output)
inline

Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.

Parameters
[out]outputthe resultant input transformed point cloud dataset

Definition at line 166 of file registration.hpp.

◆ align() [2/2]

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::Registration< PointSource, PointTarget, Scalar >::align ( PointCloudSource output,
const Matrix4 guess 
)
inline

Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.

Parameters
[out]outputthe resultant input transformed point cloud dataset
[in]guessthe initial gross estimation of the transformation

Definition at line 173 of file registration.hpp.

References pcl::PointCloud< PointT >::header, and pcl::PointCloud< PointT >::resize().

◆ clearCorrespondenceRejectors()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::clearCorrespondenceRejectors ( )
inline

Clear the list of correspondence rejectors.

Definition at line 541 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_rejectors_.

◆ computeTransformation()

template<typename PointSource , typename PointTarget , typename Scalar = float>
virtual void pcl::Registration< PointSource, PointTarget, Scalar >::computeTransformation ( PointCloudSource output,
const Matrix4 guess 
)
protectedpure virtual

◆ getClassName()

template<typename PointSource , typename PointTarget , typename Scalar = float>
const std::string& pcl::Registration< PointSource, PointTarget, Scalar >::getClassName ( ) const
inline

◆ getCorrespondenceRejectors()

template<typename PointSource , typename PointTarget , typename Scalar = float>
std::vector<CorrespondenceRejectorPtr> pcl::Registration< PointSource, PointTarget, Scalar >::getCorrespondenceRejectors ( )
inline

Get the list of correspondence rejectors.

Definition at line 522 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_rejectors_.

◆ getEuclideanFitnessEpsilon()

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getEuclideanFitnessEpsilon ( )
inline

Get the maximum allowed distance error before the algorithm will be considered to have converged, as set by the user.

See setEuclideanFitnessEpsilon

Definition at line 412 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::euclidean_fitness_epsilon_.

◆ getFinalTransformation()

template<typename PointSource , typename PointTarget , typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::getFinalTransformation ( )
inline

Get the final transformation matrix estimated by the registration method.

Definition at line 259 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::final_transformation_.

◆ getFitnessScore() [1/2]

template<typename PointSource , typename PointTarget , typename Scalar >
double pcl::Registration< PointSource, PointTarget, Scalar >::getFitnessScore ( const std::vector< float > &  distances_a,
const std::vector< float > &  distances_b 
)
inline

Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target) from two sets of correspondence distances (distances between source and target points)

Parameters
[in]distances_athe first set of distances between correspondences
[in]distances_bthe second set of distances between correspondences

Definition at line 122 of file registration.hpp.

◆ getFitnessScore() [2/2]

template<typename PointSource , typename PointTarget , typename Scalar >
double pcl::Registration< PointSource, PointTarget, Scalar >::getFitnessScore ( double  max_range = std::numeric_limits<double>::max())
inline

Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target)

Parameters
[in]max_rangemaximum allowable distance between a point and its correspondence in the target (default: double::max)

Definition at line 134 of file registration.hpp.

References pcl::transformPointCloud().

◆ getInputSource()

template<typename PointSource , typename PointTarget , typename Scalar = float>
PointCloudSourceConstPtr const pcl::Registration< PointSource, PointTarget, Scalar >::getInputSource ( )
inline

Get a pointer to the input point cloud dataset target.

Definition at line 189 of file registration.h.

References pcl::PCLBase< PointSource >::input_.

◆ getInputTarget()

template<typename PointSource , typename PointTarget , typename Scalar = float>
PointCloudTargetConstPtr const pcl::Registration< PointSource, PointTarget, Scalar >::getInputTarget ( )
inline

Get a pointer to the input point cloud dataset target.

Definition at line 202 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::target_.

◆ getLastIncrementalTransformation()

template<typename PointSource , typename PointTarget , typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::getLastIncrementalTransformation ( )
inline

Get the last incremental transformation matrix estimated by the registration method.

Definition at line 267 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::transformation_.

◆ getMaxCorrespondenceDistance()

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getMaxCorrespondenceDistance ( )
inline

Get the maximum distance threshold between two correspondent points in source <-> target.

If the distance is larger than this threshold, the points will be ignored in the alignment process.

Definition at line 346 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::corr_dist_threshold_.

◆ getMaximumIterations()

template<typename PointSource , typename PointTarget , typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::getMaximumIterations ( )
inline

Get the maximum number of iterations the internal optimization should run for, as set by the user.

Definition at line 285 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::max_iterations_.

◆ getRANSACIterations()

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getRANSACIterations ( )
inline

Get the number of iterations RANSAC should run for, as set by the user.

Definition at line 301 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::ransac_iterations_.

◆ getRANSACOutlierRejectionThreshold()

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getRANSACOutlierRejectionThreshold ( )
inline

Get the inlier distance threshold for the internal outlier rejection loop as set by the user.

Definition at line 324 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::inlier_threshold_.

◆ getSearchMethodSource()

template<typename PointSource , typename PointTarget , typename Scalar = float>
KdTreeReciprocalPtr pcl::Registration< PointSource, PointTarget, Scalar >::getSearchMethodSource ( ) const
inline

Get a pointer to the search method used to find correspondences in the source cloud.

Definition at line 251 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::tree_reciprocal_.

◆ getSearchMethodTarget()

template<typename PointSource , typename PointTarget , typename Scalar = float>
KdTreePtr pcl::Registration< PointSource, PointTarget, Scalar >::getSearchMethodTarget ( ) const
inline

Get a pointer to the search method used to find correspondences in the target cloud.

Definition at line 226 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::tree_.

◆ getTransformationEpsilon()

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getTransformationEpsilon ( )
inline

Get the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) as set by the user.

Definition at line 367 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::transformation_epsilon_.

◆ getTransformationRotationEpsilon()

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getTransformationRotationEpsilon ( )
inline

Get the transformation rotation epsilon (maximum allowable difference between two consecutive transformations) as set by the user (epsilon is the cos(angle) in a axis-angle representation).

Definition at line 390 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::transformation_rotation_epsilon_.

◆ hasConverged()

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::hasConverged ( ) const
inline

Return the state of convergence after the last align run.

Definition at line 463 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::converged_.

◆ initCompute()

template<typename PointSource , typename PointTarget , typename Scalar >
bool pcl::Registration< PointSource, PointTarget, Scalar >::initCompute

Internal computation initialization.

Definition at line 75 of file registration.hpp.

◆ initComputeReciprocal()

template<typename PointSource , typename PointTarget , typename Scalar >
bool pcl::Registration< PointSource, PointTarget, Scalar >::initComputeReciprocal

Internal computation when reciprocal lookup is needed.

Definition at line 105 of file registration.hpp.

◆ registerVisualizationCallback()

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::registerVisualizationCallback ( std::function< UpdateVisualizerCallbackSignature > &  visualizerCallback)
inline

Register the user callback function which will be called from registration thread in order to update point cloud obtained after each iteration.

Parameters
[in]visualizerCallbackreference of the user callback function

Definition at line 432 of file registration.h.

References pcl::PCLBase< PointSource >::input_, pcl::Registration< PointSource, PointTarget, Scalar >::target_, and pcl::Registration< PointSource, PointTarget, Scalar >::update_visualizer_.

Referenced by pcl::RegistrationVisualizer< PointSource, PointTarget, Scalar >::setRegistration().

◆ removeCorrespondenceRejector()

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::removeCorrespondenceRejector ( unsigned int  i)
inline

Remove the i-th correspondence rejector in the list.

Parameters
[in]ithe position of the correspondence rejector in the list to remove

Definition at line 531 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_rejectors_.

◆ searchForNeighbors()

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::searchForNeighbors ( const PointCloudSource cloud,
int  index,
pcl::Indices indices,
std::vector< float > &  distances 
)
inlineprotected

Search for the closest nearest neighbor of a given point.

Parameters
cloudthe point cloud dataset to use for nearest neighbor search
indexthe index of the query point
indicesthe resultant vector of indices representing the k-nearest neighbors
distancesthe resultant distances from the query point to the k-nearest neighbors

Definition at line 663 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::tree_.

◆ setCorrespondenceEstimation()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setCorrespondenceEstimation ( const CorrespondenceEstimationPtr ce)
inline

Provide a pointer to the correspondence estimation object.

(e.g., regular, reciprocal, normal shooting etc.)

Parameters
[in]ceis the pointer to the corresponding correspondence estimation object

Code example:

ce (new CorrespondenceEstimation<PointXYZ, PointXYZ>);
ce->setInputSource (source);
ce->setInputTarget (target);
icp.setCorrespondenceEstimation (ce);
// or...
CorrespondenceEstimationNormalShooting<PointNormal, PointNormal, PointNormal>::Ptr
cens (new CorrespondenceEstimationNormalShooting<PointNormal, PointNormal>);
ce->setInputSource (source);
ce->setInputTarget (target);
ce->setSourceNormals (source);
ce->setTargetNormals (target);
icp.setCorrespondenceEstimation (cens);
shared_ptr< CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > Ptr

Definition at line 174 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_estimation_.

◆ setEuclideanFitnessEpsilon()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setEuclideanFitnessEpsilon ( double  epsilon)
inline

Set the maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged.

The error is estimated as the sum of the differences between correspondences in an Euclidean sense, divided by the number of correspondences.

Parameters
[in]epsilonthe maximum allowed distance error before the algorithm will be considered to have converged

Definition at line 402 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::euclidean_fitness_epsilon_.

◆ setInputSource()

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::Registration< PointSource, PointTarget, Scalar >::setInputSource ( const PointCloudSourceConstPtr cloud)
inlinevirtual

◆ setInputTarget()

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::Registration< PointSource, PointTarget, Scalar >::setInputTarget ( const PointCloudTargetConstPtr cloud)
inlinevirtual

◆ setMaxCorrespondenceDistance()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setMaxCorrespondenceDistance ( double  distance_threshold)
inline

Set the maximum distance threshold between two correspondent points in source <-> target.

If the distance is larger than this threshold, the points will be ignored in the alignment process.

Parameters
[in]distance_thresholdthe maximum distance threshold between a point and its nearest neighbor correspondent in order to be considered in the alignment process

Definition at line 336 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::corr_dist_threshold_.

◆ setMaximumIterations()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setMaximumIterations ( int  nr_iterations)
inline

Set the maximum number of iterations the internal optimization should run for.

Parameters
[in]nr_iterationsthe maximum number of iterations the internal optimization should run for

Definition at line 277 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::max_iterations_.

◆ setPointRepresentation()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setPointRepresentation ( const PointRepresentationConstPtr point_representation)
inline

Provide a boost shared pointer to the PointRepresentation to be used when comparing points.

Parameters
[in]point_representationthe PointRepresentation to be used by the k-D tree

Definition at line 422 of file registration.h.

◆ setRANSACIterations()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setRANSACIterations ( int  ransac_iterations)
inline

Set the number of iterations RANSAC should run for.

Parameters
[in]ransac_iterationsis the number of iterations RANSAC should run for

Definition at line 294 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::ransac_iterations_.

◆ setRANSACOutlierRejectionThreshold()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setRANSACOutlierRejectionThreshold ( double  inlier_threshold)
inline

Set the inlier distance threshold for the internal RANSAC outlier rejection loop.

The method considers a point to be an inlier, if the distance between the target data index and the transformed source index is smaller than the given inlier distance threshold. The value is set by default to 0.05m.

Parameters
[in]inlier_thresholdthe inlier distance threshold for the internal RANSAC outlier rejection loop

Definition at line 316 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::inlier_threshold_.

◆ setSearchMethodSource()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setSearchMethodSource ( const KdTreeReciprocalPtr tree,
bool  force_no_recompute = false 
)
inline

Provide a pointer to the search object used to find correspondences in the source cloud (usually used by reciprocal correspondence finding).

Parameters
[in]treea pointer to the spatial search object.
[in]force_no_recomputeIf set to true, this tree will NEVER be recomputed, regardless of calls to setInputSource. Only use if you are extremely confident that the tree will be set correctly.

Definition at line 239 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::force_no_recompute_reciprocal_, pcl::Registration< PointSource, PointTarget, Scalar >::source_cloud_updated_, and pcl::Registration< PointSource, PointTarget, Scalar >::tree_reciprocal_.

◆ setSearchMethodTarget()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setSearchMethodTarget ( const KdTreePtr tree,
bool  force_no_recompute = false 
)
inline

Provide a pointer to the search object used to find correspondences in the target cloud.

Parameters
[in]treea pointer to the spatial search object.
[in]force_no_recomputeIf set to true, this tree will NEVER be recomputed, regardless of calls to setInputTarget. Only use if you are confident that the tree will be set correctly.

Definition at line 215 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::force_no_recompute_, pcl::Registration< PointSource, PointTarget, Scalar >::target_cloud_updated_, and pcl::Registration< PointSource, PointTarget, Scalar >::tree_.

◆ setTransformationEpsilon()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setTransformationEpsilon ( double  epsilon)
inline

Set the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.

Parameters
[in]epsilonthe transformation epsilon in order for an optimization to be considered as having converged to the final solution.

Definition at line 358 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::transformation_epsilon_.

◆ setTransformationEstimation()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setTransformationEstimation ( const TransformationEstimationPtr te)
inline

Provide a pointer to the transformation estimation object.

(e.g., SVD, point to plane etc.)

Parameters
[in]teis the pointer to the corresponding transformation estimation object

Code example:

TransformationEstimationPointToPlaneLLS<PointXYZ, PointXYZ>::Ptr trans_lls
(new TransformationEstimationPointToPlaneLLS<PointXYZ, PointXYZ>);
icp.setTransformationEstimation (trans_lls);
// or...
TransformationEstimationSVD<PointXYZ, PointXYZ>::Ptr trans_svd
(new TransformationEstimationSVD<PointXYZ, PointXYZ>);
icp.setTransformationEstimation (trans_svd);

Definition at line 145 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::transformation_estimation_.

◆ setTransformationRotationEpsilon()

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setTransformationRotationEpsilon ( double  epsilon)
inline

Set the transformation rotation epsilon (maximum allowable rotation difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.

Parameters
[in]epsilonthe transformation rotation epsilon in order for an optimization to be considered as having converged to the final solution (epsilon is the cos(angle) in a axis-angle representation).

Definition at line 380 of file registration.h.

References pcl::Registration< PointSource, PointTarget, Scalar >::transformation_rotation_epsilon_.

Member Data Documentation

◆ converged_

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::converged_ {false}
protected

Holds internal convergence state, given user parameters.

Definition at line 613 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::hasConverged().

◆ corr_dist_threshold_

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::corr_dist_threshold_
protected

The maximum distance threshold between two correspondent points in source <-> target.

If the distance is larger than this threshold, the points will be ignored in the alignment process.

Definition at line 603 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::getMaxCorrespondenceDistance(), pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::SampleConsensusInitialAlignment(), and pcl::Registration< PointSource, PointTarget, Scalar >::setMaxCorrespondenceDistance().

◆ correspondence_estimation_

template<typename PointSource , typename PointTarget , typename Scalar = float>
CorrespondenceEstimationPtr pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_estimation_
protected

A CorrespondenceEstimation object, used to estimate correspondences between the source and the target cloud.

Definition at line 629 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::setCorrespondenceEstimation().

◆ correspondence_rejectors_

template<typename PointSource , typename PointTarget , typename Scalar = float>
std::vector<CorrespondenceRejectorPtr> pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_rejectors_
protected

◆ correspondences_

template<typename PointSource , typename PointTarget , typename Scalar = float>
CorrespondencesPtr pcl::Registration< PointSource, PointTarget, Scalar >::correspondences_
protected

The set of correspondences determined at this ICP step.

Definition at line 621 of file registration.h.

◆ euclidean_fitness_epsilon_

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::euclidean_fitness_epsilon_
protected

The maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged.

The error is estimated as the sum of the differences between correspondences in an Euclidean sense, divided by the number of correspondences.

Definition at line 597 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::getEuclideanFitnessEpsilon(), and pcl::Registration< PointSource, PointTarget, Scalar >::setEuclideanFitnessEpsilon().

◆ final_transformation_

template<typename PointSource , typename PointTarget , typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::final_transformation_
protected

The final transformation matrix estimated by the registration method after N iterations.

Definition at line 573 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::getFinalTransformation().

◆ force_no_recompute_

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::force_no_recompute_ {false}
protected

A flag which, if set, means the tree operating on the target cloud will never be recomputed.

Definition at line 644 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::setSearchMethodTarget().

◆ force_no_recompute_reciprocal_

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::force_no_recompute_reciprocal_ {false}
protected

A flag which, if set, means the tree operating on the source cloud will never be recomputed.

Definition at line 648 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::setSearchMethodSource().

◆ inlier_threshold_

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::inlier_threshold_ {0.05}
protected

The inlier distance threshold for the internal RANSAC outlier rejection loop.

The method considers a point to be an inlier, if the distance between the target data index and the transformed source index is smaller than the given inlier distance threshold. The default value is 0.05.

Definition at line 610 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::getRANSACOutlierRejectionThreshold(), and pcl::Registration< PointSource, PointTarget, Scalar >::setRANSACOutlierRejectionThreshold().

◆ max_iterations_

template<typename PointSource , typename PointTarget , typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::max_iterations_ {10}
protected

◆ min_number_correspondences_

template<typename PointSource , typename PointTarget , typename Scalar = float>
unsigned int pcl::Registration< PointSource, PointTarget, Scalar >::min_number_correspondences_ {3}
protected

The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation.

The default value is 3.

Definition at line 618 of file registration.h.

◆ nr_iterations_

template<typename PointSource , typename PointTarget , typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::nr_iterations_ {0}
protected

The number of iterations the internal optimization ran for (used internally).

Definition at line 558 of file registration.h.

◆ previous_transformation_

template<typename PointSource , typename PointTarget , typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::previous_transformation_
protected

The previous transformation matrix estimated by the registration method (used internally).

Definition at line 580 of file registration.h.

◆ ransac_iterations_

template<typename PointSource , typename PointTarget , typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::ransac_iterations_ {0}
protected

◆ reg_name_

template<typename PointSource , typename PointTarget , typename Scalar = float>
std::string pcl::Registration< PointSource, PointTarget, Scalar >::reg_name_
protected

◆ source_cloud_updated_

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::source_cloud_updated_ {true}
protected

Variable that stores whether we have a new source cloud, meaning we need to pre-process it again.

This way, we avoid rebuilding the reciprocal kd-tree for the source cloud every time the determineCorrespondences () method is called.

Definition at line 641 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::setSearchMethodSource().

◆ target_

template<typename PointSource , typename PointTarget , typename Scalar = float>
PointCloudTargetConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::target_
protected

◆ target_cloud_updated_

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::target_cloud_updated_ {true}
protected

Variable that stores whether we have a new target cloud, meaning we need to pre-process it again.

This way, we avoid rebuilding the kd-tree for the target cloud every time the determineCorrespondences () method is called.

Definition at line 637 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::setSearchMethodTarget().

◆ transformation_

template<typename PointSource , typename PointTarget , typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::transformation_
protected

The transformation matrix estimated by the registration method.

Definition at line 576 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::getLastIncrementalTransformation().

◆ transformation_epsilon_

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::transformation_epsilon_ {0.0}
protected

The maximum difference between two consecutive transformations in order to consider convergence (user defined).

Definition at line 585 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::getTransformationEpsilon(), and pcl::Registration< PointSource, PointTarget, Scalar >::setTransformationEpsilon().

◆ transformation_estimation_

template<typename PointSource , typename PointTarget , typename Scalar = float>
TransformationEstimationPtr pcl::Registration< PointSource, PointTarget, Scalar >::transformation_estimation_
protected

◆ transformation_rotation_epsilon_

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::transformation_rotation_epsilon_ {0.0}
protected

The maximum rotation difference between two consecutive transformations in order to consider convergence (user defined).

Definition at line 590 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::getTransformationRotationEpsilon(), and pcl::Registration< PointSource, PointTarget, Scalar >::setTransformationRotationEpsilon().

◆ tree_

template<typename PointSource , typename PointTarget , typename Scalar = float>
KdTreePtr pcl::Registration< PointSource, PointTarget, Scalar >::tree_
protected

◆ tree_reciprocal_

template<typename PointSource , typename PointTarget , typename Scalar = float>
KdTreeReciprocalPtr pcl::Registration< PointSource, PointTarget, Scalar >::tree_reciprocal_
protected

◆ update_visualizer_

template<typename PointSource , typename PointTarget , typename Scalar = float>
std::function<UpdateVisualizerCallbackSignature> pcl::Registration< PointSource, PointTarget, Scalar >::update_visualizer_
protected

Callback function to update intermediate source point cloud position during it's registration to the target point cloud.

Definition at line 653 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::registerVisualizationCallback().


The documentation for this class was generated from the following files: