Point Cloud Library (PCL)  1.14.0-dev
List of all members | Classes | Public Types | Public Member Functions
pcl::PPFRegistration< PointSource, PointTarget > Class Template Reference

Class that registers two point clouds based on their sets of PPFSignatures. More...

#include <pcl/registration/ppf_registration.h>

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

Classes

struct  PoseWithVotes
 Structure for storing a pose (represented as an Eigen::Affine3f) and an integer for counting votes. More...
 

Public Types

using PoseWithVotesList = std::vector< PoseWithVotes, Eigen::aligned_allocator< PoseWithVotes > >
 
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
 
- Public Types inherited from pcl::Registration< PointSource, PointTarget, Scalar >
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

 PPFRegistration ()
 Empty constructor that initializes all the parameters of the algorithm with default values. More...
 
void setPositionClusteringThreshold (float clustering_position_diff_threshold)
 Method for setting the position difference clustering parameter. More...
 
float getPositionClusteringThreshold ()
 Returns the parameter defining the position difference clustering parameter. More...
 
void setRotationClusteringThreshold (float clustering_rotation_diff_threshold)
 Method for setting the rotation clustering parameter. More...
 
float getRotationClusteringThreshold ()
 Returns the parameter defining the rotation clustering threshold. More...
 
void setSceneReferencePointSamplingRate (unsigned int scene_reference_point_sampling_rate)
 Method for setting the scene reference point sampling rate. More...
 
unsigned int getSceneReferencePointSamplingRate ()
 Returns the parameter for the scene reference point sampling rate of the algorithm. More...
 
void setSearchMethod (PPFHashMapSearch::Ptr search_method)
 Function that sets the search method for the algorithm. More...
 
PPFHashMapSearch::Ptr getSearchMethod ()
 Getter function for the search method of the class. More...
 
void setInputTarget (const PointCloudTargetConstPtr &cloud) override
 Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to) More...
 
PoseWithVotesList getBestPoseCandidates ()
 Returns the most promising pose candidates, after clustering. More...
 
- Public Member Functions inherited from pcl::Registration< PointSource, PointTarget, Scalar >
 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...
 
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...
 

Additional Inherited Members

- Protected Member Functions inherited from pcl::Registration< PointSource, PointTarget, Scalar >
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 inherited from pcl::Registration< PointSource, PointTarget, Scalar >
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>
class pcl::PPFRegistration< PointSource, PointTarget >

Class that registers two point clouds based on their sets of PPFSignatures.

Please refer to the following publication for more details: B. Drost, M. Ulrich, N. Navab, S. Ilic Model Globally, Match Locally: Efficient and Robust 3D Object Recognition 2010 IEEE Conference on Computer Vision and Pattern Recognition (CVPR) 13-18 June 2010, San Francisco, CA

Note
This class works in tandem with the PPFEstimation class
Author
Alexandru-Eugen Ichim

Definition at line 175 of file ppf_registration.h.

Member Typedef Documentation

◆ PointCloudSource

template<typename PointSource , typename PointTarget >
using pcl::PPFRegistration< PointSource, PointTarget >::PointCloudSource = pcl::PointCloud<PointSource>

Definition at line 201 of file ppf_registration.h.

◆ PointCloudSourceConstPtr

template<typename PointSource , typename PointTarget >
using pcl::PPFRegistration< PointSource, PointTarget >::PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr

Definition at line 203 of file ppf_registration.h.

◆ PointCloudSourcePtr

template<typename PointSource , typename PointTarget >
using pcl::PPFRegistration< PointSource, PointTarget >::PointCloudSourcePtr = typename PointCloudSource::Ptr

Definition at line 202 of file ppf_registration.h.

◆ PointCloudTarget

template<typename PointSource , typename PointTarget >
using pcl::PPFRegistration< PointSource, PointTarget >::PointCloudTarget = pcl::PointCloud<PointTarget>

Definition at line 205 of file ppf_registration.h.

◆ PointCloudTargetConstPtr

template<typename PointSource , typename PointTarget >
using pcl::PPFRegistration< PointSource, PointTarget >::PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr

Definition at line 207 of file ppf_registration.h.

◆ PointCloudTargetPtr

template<typename PointSource , typename PointTarget >
using pcl::PPFRegistration< PointSource, PointTarget >::PointCloudTargetPtr = typename PointCloudTarget::Ptr

Definition at line 206 of file ppf_registration.h.

◆ PoseWithVotesList

template<typename PointSource , typename PointTarget >
using pcl::PPFRegistration< PointSource, PointTarget >::PoseWithVotesList = std::vector<PoseWithVotes, Eigen::aligned_allocator<PoseWithVotes> >

Definition at line 190 of file ppf_registration.h.

Constructor & Destructor Documentation

◆ PPFRegistration()

template<typename PointSource , typename PointTarget >
pcl::PPFRegistration< PointSource, PointTarget >::PPFRegistration ( )
inline

Empty constructor that initializes all the parameters of the algorithm with default values.

Definition at line 211 of file ppf_registration.h.

Member Function Documentation

◆ getBestPoseCandidates()

template<typename PointSource , typename PointTarget >
PoseWithVotesList pcl::PPFRegistration< PointSource, PointTarget >::getBestPoseCandidates ( )
inline

Returns the most promising pose candidates, after clustering.

The pose with the most votes is the result of the registration. It may make sense to check the next best pose candidates if the registration did not give the right result, or if there are more than one correct results. You need to call the align function before this one.

Definition at line 305 of file ppf_registration.h.

◆ getPositionClusteringThreshold()

template<typename PointSource , typename PointTarget >
float pcl::PPFRegistration< PointSource, PointTarget >::getPositionClusteringThreshold ( )
inline

Returns the parameter defining the position difference clustering parameter.

  • distance threshold below which two poses are considered close enough to be in the same cluster (for the clustering phase of the algorithm)

Definition at line 232 of file ppf_registration.h.

◆ getRotationClusteringThreshold()

template<typename PointSource , typename PointTarget >
float pcl::PPFRegistration< PointSource, PointTarget >::getRotationClusteringThreshold ( )
inline

Returns the parameter defining the rotation clustering threshold.

Definition at line 251 of file ppf_registration.h.

◆ getSceneReferencePointSamplingRate()

template<typename PointSource , typename PointTarget >
unsigned int pcl::PPFRegistration< PointSource, PointTarget >::getSceneReferencePointSamplingRate ( )
inline

Returns the parameter for the scene reference point sampling rate of the algorithm.

Definition at line 269 of file ppf_registration.h.

◆ getSearchMethod()

template<typename PointSource , typename PointTarget >
PPFHashMapSearch::Ptr pcl::PPFRegistration< PointSource, PointTarget >::getSearchMethod ( )
inline

Getter function for the search method of the class.

Definition at line 287 of file ppf_registration.h.

◆ setInputTarget()

template<typename PointSource , typename PointTarget >
void pcl::PPFRegistration< PointSource, PointTarget >::setInputTarget ( const PointCloudTargetConstPtr cloud)
overridevirtual

Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to)

Parameters
cloudthe input point cloud target

Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.

Definition at line 53 of file ppf_registration.hpp.

◆ setPositionClusteringThreshold()

template<typename PointSource , typename PointTarget >
void pcl::PPFRegistration< PointSource, PointTarget >::setPositionClusteringThreshold ( float  clustering_position_diff_threshold)
inline

Method for setting the position difference clustering parameter.

Parameters
clustering_position_diff_thresholddistance threshold below which two poses are considered close enough to be in the same cluster (for the clustering phase of the algorithm)

Definition at line 222 of file ppf_registration.h.

◆ setRotationClusteringThreshold()

template<typename PointSource , typename PointTarget >
void pcl::PPFRegistration< PointSource, PointTarget >::setRotationClusteringThreshold ( float  clustering_rotation_diff_threshold)
inline

Method for setting the rotation clustering parameter.

Parameters
clustering_rotation_diff_thresholdrotation difference threshold below which two poses are considered to be in the same cluster (for the clustering phase of the algorithm)

Definition at line 243 of file ppf_registration.h.

◆ setSceneReferencePointSamplingRate()

template<typename PointSource , typename PointTarget >
void pcl::PPFRegistration< PointSource, PointTarget >::setSceneReferencePointSamplingRate ( unsigned int  scene_reference_point_sampling_rate)
inline

Method for setting the scene reference point sampling rate.

Parameters
scene_reference_point_sampling_ratesampling rate for the scene reference point

Definition at line 261 of file ppf_registration.h.

◆ setSearchMethod()

template<typename PointSource , typename PointTarget >
void pcl::PPFRegistration< PointSource, PointTarget >::setSearchMethod ( PPFHashMapSearch::Ptr  search_method)
inline

Function that sets the search method for the algorithm.

Note
Right now, the only available method is the one initially proposed by the authors - by using a hash map with discretized feature vectors
Parameters
search_methodsmart pointer to the search method to be set

Definition at line 280 of file ppf_registration.h.


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