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

NDT (Normal Distributions Transform) 算法实现 / NDT algorithm implementation. More...

#include <ndt.hpp>

Inheritance diagram for toolbox::pcl::ndt_t< DataType >:

Classes

struct  voxel_cell_t
 体素单元结构 / Voxel cell structure More...
 

Public Types

using base_type = base_fine_registration_t< ndt_t< DataType >, DataType >
 
using point_type = toolbox::types::point_t< DataType >
 
using Vector3 = Eigen::Matrix< DataType, 3, 1 >
 
using Matrix3 = Eigen::Matrix< DataType, 3, 3 >
 
using Vector6 = Eigen::Matrix< DataType, 6, 1 >
 
using Matrix6 = Eigen::Matrix< DataType, 6, 6 >
 
- Public Types inherited from toolbox::pcl::base_fine_registration_t< ndt_t< DataType >, 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

 ndt_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_resolution (DataType resolution)
 设置体素分辨率 / Set voxel resolution
 
DataType get_resolution () const
 获取体素分辨率 / Get voxel resolution
 
void set_step_size (DataType step_size)
 设置步长 / Set step size
 
DataType get_step_size () const
 获取步长 / Get step size
 
void set_outlier_ratio (DataType ratio)
 设置异常值比例 / Set outlier ratio
 
DataType get_outlier_ratio () const
 获取异常值比例 / Get outlier ratio
 
void set_line_search_max_iterations (std::size_t max_iter)
 设置线搜索最大步长缩放次数 / Set line search maximum step scaling iterations
 
std::size_t get_line_search_max_iterations () const
 获取线搜索最大步长缩放次数 / Get line search maximum step scaling iterations
 
- Public Member Functions inherited from toolbox::pcl::base_fine_registration_t< ndt_t< DataType >, DataType >
 base_fine_registration_t ()=default
 
 base_fine_registration_t (const base_fine_registration_t &)=delete
 
 base_fine_registration_t (base_fine_registration_t &&)=default
 
virtual ~base_fine_registration_t ()=default
 
base_fine_registration_toperator= (const base_fine_registration_t &)=delete
 
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 ()
 预处理(构建体素网格) / Preprocessing (build voxel grid)
 
bool align_impl (const transformation_t &initial_guess, result_type &result)
 执行配准 / Perform registration
 
void build_voxel_grid ()
 构建体素网格 / Build voxel grid
 
std::array< int, 3 > compute_voxel_index (const Vector3 &point) const
 计算体素索引 / Compute voxel index
 
std::size_t get_voxel_key (const std::array< int, 3 > &index) const
 获取体素键值 / Get voxel key
 
DataType compute_objective (const transformation_t &transform, Vector6 *gradient=nullptr, Matrix6 *hessian=nullptr) const
 计算目标函数和梯度 / Compute objective function and gradient
 
DataType compute_point_contribution (const Vector3 &point, const transformation_t &transform, Vector6 *gradient=nullptr, Matrix6 *hessian=nullptr) const
 计算单个点的贡献 / Compute contribution of single point
 
DataType line_search (const transformation_t &current_transform, const Vector6 &direction, DataType initial_step_size)
 执行More-Thuente线搜索 / Perform More-Thuente line search
 
transformation_t vector_to_transformation (const Vector6 &vec) const
 将优化向量转换为变换矩阵 / Convert optimization vector to transformation matrix
 
DataType gaussian_d1 (DataType x_bar, DataType x, const Matrix3 &c_inv) const
 计算高斯分布的值 / Compute Gaussian distribution value
 
void compute_jacobian (const Vector3 &point, Eigen::Matrix< DataType, 3, 6 > &jacobian) const
 计算雅可比矩阵 / Compute Jacobian matrix
 
- Protected Member Functions inherited from toolbox::pcl::base_fine_registration_t< ndt_t< DataType >, 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< ndt_t< DataType >, DataType >
 

Additional Inherited Members

- Protected Attributes inherited from toolbox::pcl::base_fine_registration_t< ndt_t< DataType >, DataType >
point_cloud_ptr m_source_cloud
 
point_cloud_ptr m_target_cloud
 
std::size_t m_max_iterations
 
DataType m_transformation_epsilon
 
DataType m_euclidean_fitness_epsilon
 
DataType m_max_correspondence_distance
 
bool m_source_updated
 
bool m_target_updated
 
bool m_record_history
 
iteration_callback_t m_iteration_callback
 

Detailed Description

template<typename DataType>
class toolbox::pcl::ndt_t< DataType >

NDT (Normal Distributions Transform) 算法实现 / NDT algorithm implementation.

该算法将点云转换为体素网格的概率分布,通过最大化似然函数进行配准。 This algorithm converts point cloud to probability distributions in voxel grid, and performs registration by maximizing the likelihood function.

Template Parameters
DataType数据类型 / Data type
// 使用示例 / Usage example
// 设置体素分辨率 / Set voxel resolution
// 设置优化参数 / Set optimization parameters
// 设置点云 / Set point clouds
ndt.set_source(source_cloud);
ndt.set_target(target_cloud);
// 执行配准 / Perform registration
ndt.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
NDT (Normal Distributions Transform) 算法实现 / NDT algorithm implementation.
Definition ndt.hpp:47
void set_step_size(DataType step_size)
设置步长 / Set step size
Definition ndt.hpp:116
void set_outlier_ratio(DataType ratio)
设置异常值比例 / Set outlier ratio
Definition ndt.hpp:129
void set_resolution(DataType resolution)
设置体素分辨率 / Set voxel resolution
Definition ndt.hpp:102
ndt_t< float > ndt
Definition registration.hpp:108
细配准结果 / Fine registration result
Definition registration_result.hpp:46

Member Typedef Documentation

◆ base_type

template<typename DataType >
using toolbox::pcl::ndt_t< DataType >::base_type = base_fine_registration_t<ndt_t<DataType>, DataType>

◆ Matrix3

template<typename DataType >
using toolbox::pcl::ndt_t< DataType >::Matrix3 = Eigen::Matrix<DataType, 3, 3>

◆ Matrix6

template<typename DataType >
using toolbox::pcl::ndt_t< DataType >::Matrix6 = Eigen::Matrix<DataType, 6, 6>

◆ point_type

template<typename DataType >
using toolbox::pcl::ndt_t< DataType >::point_type = toolbox::types::point_t<DataType>

◆ Vector3

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

◆ Vector6

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

Constructor & Destructor Documentation

◆ ndt_t()

template<typename DataType >
toolbox::pcl::ndt_t< DataType >::ndt_t ( bool  enable_parallel = false)
inlineexplicit

构造函数 / Constructor

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

Member Function Documentation

◆ align_impl()

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

执行配准 / Perform registration

◆ build_voxel_grid()

template<typename DataType >
void toolbox::pcl::ndt_t< DataType >::build_voxel_grid ( )
protected

构建体素网格 / Build voxel grid

◆ compute_jacobian()

template<typename DataType >
void toolbox::pcl::ndt_t< DataType >::compute_jacobian ( const Vector3 point,
Eigen::Matrix< DataType, 3, 6 > &  jacobian 
) const
protected

计算雅可比矩阵 / Compute Jacobian matrix

◆ compute_objective()

template<typename DataType >
DataType toolbox::pcl::ndt_t< DataType >::compute_objective ( const transformation_t transform,
Vector6 gradient = nullptr,
Matrix6 hessian = nullptr 
) const
protected

计算目标函数和梯度 / Compute objective function and gradient

◆ compute_point_contribution()

template<typename DataType >
DataType toolbox::pcl::ndt_t< DataType >::compute_point_contribution ( const Vector3 point,
const transformation_t transform,
Vector6 gradient = nullptr,
Matrix6 hessian = nullptr 
) const
protected

计算单个点的贡献 / Compute contribution of single point

◆ compute_voxel_index()

template<typename DataType >
std::array< int, 3 > toolbox::pcl::ndt_t< DataType >::compute_voxel_index ( const Vector3 point) const
protected

计算体素索引 / Compute voxel index

◆ gaussian_d1()

template<typename DataType >
DataType toolbox::pcl::ndt_t< DataType >::gaussian_d1 ( DataType  x_bar,
DataType  x,
const Matrix3 c_inv 
) const
protected

计算高斯分布的值 / Compute Gaussian distribution value

◆ get_correspondence_type_impl()

template<typename DataType >
correspondence_type_e toolbox::pcl::ndt_t< DataType >::get_correspondence_type_impl ( ) const
inline

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

◆ get_enable_parallel()

template<typename DataType >
bool toolbox::pcl::ndt_t< DataType >::get_enable_parallel ( ) const
inline

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

◆ get_line_search_max_iterations()

template<typename DataType >
std::size_t toolbox::pcl::ndt_t< DataType >::get_line_search_max_iterations ( ) const
inline

获取线搜索最大步长缩放次数 / Get line search maximum step scaling iterations

◆ get_outlier_ratio()

template<typename DataType >
DataType toolbox::pcl::ndt_t< DataType >::get_outlier_ratio ( ) const
inline

获取异常值比例 / Get outlier ratio

◆ get_resolution()

template<typename DataType >
DataType toolbox::pcl::ndt_t< DataType >::get_resolution ( ) const
inline

获取体素分辨率 / Get voxel resolution

◆ get_step_size()

template<typename DataType >
DataType toolbox::pcl::ndt_t< DataType >::get_step_size ( ) const
inline

获取步长 / Get step size

◆ get_voxel_key()

template<typename DataType >
std::size_t toolbox::pcl::ndt_t< DataType >::get_voxel_key ( const std::array< int, 3 > &  index) const
protected

获取体素键值 / Get voxel key

◆ line_search()

template<typename DataType >
DataType toolbox::pcl::ndt_t< DataType >::line_search ( const transformation_t current_transform,
const Vector6 direction,
DataType  initial_step_size 
)
protected

执行More-Thuente线搜索 / Perform More-Thuente line search

◆ preprocess_impl()

template<typename DataType >
void toolbox::pcl::ndt_t< DataType >::preprocess_impl ( )
protected

预处理(构建体素网格) / Preprocessing (build voxel grid)

◆ set_enable_parallel()

template<typename DataType >
void toolbox::pcl::ndt_t< DataType >::set_enable_parallel ( bool  enable)
inline

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

◆ set_line_search_max_iterations()

template<typename DataType >
void toolbox::pcl::ndt_t< DataType >::set_line_search_max_iterations ( std::size_t  max_iter)
inline

设置线搜索最大步长缩放次数 / Set line search maximum step scaling iterations

◆ set_outlier_ratio()

template<typename DataType >
void toolbox::pcl::ndt_t< DataType >::set_outlier_ratio ( DataType  ratio)
inline

设置异常值比例 / Set outlier ratio

Parameters
ratio异常值比例(0-1) / Outlier ratio (0-1)

◆ set_resolution()

template<typename DataType >
void toolbox::pcl::ndt_t< DataType >::set_resolution ( DataType  resolution)
inline

设置体素分辨率 / Set voxel resolution

Parameters
resolution体素大小 / Voxel size

◆ set_step_size()

template<typename DataType >
void toolbox::pcl::ndt_t< DataType >::set_step_size ( DataType  step_size)
inline

设置步长 / Set step size

Parameters
step_size优化步长 / Optimization step size

◆ vector_to_transformation()

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

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

Friends And Related Symbol Documentation

◆ base_fine_registration_t< ndt_t< DataType >, DataType >

template<typename DataType >
friend class base_fine_registration_t< ndt_t< DataType >, DataType >
friend

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