cpp-toolbox  0.0.1
A toolbox library for C++
Loading...
Searching...
No Matches
toolbox::pcl::generalized_icp_t< DataType, KNNSearcher > Class Template Reference

Generalized ICP (Plane-to-Plane) 算法实现 / Generalized ICP algorithm implementation. More...

#include <generalized_icp.hpp>

Inheritance diagram for toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >:

Public Types

using base_type = base_fine_registration_t< generalized_icp_t< DataType, KNNSearcher >, DataType >
 
using point_type = toolbox::types::point_t< DataType >
 
using knn_searcher_type = KNNSearcher
 
using Matrix3 = Eigen::Matrix< DataType, 3, 3 >
 
using Vector3 = Eigen::Matrix< DataType, 3, 1 >
 
using Vector6 = Eigen::Matrix< DataType, 6, 1 >
 
using Matrix6 = Eigen::Matrix< DataType, 6, 6 >
 
using point_cloud = toolbox::types::point_cloud_t< DataType >
 
using point_cloud_ptr = std::shared_ptr< point_cloud >
 
using transformation_t = Eigen::Matrix< DataType, 4, 4 >
 
using result_type = fine_registration_result_t< DataType >
 
- Public Types inherited from toolbox::pcl::base_fine_registration_t< Derived, DataType >
using point_cloud = toolbox::types::point_cloud_t< DataType >
 
using point_cloud_ptr = std::shared_ptr< point_cloud >
 
using transformation_t = Eigen::Matrix< DataType, 4, 4 >
 
using result_type = fine_registration_result_t< DataType >
 
using iteration_callback_t = std::function< bool(const iteration_state_t< DataType > &)>
 

Public Member Functions

 generalized_icp_t (bool enable_parallel=false)
 构造函数 / Constructor
 
void set_enable_parallel (bool enable)
 设置是否启用并行优化 / Set whether to enable parallel optimization
 
bool get_enable_parallel () const
 获取是否启用并行优化 / Get whether parallel optimization is enabled
 
correspondence_type_e get_correspondence_type_impl () const
 获取对应关系类型 / Get correspondence type
 
void set_k_correspondences (std::size_t k)
 设置用于协方差估计的近邻数 / Set number of neighbors for covariance estimation
 
std::size_t get_k_correspondences () const
 获取用于协方差估计的近邻数 / Get number of neighbors for covariance estimation
 
void set_covariance_epsilon (DataType epsilon)
 设置协方差正则化参数 / Set covariance regularization parameter
 
DataType get_covariance_epsilon () const
 获取协方差正则化参数 / Get covariance regularization parameter
 
void set_outlier_rejection_ratio (DataType ratio)
 设置异常值剔除比例 / Set outlier rejection ratio
 
DataType get_outlier_rejection_ratio () const
 获取异常值剔除比例 / Get outlier rejection ratio
 
void set_optimizer_max_iterations (std::size_t max_iter)
 设置优化器最大内部迭代次数 / Set optimizer maximum inner iterations
 
std::size_t get_optimizer_max_iterations () const
 获取优化器最大内部迭代次数 / Get optimizer maximum inner iterations
 
- Public Member Functions inherited from toolbox::pcl::base_fine_registration_t< Derived, DataType >
 base_fine_registration_t ()=default
 
virtual ~base_fine_registration_t ()=default
 
 base_fine_registration_t (const base_fine_registration_t &)=delete
 
base_fine_registration_toperator= (const base_fine_registration_t &)=delete
 
 base_fine_registration_t (base_fine_registration_t &&)=default
 
base_fine_registration_toperator= (base_fine_registration_t &&)=default
 
void set_source (const point_cloud_ptr &source)
 设置源点云 / Set source point cloud
 
void set_target (const point_cloud_ptr &target)
 设置目标点云 / Set target point cloud
 
void set_max_iterations (std::size_t max_iterations)
 设置最大迭代次数 / Set maximum iterations
 
std::size_t get_max_iterations () const
 获取最大迭代次数 / Get maximum iterations
 
void set_transformation_epsilon (DataType epsilon)
 设置变换epsilon(收敛阈值) / Set transformation epsilon (convergence threshold)
 
DataType get_transformation_epsilon () const
 获取变换epsilon / Get transformation epsilon
 
void set_euclidean_fitness_epsilon (DataType epsilon)
 设置欧氏距离epsilon / Set Euclidean fitness epsilon
 
DataType get_euclidean_fitness_epsilon () const
 获取欧氏距离epsilon / Get Euclidean fitness epsilon
 
void set_max_correspondence_distance (DataType distance)
 设置最大对应距离 / Set maximum correspondence distance
 
DataType get_max_correspondence_distance () const
 获取最大对应距离 / Get maximum correspondence distance
 
void set_record_history (bool record)
 设置是否记录迭代历史 / Set whether to record iteration history
 
bool get_record_history () const
 获取是否记录迭代历史 / Get whether to record iteration history
 
void set_iteration_callback (iteration_callback_t callback)
 设置迭代回调函数 / Set iteration callback function
 
correspondence_type_e get_correspondence_type () const
 获取对应关系类型 / Get correspondence type
 
bool has_source_normals () const
 检查源点云是否有法线 / Check if source cloud has normals
 
bool has_target_normals () const
 检查目标点云是否有法线 / Check if target cloud has normals
 
bool align (const transformation_t &initial_guess, result_type &result)
 执行配准 / Perform registration
 
bool align (result_type &result)
 执行配准(使用单位矩阵作为初始猜测) / Perform registration (using identity as initial guess)
 

Protected Member Functions

void preprocess_impl ()
 预处理(构建KD树和计算协方差) / Preprocessing (build KD-trees and compute covariances)
 
bool align_impl (const transformation_t &initial_guess, result_type &result)
 执行配准 / Perform registration
 
void compute_covariances (const point_cloud &cloud, knn_searcher_type &searcher, std::vector< Matrix3 > &covariances)
 计算点云的协方差矩阵 / Compute covariance matrices for point cloud
 
void find_correspondences (const point_cloud &transformed_source, std::vector< std::pair< std::size_t, std::size_t > > &correspondences, std::vector< DataType > &distances)
 查找对应关系 / Find correspondences
 
transformation_t compute_transformation (const point_cloud &source, const point_cloud &target, const std::vector< std::pair< std::size_t, std::size_t > > &correspondences, const transformation_t &current_transform)
 计算变换矩阵(使用L-BFGS优化) / Compute transformation matrix (using L-BFGS optimization)
 
DataType compute_mahalanobis_distance (const Vector3 &p_src, const Vector3 &p_tgt, const Matrix3 &C_src, const Matrix3 &C_tgt, const transformation_t &transform, Vector6 *gradient=nullptr) const
 计算Mahalanobis距离和梯度 / Compute Mahalanobis distance and gradient
 
DataType compute_error (const point_cloud &source, const point_cloud &target, const std::vector< std::pair< std::size_t, std::size_t > > &correspondences, const transformation_t &transform) const
 计算配准误差 / Compute registration error
 
void reject_outliers (std::vector< std::pair< std::size_t, std::size_t > > &correspondences, std::vector< DataType > &distances)
 剔除异常值 / Reject outliers
 
DataType objective_function (const Vector6 &x, const point_cloud &source, const point_cloud &target, const std::vector< std::pair< std::size_t, std::size_t > > &correspondences, const transformation_t &base_transform, Vector6 *gradient=nullptr) const
 优化目标函数 / Optimization objective function
 
Vector6 lbfgs_optimize (const Vector6 &x0, const point_cloud &source, const point_cloud &target, const std::vector< std::pair< std::size_t, std::size_t > > &correspondences, const transformation_t &base_transform)
 L-BFGS优化器 / L-BFGS optimizer.
 
Vector6 transformation_to_vector (const transformation_t &transform) const
 将变换矩阵转换为优化向量 / Convert transformation matrix to optimization vector
 
transformation_t vector_to_transformation (const Vector6 &vec) const
 将优化向量转换为变换矩阵 / Convert optimization vector to transformation matrix
 
- Protected Member Functions inherited from toolbox::pcl::base_fine_registration_t< Derived, DataType >
bool validate_input () const
 验证输入 / Validate input
 
bool validate_input_impl () const
 派生类的额外输入验证 / Additional input validation for derived class
 
bool has_converged (std::size_t iteration, const transformation_t &current_transform, const transformation_t &previous_transform, DataType current_error, DataType previous_error, std::string &termination_reason) const
 检查收敛条件 / Check convergence criteria
 
bool has_converged_impl (std::size_t, const transformation_t &, const transformation_t &, DataType, DataType, std::string &) const
 派生类的额外收敛检查 / Additional convergence check for derived class
 
void preprocess_impl ()
 预处理钩子(派生类实现) / Preprocessing hook (derived class implementation)
 
void record_iteration (result_type &result, std::size_t iteration, const transformation_t &transform, DataType error, DataType error_change, std::size_t num_correspondences)
 记录迭代状态 / Record iteration state
 

Friends

class base_fine_registration_t< generalized_icp_t< DataType, KNNSearcher >, DataType >
 

Additional Inherited Members

- Protected Attributes inherited from toolbox::pcl::base_fine_registration_t< Derived, DataType >
point_cloud_ptr m_source_cloud
 
point_cloud_ptr m_target_cloud
 
std::size_t m_max_iterations = 50
 
DataType m_transformation_epsilon = static_cast<DataType>(1e-8)
 
DataType m_euclidean_fitness_epsilon = static_cast<DataType>(1e-6)
 
DataType m_max_correspondence_distance = static_cast<DataType>(0.05)
 
bool m_source_updated = false
 
bool m_target_updated = false
 
bool m_record_history = false
 
iteration_callback_t m_iteration_callback
 

Detailed Description

template<typename DataType, typename KNNSearcher = kdtree_t<DataType>>
class toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >

Generalized ICP (Plane-to-Plane) 算法实现 / Generalized ICP algorithm implementation.

该算法考虑两个点云的局部平面结构,通过协方差矩阵建模局部不确定性。 This algorithm considers local planar structure of both point clouds, modeling local uncertainty through covariance matrices.

Template Parameters
DataType数据类型 / Data type
KNNSearcherKNN搜索器类型 / KNN searcher type
// 使用示例 / Usage example
// 设置点云 / Set point clouds
gicp.set_source(source_cloud);
gicp.set_target(target_cloud);
// 设置参数 / Set parameters
gicp.set_k_correspondences(20); // 用于协方差估计的邻居数
// 执行配准 / Perform registration
gicp.align(initial_guess, result);
void set_target(const point_cloud_ptr &target)
设置目标点云 / Set target point cloud
Definition base_fine_registration.hpp:69
void set_source(const point_cloud_ptr &source)
设置源点云 / Set source point cloud
Definition base_fine_registration.hpp:60
void set_max_iterations(std::size_t max_iterations)
设置最大迭代次数 / Set maximum iterations
Definition base_fine_registration.hpp:78
bool align(const transformation_t &initial_guess, result_type &result)
执行配准 / Perform registration
Definition base_fine_registration.hpp:189
Generalized ICP (Plane-to-Plane) 算法实现 / Generalized ICP algorithm implementation.
Definition generalized_icp.hpp:44
void set_k_correspondences(std::size_t k)
设置用于协方差估计的近邻数 / Set number of neighbors for covariance estimation
Definition generalized_icp.hpp:90
细配准结果 / Fine registration result
Definition registration_result.hpp:46

Member Typedef Documentation

◆ base_type

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::base_type = base_fine_registration_t<generalized_icp_t<DataType, KNNSearcher>, DataType>

◆ knn_searcher_type

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::knn_searcher_type = KNNSearcher

◆ Matrix3

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::Matrix3 = Eigen::Matrix<DataType, 3, 3>

◆ Matrix6

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::Matrix6 = Eigen::Matrix<DataType, 6, 6>

◆ point_cloud

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::base_fine_registration_t< Derived, DataType >::point_cloud = toolbox::types::point_cloud_t<DataType>

◆ point_cloud_ptr

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::base_fine_registration_t< Derived, DataType >::point_cloud_ptr = std::shared_ptr<point_cloud>

◆ point_type

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::point_type = toolbox::types::point_t<DataType>

◆ result_type

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::base_fine_registration_t< Derived, DataType >::result_type = fine_registration_result_t<DataType>

◆ transformation_t

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::base_fine_registration_t< Derived, DataType >::transformation_t = Eigen::Matrix<DataType, 4, 4>

◆ Vector3

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::Vector3 = Eigen::Matrix<DataType, 3, 1>

◆ Vector6

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
using toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::Vector6 = Eigen::Matrix<DataType, 6, 1>

Constructor & Destructor Documentation

◆ generalized_icp_t()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::generalized_icp_t ( bool  enable_parallel = false)
inlineexplicit

构造函数 / Constructor

Parameters
enable_parallel是否启用并行优化(默认开启) / Enable parallel optimization (default enabled)

Member Function Documentation

◆ align_impl()

template<typename DataType , typename KNNSearcher >
bool toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::align_impl ( const transformation_t initial_guess,
result_type result 
)
protected

执行配准 / Perform registration

◆ compute_covariances()

template<typename DataType , typename KNNSearcher >
void toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::compute_covariances ( const point_cloud cloud,
knn_searcher_type searcher,
std::vector< Matrix3 > &  covariances 
)
protected

计算点云的协方差矩阵 / Compute covariance matrices for point cloud

◆ compute_error()

template<typename DataType , typename KNNSearcher >
DataType toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::compute_error ( const point_cloud source,
const point_cloud target,
const std::vector< std::pair< std::size_t, std::size_t > > &  correspondences,
const transformation_t transform 
) const
protected

计算配准误差 / Compute registration error

◆ compute_mahalanobis_distance()

template<typename DataType , typename KNNSearcher >
DataType toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::compute_mahalanobis_distance ( const Vector3 p_src,
const Vector3 p_tgt,
const Matrix3 C_src,
const Matrix3 C_tgt,
const transformation_t transform,
Vector6 gradient = nullptr 
) const
protected

计算Mahalanobis距离和梯度 / Compute Mahalanobis distance and gradient

◆ compute_transformation()

template<typename DataType , typename KNNSearcher >
generalized_icp_t< DataType, KNNSearcher >::transformation_t toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::compute_transformation ( const point_cloud source,
const point_cloud target,
const std::vector< std::pair< std::size_t, std::size_t > > &  correspondences,
const transformation_t current_transform 
)
protected

计算变换矩阵(使用L-BFGS优化) / Compute transformation matrix (using L-BFGS optimization)

◆ find_correspondences()

template<typename DataType , typename KNNSearcher >
void toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::find_correspondences ( const point_cloud transformed_source,
std::vector< std::pair< std::size_t, std::size_t > > &  correspondences,
std::vector< DataType > &  distances 
)
protected

查找对应关系 / Find correspondences

◆ get_correspondence_type_impl()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
correspondence_type_e toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::get_correspondence_type_impl ( ) const
inline

获取对应关系类型 / Get correspondence type

◆ get_covariance_epsilon()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
DataType toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::get_covariance_epsilon ( ) const
inline

获取协方差正则化参数 / Get covariance regularization parameter

◆ get_enable_parallel()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
bool toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::get_enable_parallel ( ) const
inline

获取是否启用并行优化 / Get whether parallel optimization is enabled

◆ get_k_correspondences()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
std::size_t toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::get_k_correspondences ( ) const
inline

获取用于协方差估计的近邻数 / Get number of neighbors for covariance estimation

◆ get_optimizer_max_iterations()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
std::size_t toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::get_optimizer_max_iterations ( ) const
inline

获取优化器最大内部迭代次数 / Get optimizer maximum inner iterations

◆ get_outlier_rejection_ratio()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
DataType toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::get_outlier_rejection_ratio ( ) const
inline

获取异常值剔除比例 / Get outlier rejection ratio

◆ lbfgs_optimize()

template<typename DataType , typename KNNSearcher >
generalized_icp_t< DataType, KNNSearcher >::Vector6 toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::lbfgs_optimize ( const Vector6 x0,
const point_cloud source,
const point_cloud target,
const std::vector< std::pair< std::size_t, std::size_t > > &  correspondences,
const transformation_t base_transform 
)
protected

L-BFGS优化器 / L-BFGS optimizer.

◆ objective_function()

template<typename DataType , typename KNNSearcher >
DataType toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::objective_function ( const Vector6 x,
const point_cloud source,
const point_cloud target,
const std::vector< std::pair< std::size_t, std::size_t > > &  correspondences,
const transformation_t base_transform,
Vector6 gradient = nullptr 
) const
protected

优化目标函数 / Optimization objective function

◆ preprocess_impl()

template<typename DataType , typename KNNSearcher >
void toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::preprocess_impl ( )
protected

预处理(构建KD树和计算协方差) / Preprocessing (build KD-trees and compute covariances)

◆ reject_outliers()

template<typename DataType , typename KNNSearcher >
void toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::reject_outliers ( std::vector< std::pair< std::size_t, std::size_t > > &  correspondences,
std::vector< DataType > &  distances 
)
protected

剔除异常值 / Reject outliers

◆ set_covariance_epsilon()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
void toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::set_covariance_epsilon ( DataType  epsilon)
inline

设置协方差正则化参数 / Set covariance regularization parameter

Parameters
epsilon正则化系数 / Regularization coefficient

◆ set_enable_parallel()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
void toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::set_enable_parallel ( bool  enable)
inline

设置是否启用并行优化 / Set whether to enable parallel optimization

◆ set_k_correspondences()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
void toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::set_k_correspondences ( std::size_t  k)
inline

设置用于协方差估计的近邻数 / Set number of neighbors for covariance estimation

◆ set_optimizer_max_iterations()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
void toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::set_optimizer_max_iterations ( std::size_t  max_iter)
inline

设置优化器最大内部迭代次数 / Set optimizer maximum inner iterations

◆ set_outlier_rejection_ratio()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
void toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::set_outlier_rejection_ratio ( DataType  ratio)
inline

设置异常值剔除比例 / Set outlier rejection ratio

◆ transformation_to_vector()

template<typename DataType , typename KNNSearcher >
generalized_icp_t< DataType, KNNSearcher >::Vector6 toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::transformation_to_vector ( const transformation_t transform) const
protected

将变换矩阵转换为优化向量 / Convert transformation matrix to optimization vector

◆ vector_to_transformation()

template<typename DataType , typename KNNSearcher >
generalized_icp_t< DataType, KNNSearcher >::transformation_t toolbox::pcl::generalized_icp_t< DataType, KNNSearcher >::vector_to_transformation ( const Vector6 vec) const
protected

将优化向量转换为变换矩阵 / Convert optimization vector to transformation matrix

Friends And Related Symbol Documentation

◆ base_fine_registration_t< generalized_icp_t< DataType, KNNSearcher >, DataType >

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
friend class base_fine_registration_t< generalized_icp_t< DataType, KNNSearcher >, DataType >
friend

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