Point Cloud Library (PCL)  1.14.0-dev
List of all members | Classes | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::GeneralizedIterativeClosestPoint6D Class Reference

GeneralizedIterativeClosestPoint6D integrates L*a*b* color space information into the Generalized Iterative Closest Point (GICP) algorithm. More...

#include <pcl/registration/gicp6d.h>

+ Inheritance diagram for pcl::GeneralizedIterativeClosestPoint6D:
+ Collaboration diagram for pcl::GeneralizedIterativeClosestPoint6D:

Classes

class  MyPointRepresentation
 Custom point representation to perform kdtree searches in more than 3 (i.e. More...
 

Public Member Functions

 GeneralizedIterativeClosestPoint6D (float lab_weight=0.032f)
 constructor. 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 &target) override
 Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to) More...
 
- Public Member Functions inherited from pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >
PCL_MAKE_ALIGNED_OPERATOR_NEW 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, Matrix4 &transformation_matrix)
 Estimate a rigid rotation transformation between a source and a target point cloud using an iterative non-linear BFGS approach. More...
 
void estimateRigidTransformationNewton (const PointCloudSource &cloud_src, const pcl::Indices &indices_src, const PointCloudTarget &cloud_tgt, const pcl::Indices &indices_tgt, Matrix4 &transformation_matrix)
 Estimate a rigid rotation transformation between a source and a target point cloud using an iterative non-linear Newton approach. More...
 
const Eigen::Matrix3d & mahalanobis (std::size_t index) const
 
void computeRDerivative (const Vector6d &x, const Eigen::Matrix3d &dCost_dR_T, Vector6d &g) const
 Computes the derivative of the cost function w.r.t rotation angles. 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 useBFGS ()
 Use BFGS optimizer instead of default Newton optimizer. 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< PointXYZRGBA, PointXYZRGBA, float >
 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
 
IterativeClosestPointoperator= (const IterativeClosestPoint &)=delete
 
IterativeClosestPointoperator= (IterativeClosestPoint &&)=delete
 
 ~IterativeClosestPoint () override=default
 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 the input source to) 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, 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...
 
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

void computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess) override
 Rigid transformation computation method with initial guess. More...
 
bool searchForNeighbors (const PointXYZLAB &query, pcl::Indices &index, std::vector< float > &distance)
 Search for the closest nearest neighbor of a given point. More...
 
- Protected Member Functions inherited from pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >
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 Matrix4 &guess) override
 Rigid transformation computation method with initial guess. More...
 
bool searchForNeighbors (const PointXYZRGBA &query, pcl::Indices &index, std::vector< float > &distance)
 Search for the closest nearest neighbor of a given point. More...
 
void applyState (Matrix4 &t, const Vector6d &x) const
 compute transformation matrix from transformation matrix More...
 
- Protected Member Functions inherited from pcl::IterativeClosestPoint< PointXYZRGBA, PointXYZRGBA, float >
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, 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...
 
- 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

pcl::PointCloud< PointXYZLAB >::Ptr cloud_lab_
 Holds the converted (LAB) data cloud. More...
 
pcl::PointCloud< PointXYZLAB >::Ptr target_lab_
 Holds the converted (LAB) model cloud. More...
 
KdTreeFLANN< PointXYZLABtarget_tree_lab_
 6d-tree to search in model cloud. More...
 
float lab_weight_
 The color weight. More...
 
MyPointRepresentation point_rep_
 Enables 6d searches with kd-tree class using the color weight. More...
 
- Protected Attributes inherited from pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >
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...
 
Matrix4 base_transformation_
 base transformation More...
 
const PointCloudSourcetmp_src_
 Temporary pointer to the source dataset. More...
 
const PointCloudTargettmp_tgt_
 Temporary pointer to the target dataset. More...
 
const pcl::Indicestmp_idx_src_
 Temporary pointer to the source dataset indices. More...
 
const pcl::Indicestmp_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< PointXYZRGBA > &cloud_src, const pcl::Indices &src_indices, const pcl::PointCloud< PointXYZRGBA > &cloud_tgt, const pcl::Indices &tgt_indices, Matrix4 &transformation_matrix)> rigid_transformation_estimation_
 
- Protected Attributes inherited from pcl::IterativeClosestPoint< PointXYZRGBA, PointXYZRGBA, float >
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, 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...
 

Additional Inherited Members

- Public Types inherited from pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >
using PointCloudSource = pcl::PointCloud< PointXYZRGBA >
 
using PointCloudSourcePtr = typename PointCloudSource::Ptr
 
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr
 
using PointCloudTarget = pcl::PointCloud< PointXYZRGBA >
 
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< PointXYZRGBA, PointXYZRGBA, float >::KdTree
 
using InputKdTreePtr = typename Registration< PointXYZRGBA, PointXYZRGBA, float >::KdTreePtr
 
using Ptr = shared_ptr< GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA, float > >
 
using ConstPtr = shared_ptr< const GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA, float > >
 
using Vector3 = typename Eigen::Matrix< float, 3, 1 >
 
using Vector4 = typename Eigen::Matrix< float, 4, 1 >
 
using Vector6d = Eigen::Matrix< double, 6, 1 >
 
using Matrix3 = typename Eigen::Matrix< float, 3, 3 >
 
using Matrix4 = typename IterativeClosestPoint< PointXYZRGBA, PointXYZRGBA, float >::Matrix4
 
using Matrix6d = Eigen::Matrix< double, 6, 6 >
 
using AngleAxis = typename Eigen::AngleAxis< float >
 
- Public Types inherited from pcl::IterativeClosestPoint< PointXYZRGBA, PointXYZRGBA, float >
using PointCloudSource = typename Registration< PointXYZRGBA, PointXYZRGBA, float >::PointCloudSource
 
using PointCloudSourcePtr = typename PointCloudSource::Ptr
 
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr
 
using PointCloudTarget = typename Registration< PointXYZRGBA, PointXYZRGBA, 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< PointXYZRGBA, PointXYZRGBA, float > >
 
using ConstPtr = shared_ptr< const IterativeClosestPoint< PointXYZRGBA, PointXYZRGBA, float > >
 
using Matrix4 = typename Registration< PointXYZRGBA, PointXYZRGBA, float >::Matrix4
 
- 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 Attributes inherited from pcl::IterativeClosestPoint< PointXYZRGBA, PointXYZRGBA, float >
pcl::registration::DefaultConvergenceCriteria< float >::Ptr convergence_criteria_
 

Detailed Description

GeneralizedIterativeClosestPoint6D integrates L*a*b* color space information into the Generalized Iterative Closest Point (GICP) algorithm.

The suggested input is PointXYZRGBA.

Note
If you use this code in any academic work, please cite:
Author
Martin Holzkothen, Michael Korn

Definition at line 65 of file gicp6d.h.

Constructor & Destructor Documentation

◆ GeneralizedIterativeClosestPoint6D()

pcl::GeneralizedIterativeClosestPoint6D::GeneralizedIterativeClosestPoint6D ( float  lab_weight = 0.032f)

constructor.

Parameters
[in]lab_weightthe color weight

Member Function Documentation

◆ computeTransformation()

void pcl::GeneralizedIterativeClosestPoint6D::computeTransformation ( PointCloudSource output,
const Eigen::Matrix4f &  guess 
)
overrideprotected

Rigid transformation computation method with initial guess.

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

◆ searchForNeighbors()

bool pcl::GeneralizedIterativeClosestPoint6D::searchForNeighbors ( const PointXYZLAB query,
pcl::Indices index,
std::vector< float > &  distance 
)
inlineprotected

Search for the closest nearest neighbor of a given point.

Parameters
querythe point to search a nearest neighbour for
indexvector of size 1 to store the index of the nearest neighbour found
distancevector of size 1 to store the distance to nearest neighbour found

◆ setInputSource()

void pcl::GeneralizedIterativeClosestPoint6D::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)

Parameters
[in]cloudthe input point cloud source

◆ setInputTarget()

void pcl::GeneralizedIterativeClosestPoint6D::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)

Parameters
[in]targetthe input point cloud target

Member Data Documentation

◆ cloud_lab_

pcl::PointCloud<PointXYZLAB>::Ptr pcl::GeneralizedIterativeClosestPoint6D::cloud_lab_
protected

Holds the converted (LAB) data cloud.

Definition at line 115 of file gicp6d.h.

◆ lab_weight_

float pcl::GeneralizedIterativeClosestPoint6D::lab_weight_
protected

The color weight.

Definition at line 124 of file gicp6d.h.

◆ point_rep_

MyPointRepresentation pcl::GeneralizedIterativeClosestPoint6D::point_rep_
protected

Enables 6d searches with kd-tree class using the color weight.

Definition at line 164 of file gicp6d.h.

◆ target_lab_

pcl::PointCloud<PointXYZLAB>::Ptr pcl::GeneralizedIterativeClosestPoint6D::target_lab_
protected

Holds the converted (LAB) model cloud.

Definition at line 118 of file gicp6d.h.

◆ target_tree_lab_

KdTreeFLANN<PointXYZLAB> pcl::GeneralizedIterativeClosestPoint6D::target_tree_lab_
protected

6d-tree to search in model cloud.

Definition at line 121 of file gicp6d.h.


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