1. NDT介绍
Normal Distributions Transform (NDT) 算法对于大型点云比较有效,它使用3D点云统计模型的标准最优化技术来确定两个点云可能的配准。NDT配准算法耗时稳定,跟初值相关不大,初值误差大时,也能很好的纠正过来。
NDT算法步骤为:
- 将空间(reference scan)划分成各个格子cell
- 将点云投票到各个格子
- 计算格子的正态分布的参数
- 将第二幅scan的每个点按转移矩阵T的变换
- 第二幅scan的点落于reference的哪个格子,计算响应的概率分布函数
- 求所有点的最优值,目标函数为
如果想要了解更多信息可以查阅Martin Magnusson的2009年博士论文:《The Three-Dimensional Normal Distributions Transform – an Efficient Representation for Registration, Surface Analysis, and Loop Detection》
2. NDT代码示例
#include <iostream>
#include <thread>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/registration/ndt.h>
#include <pcl/filters/approximate_voxel_grid.h>
#include <pcl/visualization/pcl_visualizer.h>
using namespace std::chrono;
int
main (int argc, char** argv)
{
// Loading first scan of room.
// 加载房间的第一次扫描点云数据作为目标
pcl::PointCloud<pcl::PointXYZ>::Ptr target_cloud (new pcl::PointCloud<pcl::PointXYZ>);
if (pcl::io::loadPCDFile<pcl::PointXYZ> ("room_scan1.pcd", *target_cloud) == -1)
{
PCL_ERROR ("Couldn't read file room_scan1.pcd \n");
return (-1);
}
std::cout << "Loaded " << target_cloud->size () << " data points from room_scan1.pcd" << std::endl;
// Loading second scan of room from new perspective.
// 加载从新视角得到的第二次扫描点云数据作为源点云
pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ>);
if (pcl::io::loadPCDFile<pcl::PointXYZ> ("room_scan2.pcd", *input_cloud) == -1)
{
PCL_ERROR ("Couldn't read file room_scan2.pcd \n");
return (-1);
}
std::cout << "Loaded " << input_cloud->size () << " data points from room_scan2.pcd" << std::endl;
// Filtering input scan to roughly 10% of original size to increase speed of registration.
// 将输入的扫描点云数据过滤到原始尺寸的10%以提高匹配的速度,只对源点云进行滤波,减少其数据量,而目标点云不需要滤波处理
//因为在NDT算法中在目标点云对应的体素网格数据结构的统计计算不使用单个点,而是使用包含在每个体素单元格中的点的统计数据
pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::ApproximateVoxelGrid<pcl::PointXYZ> approximate_voxel_filter;
approximate_voxel_filter.setLeafSize (0.2, 0.2, 0.2);
approximate_voxel_filter.setInputCloud (input_cloud);
approximate_voxel_filter.filter (*filtered_cloud);
std::cout << "Filtered cloud contains " << filtered_cloud->size ()
<< " data points from room_scan2.pcd" << std::endl;
// Initializing Normal Distributions Transform (NDT).
//初始化ndt
pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> ndt;
// Setting scale dependent NDT parameters
// Setting minimum transformation difference for termination condition.
ndt.setTransformationEpsilon (0.01);//为终止条件设置最小转换差异
// Setting maximum step size for More-Thuente line search.
ndt.setStepSize (0.1);//为more-thuente线搜索设置最大步长
//Setting Resolution of NDT grid structure (VoxelGridCovariance).
ndt.setResolution (1.0); //设置NDT网格网格结构的分辨率(voxelgridcovariance)
// Setting max number of registration iterations.
//添加最大迭代次数限制能够增加程序的鲁棒性阻止了它在错误的方向上运行时间过长
ndt.setMaximumIterations (35);
// Setting point cloud to be aligned.
ndt.setInputSource (filtered_cloud); //源点云
// Setting point cloud to be aligned to.
ndt.setInputTarget (target_cloud);//目标点云
// Set initial alignment estimate found using robot odometry.
// 设置使用机器人测距法得到的粗略初始变换矩阵结果
Eigen::AngleAxisf init_rotation (0.6931, Eigen::Vector3f::UnitZ ());
Eigen::Translation3f init_translation (1.79387, 0.720047, 0);
Eigen::Matrix4f init_guess = (init_translation * init_rotation).matrix ();
// Calculating required rigid transform to align the input cloud to the target cloud.
// 计算需要的刚体变换以便将输入的源点云匹配到目标点云
pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud (new pcl::PointCloud<pcl::PointXYZ>);
ndt.align (*output_cloud, init_guess);
//这个地方的output_cloud不能作为最终的源点云变换,因为上面对点云进行了滤波处理
std::cout << "Normal Distributions Transform has converged:" << ndt.hasConverged ()
<< " score: " << ndt.getFitnessScore () << std::endl;
// Transforming unfiltered, input cloud using found transform.
// 使用创建的变换对为过滤的输入点云进行变换
pcl::transformPointCloud (*input_cloud, *output_cloud, ndt.getFinalTransformation ());
// Saving transformed input cloud.
// 保存转换后的源点云作为最终的变换输出
pcl::io::savePCDFileASCII ("room_scan2_transformed.pcd", *output_cloud);
// Initializing point cloud visualizer
// 初始化点云可视化对象
pcl::visualization::PCLVisualizer::Ptr
viewer_final (new pcl::visualization::PCLVisualizer ("3D Viewer"));
viewer_final->setBackgroundColor (0, 0, 0);
// Coloring and visualizing target cloud (red).
// 对目标点云着色可视化 (red).
pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>
target_color (target_cloud, 255, 0, 0);
viewer_final->addPointCloud<pcl::PointXYZ> (target_cloud, target_color, "target cloud");
viewer_final->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE,
1, "target cloud");
// Coloring and visualizing transformed input cloud (green).
// 对转换后的源点云着色 (green)可视化.
pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>
output_color (output_cloud, 0, 255, 0);
viewer_final->addPointCloud<pcl::PointXYZ> (output_cloud, output_color, "output cloud");
viewer_final->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE,
1, "output cloud");
// Starting visualizer
viewer_final->addCoordinateSystem (1.0, "global");//显示XYZ指示轴
viewer_final->initCameraParameters ();//初始化摄像头参数
// Wait until visualizer window is closed.
while (!viewer_final->wasStopped ())
{
viewer_final->spinOnce (100);
//std::this_thread::sleep_for(100);
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
return (0);
}
未匹配的room_scan1和room_scan2如下图所示:
使用NDT匹配后的效果图如下所示: