point_cloud_library / 1.12.1 / classpcl_1_1_generalized_iterative_closest_point.html /

GeneralizedIterativeClosestPoint is an ICP variant that implements the generalized iterative closest point algorithm as described by Alex Segal et al. More...

#include <pcl/registration/gicp.h>

Classes

struct OptimizationFunctorWithIndices
optimization functor structure More...

Public Types

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 PointIndicesPtr = PointIndices::Ptr
using PointIndicesConstPtr = PointIndices::ConstPtr
using MatricesVector = std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > >
using MatricesVectorPtr = shared_ptr< MatricesVector >
using MatricesVectorConstPtr = shared_ptr< const MatricesVector >
using InputKdTree = typename Registration< PointSource, PointTarget >::KdTree
using InputKdTreePtr = typename Registration< PointSource, PointTarget >::KdTreePtr
using Ptr = shared_ptr< GeneralizedIterativeClosestPoint< PointSource, PointTarget > >
using ConstPtr = shared_ptr< const GeneralizedIterativeClosestPoint< PointSource, PointTarget > >
using Vector6d = Eigen::Matrix< double, 6, 1 >
- Public Types inherited from pcl::IterativeClosestPoint< PointSource, PointTarget >
using PointCloudSource = typename Registration< PointSource, PointTarget, float >::PointCloudSource
using PointCloudSourcePtr = typename PointCloudSource::Ptr
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr
using PointCloudTarget = typename Registration< PointSource, PointTarget, float >::PointCloudTarget
using PointCloudTargetPtr = typename PointCloudTarget::Ptr
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr
using PointIndicesPtr = PointIndices::Ptr
using PointIndicesConstPtr = PointIndices::ConstPtr
using Ptr = shared_ptr< IterativeClosestPoint< PointSource, PointTarget, float > >
using ConstPtr = shared_ptr< const IterativeClosestPoint< PointSource, PointTarget, float > >
using Matrix4 = typename Registration< PointSource, PointTarget, float >::Matrix4
- Public Types inherited from pcl::Registration< PointSource, PointTarget, float >
using Matrix4 = Eigen::Matrix< float, 4, 4 >
using Ptr = shared_ptr< Registration< PointSource, PointTarget, float > >
using ConstPtr = shared_ptr< const Registration< PointSource, PointTarget, float > >
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, float >
using TransformationEstimationPtr = typename TransformationEstimation::Ptr
using TransformationEstimationConstPtr = typename TransformationEstimation::ConstPtr
using CorrespondenceEstimation = pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, float >
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

GeneralizedIterativeClosestPoint ()
Empty constructor. More...
void setInputSource (const PointCloudSourceConstPtr &cloud) override
Provide a pointer to the input dataset. More...
void setSourceCovariances (const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input source (if computed externally!). More...
void setInputTarget (const PointCloudTargetConstPtr &target) override
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to) More...
void setTargetCovariances (const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input target (if computed externally!). More...
void estimateRigidTransformationBFGS (const PointCloudSource &cloud_src, const pcl::Indices &indices_src, const PointCloudTarget &cloud_tgt, const pcl::Indices &indices_tgt, Eigen::Matrix4f &transformation_matrix)
Estimate a rigid rotation transformation between a source and a target point cloud using an iterative non-linear Levenberg-Marquardt approach. More...
const Eigen::Matrix3d & mahalanobis (std::size_t index) const
void computeRDerivative (const Vector6d &x, const Eigen::Matrix3d &R, Vector6d &g) const
Computes rotation matrix derivative. More...
void setRotationEpsilon (double epsilon)
Set the rotation epsilon (maximum allowable difference between two consecutive rotations) in order for an optimization to be considered as having converged to the final solution. More...
double getRotationEpsilon () const
Get the rotation epsilon (maximum allowable difference between two consecutive rotations) as set by the user. More...
void setCorrespondenceRandomness (int k)
Set the number of neighbors used when selecting a point neighbourhood to compute covariances. More...
int getCorrespondenceRandomness () const
Get the number of neighbors used when computing covariances as set by the user. More...
void setMaximumOptimizerIterations (int max)
Set maximum number of iterations at the optimization step. More...
int getMaximumOptimizerIterations () const
Return maximum number of iterations at the optimization step. More...
void setTranslationGradientTolerance (double tolerance)
Set the minimal translation gradient threshold for early optimization stop. More...
double getTranslationGradientTolerance () const
Return the minimal translation gradient threshold for early optimization stop. More...
void setRotationGradientTolerance (double tolerance)
Set the minimal rotation gradient threshold for early optimization stop. More...
double getRotationGradientTolerance () const
Return the minimal rotation gradient threshold for early optimization stop. More...
- Public Member Functions inherited from pcl::IterativeClosestPoint< PointSource, PointTarget >
IterativeClosestPoint ()
Empty constructor. More...
IterativeClosestPoint (const IterativeClosestPoint &)=delete
Due to convergence_criteria_ holding references to the class members, it is tricky to correctly implement its copy and move operations correctly. More...
IterativeClosestPoint (IterativeClosestPoint &&)=delete
IterativeClosestPoint & operator= (const IterativeClosestPoint &)=delete
IterativeClosestPoint & operator= (IterativeClosestPoint &&)=delete
~IterativeClosestPoint ()
Empty destructor. More...
pcl::registration::DefaultConvergenceCriteria< float >::Ptr getConvergeCriteria ()
Returns a pointer to the DefaultConvergenceCriteria used by the IterativeClosestPoint class. More...
void setInputSource (const PointCloudSourceConstPtr &cloud) override
Provide a pointer to the input source (e.g., the point cloud that we want to align to the target) More...
void setInputTarget (const PointCloudTargetConstPtr &cloud) override
Provide a pointer to the input target (e.g., the point cloud that we want to align to the target) More...
void setUseReciprocalCorrespondences (bool use_reciprocal_correspondence)
Set whether to use reciprocal correspondence or not. More...
bool getUseReciprocalCorrespondences () const
Obtain whether reciprocal correspondence are used or not. More...
- Public Member Functions inherited from pcl::Registration< PointSource, PointTarget, float >
Registration ()
Empty constructor. More...
~Registration ()
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...
const PointCloudSourceConstPtr getInputSource ()
Get a pointer to the input point cloud dataset target. More...
const PointCloudTargetConstPtr 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< CorrespondenceRejectorPtr > getCorrespondenceRejectors ()
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...
const PointCloudConstPtr 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...
const IndicesConstPtr 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

template<typename PointT >
void computeCovariances (typename pcl::PointCloud< PointT >::ConstPtr cloud, const typename pcl::search::KdTree< PointT >::Ptr tree, MatricesVector &cloud_covariances)
compute points covariances matrices according to the K nearest neighbors. More...
double matricesInnerProd (const Eigen::MatrixXd &mat1, const Eigen::MatrixXd &mat2) const
void computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess) override
Rigid transformation computation method with initial guess. More...
bool searchForNeighbors (const PointSource &query, pcl::Indices &index, std::vector< float > &distance)
Search for the closest nearest neighbor of a given point. More...
void applyState (Eigen::Matrix4f &t, const Vector6d &x) const
compute transformation matrix from transformation matrix More...
- Protected Member Functions inherited from pcl::IterativeClosestPoint< PointSource, PointTarget >
virtual void transformCloud (const PointCloudSource &input, PointCloudSource &output, const Matrix4 &transform)
Apply a rigid transform to a given dataset. More...
void computeTransformation (PointCloudSource &output, const Matrix4 &guess) override
Rigid transformation computation method with initial guess. More...
virtual void determineRequiredBlobData ()
Looks at the Estimators and Rejectors and determines whether their blob-setter methods need to be called. More...
- Protected Member Functions inherited from pcl::Registration< PointSource, PointTarget, float >
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

int k_correspondences_
The number of neighbors used for covariances computation. More...
double gicp_epsilon_
The epsilon constant for gicp paper; this is NOT the convergence tolerance default: 0.001. More...
double rotation_epsilon_
The epsilon constant for rotation error. More...
Eigen::Matrix4f base_transformation_
base transformation More...
const PointCloudSource * tmp_src_
Temporary pointer to the source dataset. More...
const PointCloudTarget * tmp_tgt_
Temporary pointer to the target dataset. More...
const pcl::Indices * tmp_idx_src_
Temporary pointer to the source dataset indices. More...
const pcl::Indices * tmp_idx_tgt_
Temporary pointer to the target dataset indices. More...
MatricesVectorPtr input_covariances_
Input cloud points covariances. More...
MatricesVectorPtr target_covariances_
Target cloud points covariances. More...
std::vector< Eigen::Matrix3d > mahalanobis_
Mahalanobis matrices holder. More...
int max_inner_iterations_
maximum number of optimizations More...
double translation_gradient_tolerance_
minimal translation gradient for early optimization stop More...
double rotation_gradient_tolerance_
minimal rotation gradient for early optimization stop More...
std::function< void(const pcl::PointCloud< PointSource > &cloud_src, const pcl::Indices &src_indices, const pcl::PointCloud< PointTarget > &cloud_tgt, const pcl::Indices &tgt_indices, Eigen::Matrix4f &transformation_matrix)> rigid_transformation_estimation_
- Protected Attributes inherited from pcl::IterativeClosestPoint< PointSource, PointTarget >
std::size_t x_idx_offset_
XYZ fields offset. More...
std::size_t y_idx_offset_
std::size_t z_idx_offset_
std::size_t nx_idx_offset_
Normal fields offset. More...
std::size_t ny_idx_offset_
std::size_t nz_idx_offset_
bool use_reciprocal_correspondence_
The correspondence type used for correspondence estimation. More...
bool source_has_normals_
Internal check whether source dataset has normals or not. More...
bool target_has_normals_
Internal check whether target dataset has normals or not. More...
bool need_source_blob_
Checks for whether estimators and rejectors need various data. More...
bool need_target_blob_
- Protected Attributes inherited from pcl::Registration< PointSource, PointTarget, float >
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_
The number of iterations the internal optimization ran for (used internally). More...
int max_iterations_
The maximum number of iterations the internal optimization should run for. More...
int ransac_iterations_
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_
The maximum difference between two consecutive transformations in order to consider convergence (user defined). More...
double transformation_rotation_epsilon_
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_
The inlier distance threshold for the internal RANSAC outlier rejection loop. More...
bool converged_
Holds internal convergence state, given user parameters. More...
int min_number_correspondences_
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< CorrespondenceRejectorPtr > correspondence_rejectors_
The list of correspondence rejectors to use. More...
bool target_cloud_updated_
Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. More...
bool source_cloud_updated_
Variable that stores whether we have a new source cloud, meaning we need to pre-process it again. More...
bool force_no_recompute_
A flag which, if set, means the tree operating on the target cloud will never be recomputed. More...
bool force_no_recompute_reciprocal_
A flag which, if set, means the tree operating on the source cloud will never be recomputed. More...
std::function< UpdateVisualizerCallbackSignature > update_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...

Additional Inherited Members

- Public Attributes inherited from pcl::IterativeClosestPoint< PointSource, PointTarget >
pcl::registration::DefaultConvergenceCriteria< float >::Ptr convergence_criteria_

Detailed Description

template<typename PointSource, typename PointTarget>
class pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >

GeneralizedIterativeClosestPoint is an ICP variant that implements the generalized iterative closest point algorithm as described by Alex Segal et al.

in http://www.robots.ox.ac.uk/~avsegal/resources/papers/Generalized_ICP.pdf The approach is based on using anistropic cost functions to optimize the alignment after closest point assignments have been made. The original code uses GSL and ANN while in ours we use an eigen mapped BFGS and FLANN.

Author
Nizar Sallem

Definition at line 58 of file gicp.h.

Member Typedef Documentation

ConstPtr

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::ConstPtr = shared_ptr<const GeneralizedIterativeClosestPoint<PointSource, PointTarget> >

Definition at line 101 of file gicp.h.

InputKdTree

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::InputKdTree = typename Registration<PointSource, PointTarget>::KdTree

Definition at line 96 of file gicp.h.

InputKdTreePtr

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::InputKdTreePtr = typename Registration<PointSource, PointTarget>::KdTreePtr

Definition at line 97 of file gicp.h.

MatricesVector

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::MatricesVector = std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d> >

Definition at line 92 of file gicp.h.

MatricesVectorConstPtr

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::MatricesVectorConstPtr = shared_ptr<const MatricesVector>

Definition at line 94 of file gicp.h.

MatricesVectorPtr

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::MatricesVectorPtr = shared_ptr<MatricesVector>

Definition at line 93 of file gicp.h.

PointCloudSource

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

Definition at line 80 of file gicp.h.

PointCloudSourceConstPtr

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

Definition at line 82 of file gicp.h.

PointCloudSourcePtr

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

Definition at line 81 of file gicp.h.

PointCloudTarget

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

Definition at line 84 of file gicp.h.

PointCloudTargetConstPtr

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

Definition at line 86 of file gicp.h.

PointCloudTargetPtr

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

Definition at line 85 of file gicp.h.

PointIndicesConstPtr

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::PointIndicesConstPtr = PointIndices::ConstPtr

Definition at line 89 of file gicp.h.

PointIndicesPtr

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::PointIndicesPtr = PointIndices::Ptr

Definition at line 88 of file gicp.h.

Ptr

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::Ptr = shared_ptr<GeneralizedIterativeClosestPoint<PointSource, PointTarget> >

Definition at line 99 of file gicp.h.

Vector6d

template<typename PointSource , typename PointTarget >
using pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::Vector6d = Eigen::Matrix<double, 6, 1>

Definition at line 103 of file gicp.h.

Constructor & Destructor Documentation

GeneralizedIterativeClosestPoint()

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

Empty constructor.

Definition at line 106 of file gicp.h.

Member Function Documentation

applyState()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::applyState ( Eigen::Matrix4f & t,
const Vector6d & x
) const
protected

compute transformation matrix from transformation matrix

Definition at line 518 of file gicp.hpp.

computeCovariances()

template<typename PointSource , typename PointTarget >
template<typename PointT >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::computeCovariances ( typename pcl::PointCloud< PointT >::ConstPtr cloud,
const typename pcl::search::KdTree< PointT >::Ptr tree,
MatricesVector & cloud_covariances
)
protected

compute points covariances matrices according to the K nearest neighbors.

K is set via setCorrespondenceRandomness() method.

Parameters
cloud pointer to point cloud
tree KD tree performer for nearest neighbors search
[out] cloud_covariances covariances matrices for each point in the cloud

Definition at line 51 of file gicp.hpp.

computeRDerivative()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::computeRDerivative ( const Vector6d & x,
const Eigen::Matrix3d & R,
Vector6d & g
) const

Computes rotation matrix derivative.

rotation matrix is obtainded from rotation angles x[3], x[4] and x[5]

Returns
d/d_rx, d/d_ry and d/d_rz respectively in g[3], g[4] and g[5] param x array representing 3D transformation param R rotation matrix param g gradient vector

Definition at line 131 of file gicp.hpp.

computeTransformation()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::computeTransformation ( PointCloudSource & output,
const Eigen::Matrix4f & guess
)
inlineoverrideprotected

Rigid transformation computation method with initial guess.

Parameters
output the transformed input point cloud dataset using the rigid transformation found
guess the initial guess of the transformation to compute

Definition at line 390 of file gicp.hpp.

estimateRigidTransformationBFGS()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::estimateRigidTransformationBFGS ( const PointCloudSource & cloud_src,
const pcl::Indices & indices_src,
const PointCloudTarget & cloud_tgt,
const pcl::Indices & indices_tgt,
Eigen::Matrix4f & transformation_matrix
)

Estimate a rigid rotation transformation between a source and a target point cloud using an iterative non-linear Levenberg-Marquardt approach.

Parameters
[in] cloud_src the source point cloud dataset
[in] indices_src the vector of indices describing the points of interest in cloud_src
[in] cloud_tgt the target point cloud dataset
[in] indices_tgt the vector of indices describing the correspondences of the interest points from indices_src
[out] transformation_matrix the resultant transformation matrix

Definition at line 188 of file gicp.hpp.

Referenced by pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >::GeneralizedIterativeClosestPoint().

getCorrespondenceRandomness()

template<typename PointSource , typename PointTarget >
int pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::getCorrespondenceRandomness ( ) const
inline

Get the number of neighbors used when computing covariances as set by the user.

Definition at line 256 of file gicp.h.

getMaximumOptimizerIterations()

template<typename PointSource , typename PointTarget >
int pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::getMaximumOptimizerIterations ( ) const
inline

Return maximum number of iterations at the optimization step.

Definition at line 273 of file gicp.h.

getRotationEpsilon()

template<typename PointSource , typename PointTarget >
double pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::getRotationEpsilon ( ) const
inline

Get the rotation epsilon (maximum allowable difference between two consecutive rotations) as set by the user.

Definition at line 235 of file gicp.h.

getRotationGradientTolerance()

template<typename PointSource , typename PointTarget >
double pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::getRotationGradientTolerance ( ) const
inline

Return the minimal rotation gradient threshold for early optimization stop.

Definition at line 308 of file gicp.h.

getTranslationGradientTolerance()

template<typename PointSource , typename PointTarget >
double pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::getTranslationGradientTolerance ( ) const
inline

Return the minimal translation gradient threshold for early optimization stop.

Definition at line 291 of file gicp.h.

mahalanobis()

template<typename PointSource , typename PointTarget >
const Eigen::Matrix3d& pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::mahalanobis ( std::size_t index ) const
inline
Returns
Mahalanobis distance matrix for the given point index

Definition at line 204 of file gicp.h.

matricesInnerProd()

template<typename PointSource , typename PointTarget >
double pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::matricesInnerProd ( const Eigen::MatrixXd & mat1,
const Eigen::MatrixXd & mat2
) const
inlineprotected
Returns
trace of mat1^t . mat2
Parameters
mat1 matrix of dimension nxm
mat2 matrix of dimension nxp

Definition at line 381 of file gicp.h.

searchForNeighbors()

template<typename PointSource , typename PointTarget >
bool pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::searchForNeighbors ( const PointSource & query,
pcl::Indices & index,
std::vector< float > & distance
)
inlineprotected

Search for the closest nearest neighbor of a given point.

Parameters
query the point to search a nearest neighbour for
index vector of size 1 to store the index of the nearest neighbour found
distance vector of size 1 to store the distance to nearest neighbour found

Definition at line 407 of file gicp.h.

setCorrespondenceRandomness()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setCorrespondenceRandomness ( int k )
inline

Set the number of neighbors used when selecting a point neighbourhood to compute covariances.

A higher value will bring more accurate covariance matrix but will make covariances computation slower.

Parameters
k the number of neighbors to use when computing covariances

Definition at line 247 of file gicp.h.

setInputSource()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setInputSource ( const PointCloudSourceConstPtr & cloud )
inlineoverridevirtual

Provide a pointer to the input dataset.

Parameters
cloud the const boost shared pointer to a PointCloud message

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

Definition at line 134 of file gicp.h.

setInputTarget()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setInputTarget ( const PointCloudTargetConstPtr & target )
inlineoverridevirtual

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

Parameters
[in] target the input point cloud target

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

Definition at line 168 of file gicp.h.

setMaximumOptimizerIterations()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setMaximumOptimizerIterations ( int max )
inline

Set maximum number of iterations at the optimization step.

Parameters
[in] max maximum number of iterations for the optimizer

Definition at line 265 of file gicp.h.

setRotationEpsilon()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setRotationEpsilon ( double epsilon )
inline

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

Parameters
epsilon the rotation epsilon

Definition at line 226 of file gicp.h.

setRotationGradientTolerance()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setRotationGradientTolerance ( double tolerance )
inline

Set the minimal rotation gradient threshold for early optimization stop.

Parameters
[in] tolerance rotation gradient threshold in radians

Definition at line 300 of file gicp.h.

setSourceCovariances()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setSourceCovariances ( const MatricesVectorPtr & covariances )
inline

Provide a pointer to the covariances of the input source (if computed externally!).

If not set, GeneralizedIterativeClosestPoint will compute the covariances itself. Make sure to set the covariances AFTER setting the input source point cloud (setting the input source point cloud will reset the covariances).

Parameters
[in] covariances the input source covariances

Definition at line 159 of file gicp.h.

setTargetCovariances()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setTargetCovariances ( const MatricesVectorPtr & covariances )
inline

Provide a pointer to the covariances of the input target (if computed externally!).

If not set, GeneralizedIterativeClosestPoint will compute the covariances itself. Make sure to set the covariances AFTER setting the input source point cloud (setting the input source point cloud will reset the covariances).

Parameters
[in] covariances the input target covariances

Definition at line 181 of file gicp.h.

setTranslationGradientTolerance()

template<typename PointSource , typename PointTarget >
void pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setTranslationGradientTolerance ( double tolerance )
inline

Set the minimal translation gradient threshold for early optimization stop.

Parameters
[in] tolerance translation gradient threshold in meters

Definition at line 282 of file gicp.h.

Member Data Documentation

base_transformation_

template<typename PointSource , typename PointTarget >
Eigen::Matrix4f pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::base_transformation_
protected

base transformation

Definition at line 332 of file gicp.h.

gicp_epsilon_

template<typename PointSource , typename PointTarget >
double pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::gicp_epsilon_
protected

The epsilon constant for gicp paper; this is NOT the convergence tolerance default: 0.001.

Definition at line 323 of file gicp.h.

input_covariances_

template<typename PointSource , typename PointTarget >
MatricesVectorPtr pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::input_covariances_
protected

k_correspondences_

template<typename PointSource , typename PointTarget >
int pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::k_correspondences_
protected

mahalanobis_

template<typename PointSource , typename PointTarget >
std::vector<Eigen::Matrix3d> pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::mahalanobis_
protected

Mahalanobis matrices holder.

Definition at line 353 of file gicp.h.

Referenced by pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >::mahalanobis().

max_inner_iterations_

template<typename PointSource , typename PointTarget >
int pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::max_inner_iterations_
protected

rigid_transformation_estimation_

template<typename PointSource , typename PointTarget >
std::function<void(const pcl::PointCloud<PointSource>& cloud_src, const pcl::Indices& src_indices, const pcl::PointCloud<PointTarget>& cloud_tgt, const pcl::Indices& tgt_indices, Eigen::Matrix4f& transformation_matrix)> pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::rigid_transformation_estimation_
protected

rotation_epsilon_

template<typename PointSource , typename PointTarget >
double pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::rotation_epsilon_
protected

The epsilon constant for rotation error.

(In GICP the transformation epsilon is split in rotation part and translation part). default: 2e-3

Definition at line 329 of file gicp.h.

Referenced by pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >::getRotationEpsilon(), and pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >::setRotationEpsilon().

rotation_gradient_tolerance_

template<typename PointSource , typename PointTarget >
double pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::rotation_gradient_tolerance_
protected

target_covariances_

template<typename PointSource , typename PointTarget >
MatricesVectorPtr pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::target_covariances_
protected

tmp_idx_src_

template<typename PointSource , typename PointTarget >
const pcl::Indices* pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::tmp_idx_src_
protected

Temporary pointer to the source dataset indices.

Definition at line 341 of file gicp.h.

tmp_idx_tgt_

template<typename PointSource , typename PointTarget >
const pcl::Indices* pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::tmp_idx_tgt_
protected

Temporary pointer to the target dataset indices.

Definition at line 344 of file gicp.h.

tmp_src_

template<typename PointSource , typename PointTarget >
const PointCloudSource* pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::tmp_src_
protected

Temporary pointer to the source dataset.

Definition at line 335 of file gicp.h.

tmp_tgt_

template<typename PointSource , typename PointTarget >
const PointCloudTarget* pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::tmp_tgt_
protected

Temporary pointer to the target dataset.

Definition at line 338 of file gicp.h.

translation_gradient_tolerance_

template<typename PointSource , typename PointTarget >
double pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::translation_gradient_tolerance_
protected

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

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_generalized_iterative_closest_point.html