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

Point-to-Point ICP 算法实现 / Point-to-Point ICP algorithm implementation. More...

#include <point_to_point_icp.hpp>

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

Public Types

using base_type = base_fine_registration_t< point_to_point_icp_t< DataType, KNNSearcher >, DataType >
 
using point_type = toolbox::types::point_t< DataType >
 
using knn_searcher_type = KNNSearcher
 
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

 point_to_point_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_outlier_rejection_ratio (DataType ratio)
 设置异常值剔除比例 / Set outlier rejection ratio
 
DataType get_outlier_rejection_ratio () const
 获取异常值剔除比例 / Get outlier rejection ratio
 
- 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-tree)
 
bool align_impl (const transformation_t &initial_guess, result_type &result)
 执行配准 / Perform registration
 
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 std::vector< DataType > &distances)
 计算变换矩阵(使用SVD) / Compute transformation matrix (using SVD)
 
DataType compute_error (const std::vector< DataType > &distances) const
 计算配准误差 / Compute registration error
 
void reject_outliers (std::vector< std::pair< std::size_t, std::size_t > > &correspondences, std::vector< DataType > &distances)
 剔除异常值 / Reject outliers
 
- 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< point_to_point_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::point_to_point_icp_t< DataType, KNNSearcher >

Point-to-Point ICP 算法实现 / Point-to-Point ICP algorithm implementation.

该算法最小化点对之间的欧氏距离平方和。 This algorithm minimizes the sum of squared Euclidean distances between point pairs.

Template Parameters
DataType数据类型 / Data type
KNNSearcherKNN搜索器类型 / KNN searcher type
// 使用默认KD树 / Using default KD-tree
// 使用自定义KNN搜索器 / Using custom KNN searcher
// 设置点云 / Set point clouds
icp.set_source(source_cloud);
icp.set_target(target_cloud);
// 执行配准 / Perform registration
icp.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
bool align(const transformation_t &initial_guess, result_type &result)
执行配准 / Perform registration
Definition base_fine_registration.hpp:189
Point-to-Point ICP 算法实现 / Point-to-Point ICP algorithm implementation.
Definition point_to_point_icp.hpp:42
细配准结果 / Fine registration result
Definition registration_result.hpp:46

Member Typedef Documentation

◆ base_type

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

◆ knn_searcher_type

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

◆ 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::point_to_point_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>

Constructor & Destructor Documentation

◆ point_to_point_icp_t()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
toolbox::pcl::point_to_point_icp_t< DataType, KNNSearcher >::point_to_point_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::point_to_point_icp_t< DataType, KNNSearcher >::align_impl ( const transformation_t initial_guess,
result_type result 
)
protected

执行配准 / Perform registration

◆ compute_error()

template<typename DataType , typename KNNSearcher >
DataType toolbox::pcl::point_to_point_icp_t< DataType, KNNSearcher >::compute_error ( const std::vector< DataType > &  distances) const
protected

计算配准误差 / Compute registration error

◆ compute_transformation()

template<typename DataType , typename KNNSearcher >
point_to_point_icp_t< DataType, KNNSearcher >::transformation_t toolbox::pcl::point_to_point_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 std::vector< DataType > &  distances 
)
protected

计算变换矩阵(使用SVD) / Compute transformation matrix (using SVD)

◆ find_correspondences()

template<typename DataType , typename KNNSearcher >
void toolbox::pcl::point_to_point_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::point_to_point_icp_t< DataType, KNNSearcher >::get_correspondence_type_impl ( ) const
inline

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

◆ get_enable_parallel()

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

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

◆ get_outlier_rejection_ratio()

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

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

◆ preprocess_impl()

template<typename DataType , typename KNNSearcher = kdtree_t<DataType>>
void toolbox::pcl::point_to_point_icp_t< DataType, KNNSearcher >::preprocess_impl ( )
inlineprotected

预处理(构建KD树) / Preprocessing (build KD-tree)

◆ reject_outliers()

template<typename DataType , typename KNNSearcher >
void toolbox::pcl::point_to_point_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_enable_parallel()

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

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

◆ set_outlier_rejection_ratio()

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

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

Parameters
ratio剔除比例(0-1),0表示不剔除 / Rejection ratio (0-1), 0 means no rejection

Friends And Related Symbol Documentation

◆ base_fine_registration_t< point_to_point_icp_t< DataType, KNNSearcher >, DataType >

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

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