PCL 筛选对应点对(距离筛选+中值筛选+法线一致性筛选+ICP重叠率估计筛选+一对一删除重复点对)(Registration_CorrespondenceRejector)

PCL专栏目录及须知

注意:本文较长,包括PCL中大多数筛选对应点对的方法,该方法均用于提高配准的精确性和减少可能的误匹配。因方法大多简单,合并为一个文章。目录如下。

目录

1.根据距离筛选对应点对

2.根据中值筛选对应点对

3.一对一删除重复点对

4.根据法线一致性筛选对应点对

5.根据ICP重叠率估计筛选对应点对

6.完整代码


如何寻找对应点对

本文基于寻找到对应点对之后,对寻找到的对应点对

pcl::CorrespondencesPtr correspondences(new pcl::Correspondences)做二次筛选。

如果完全不会PCL,想直接拷贝使用,文末附有完整代码

用于下方各筛选方法测试的原始点对关系如下图。

1.根据距离筛选对应点对

1.1 原理

基于距离阈值来删除不符合指定距离条件的点云对应点对。

用户可以通过设置距离阈值来删除不符合距离阈值的点对,通常距离阈值是一个正数,表示两点之间的最大距离。如果两个点之间的距离超过了这个阈值,它们将被删除。

1.2 代码

(1)头文件

#include <pcl/registration/correspondence_rejection_distance.h>			// 根据距离筛选对应点对

(2)示例代码

// 基于距离筛选对应关系
	pcl::CorrespondencesPtr  correspondencesRejDis(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorDistance corrRejDis;
	corrRejDis.setInputCorrespondences(correspondences);					// 输入对应关系
	corrRejDis.setMaximumDistance(0.9);										// 对应关系之间的最大距离阈值
	corrRejDis.getCorrespondences(*correspondencesRejDis);						// 输出筛选后的对应关系

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "基于距离筛选后剩余点对数:" << correspondencesRejDis->size() << std::endl;

1.3 结果展示

2.根据中值筛选对应点对

2.1 原理

基于对应关系之间的中值距离阈值的点对对应关系的筛选。

如果一对对应点的距离大于中值的某个倍数(阈值),则该点对对应关系将被删除,通过排除这些异常对应关系,可以提高配准的精度,降低对配准结果的干扰。

2.2 代码

(1)头文件

#include <pcl/registration/correspondence_rejection_median_distance.h>			// 根据中值筛选对应点对

(2)示例代码

// 基于中值筛选对应关系
	pcl::CorrespondencesPtr  correspondencesRejMedianDistance(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorMedianDistance corrRejMedianDistance;
	corrRejMedianDistance.setMedianFactor(1);														// 中值阈值
	corrRejMedianDistance.setInputCorrespondences(correspondences);									// 输入对应关系
	corrRejMedianDistance.getCorrespondences(*correspondencesRejMedianDistance);					// 输出筛选后的对应关系

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "基于中值筛选后剩余点对数:" << correspondencesRejMedianDistance->size() << std::endl;

2.3 结果展示

3.一对一删除重复点对

3.1 原理

从现有点对中筛选出一对一的对应点关系,消除对应关系中重复匹配索引的对应点。

3.2 代码

(1)头文件

#include <pcl/registration/correspondence_rejection_one_to_one.h>			// 一对一删除重复点对

(2)示例代码

	// 一对一删除重复点对(用于去除重复对应点)
	pcl::CorrespondencesPtr  correspondencesRejOneToOne(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorOneToOne corrRejOneToOne;
	corrRejOneToOne.getRemainingCorrespondences(*correspondences, *correspondencesRejOneToOne);		// 一对一删除重复点对

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "一对一删除重复点对后剩余点对数:" << correspondencesRejOneToOne->size() << std::endl;

3.3 结果展示

4.根据法线一致性筛选对应点对

4.1 原理

利用点云中的法线信息(夹角)来排除不符合法线一致性的点云对应关系。

法线在点云中通常用于描述表面的方向,计算各对应点对之间的夹角,判断是否具有法线一致性,如果没有法线一致性,那么删除该对应点对

4.2 代码

(1)头文件

#include <pcl/registration/correspondence_rejection_surface_normal.h>			// 根据法线一致性筛选对应点对

(2)示例代码

本示例将计算法线封装成了一个方法,需注意。

// 计算法线
void computeNormal(pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud, pcl::PointCloud<pcl::PointNormal>::Ptr& normals)
{
	pcl::NormalEstimationOMP<pcl::PointXYZ, pcl::PointNormal> n;//OMP加速
	pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>());
	n.setNumberOfThreads(6);
	n.setInputCloud(cloud);
	n.setSearchMethod(tree);
	n.setKSearch(10);
	n.compute(*normals);
}

// 法向量夹角筛选重复点对
	pcl::CorrespondencesPtr  correspondencesRejNoraml(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorSurfaceNormal corrRejNormal;
	corrRejNormal.initializeDataContainer<pcl::PointNormal, pcl::PointNormal>();					// 初始化点类型和普通类型的数据容器对象

	pcl::PointCloud<pcl::PointNormal>::Ptr sourceNormals(new pcl::PointCloud<pcl::PointNormal>);
	computeNormal(source, sourceNormals);															// 计算源点云法线
	pcl::PointCloud<pcl::PointNormal>::Ptr targetNormals(new pcl::PointCloud<pcl::PointNormal>);
	computeNormal(target, targetNormals);															// 计算目标点云法线

	corrRejNormal.setInputSource<pcl::PointNormal>(sourceNormals);
	corrRejNormal.setInputTarget<pcl::PointNormal>(targetNormals);
	corrRejNormal.setInputNormals<pcl::PointNormal, pcl::PointNormal>(sourceNormals);
	corrRejNormal.setTargetNormals<pcl::PointNormal, pcl::PointNormal>(targetNormals);
	corrRejNormal.setInputCorrespondences(correspondences);

	double angle = 20;					// 夹角阈值
	corrRejNormal.setThreshold(cos(M_PI * angle / 180));					// 设置法线之间的夹角阈值,输入的是夹角余弦值
	corrRejNormal.getCorrespondences(*correspondencesRejNoraml);

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "法向量夹角筛选重复点对后剩余点对数:" << correspondencesRejNoraml->size() << std::endl;

4.3 结果展示

5.根据ICP重叠率估计筛选对应点对

5.1 原理

通过设置一个预估的两点云重叠率,暴力匹配(类似于ICP配准),得到符合重叠率的点云。

5.2 代码

(1)头文件

#include <pcl/registration/correspondence_rejection_trimmed.h>			// 根据ICP重叠率估计筛选对应点对

(2)示例代码

	// 根据重叠率估计筛选对应点对
	pcl::CorrespondencesPtr  correspondencesRejTrimmed(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorTrimmed corrRejTrimmed;
	corrRejTrimmed.setOverlapRatio(0.5);						// 设置两点云间的预估重叠率,范围为0-1
	corrRejTrimmed.getRemainingCorrespondences(*correspondences, *correspondencesRejTrimmed);		// 根据重叠率估计筛选对应点对

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "根据重叠率估计筛选对应点对后剩余点对数:" << correspondencesRejTrimmed->size() << std::endl;

5.3 结果展示

6.完整代码

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/features/normal_3d_omp.h>
#include <pcl/registration/correspondence_estimation.h>
#include <pcl/registration/correspondence_rejection_distance.h>			// 根据距离筛选对应点对
#include <pcl/registration/correspondence_rejection_median_distance.h>			// 根据中值筛选对应点对
#include <pcl/registration/correspondence_rejection_one_to_one.h>			// 一对一删除重复点对
#include <pcl/registration/correspondence_rejection_surface_normal.h>			// 根据法线一致性筛选对应点对
#include <pcl/registration/correspondence_rejection_trimmed.h>			// 根据ICP重叠率估计筛选对应点对
#include <boost/thread/thread.hpp>
#include <pcl/visualization/pcl_visualizer.h>

// 计算法线
void computeNormal(pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud, pcl::PointCloud<pcl::PointNormal>::Ptr& normals)
{
	pcl::NormalEstimationOMP<pcl::PointXYZ, pcl::PointNormal> n;//OMP加速
	pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>());
	n.setNumberOfThreads(6);
	n.setInputCloud(cloud);
	n.setSearchMethod(tree);
	n.setKSearch(10);
	n.compute(*normals);
}

int main()
{
	/****************寻找对应点对********************/
	pcl::PointCloud<pcl::PointXYZ>::Ptr source(new pcl::PointCloud<pcl::PointXYZ>);			// 源点云
	pcl::PointCloud<pcl::PointXYZ>::Ptr target(new pcl::PointCloud<pcl::PointXYZ>);			// 目标点云
	pcl::io::loadPCDFile("D:/code/csdn/data/B30.pcd", *source);
	pcl::io::loadPCDFile("D:/code/csdn/data/B31.pcd", *target);

	// 寻找对应点对
	pcl::registration::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ, pcl::Normal> registration;
	registration.setInputSource(source);
	registration.setInputTarget(target);									// 设置目标点云
	pcl::CorrespondencesPtr correspondences(new pcl::Correspondences);
	registration.determineCorrespondences(*correspondences, 5);				// 对应点结果和匹配点之间的最短距离

	// 基于距离筛选对应关系
	pcl::CorrespondencesPtr  correspondencesRejDis(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorDistance corrRejDis;
	corrRejDis.setInputCorrespondences(correspondences);					// 输入对应关系
	corrRejDis.setMaximumDistance(0.9);										// 对应关系之间的最大距离阈值
	corrRejDis.getCorrespondences(*correspondencesRejDis);						// 输出筛选后的对应关系

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "基于距离筛选后剩余点对数:" << correspondencesRejDis->size() << std::endl;

	// 基于中值筛选对应关系
	pcl::CorrespondencesPtr  correspondencesRejMedianDistance(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorMedianDistance corrRejMedianDistance;
	corrRejMedianDistance.setMedianFactor(1);														// 中值阈值
	corrRejMedianDistance.setInputCorrespondences(correspondences);									// 输入对应关系
	corrRejMedianDistance.getCorrespondences(*correspondencesRejMedianDistance);					// 输出筛选后的对应关系

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "基于中值筛选后剩余点对数:" << correspondencesRejMedianDistance->size() << std::endl;

	// 一对一删除重复点对(用于去除重复对应点)
	pcl::CorrespondencesPtr  correspondencesRejOneToOne(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorOneToOne corrRejOneToOne;
	corrRejOneToOne.getRemainingCorrespondences(*correspondences, *correspondencesRejOneToOne);		// 一对一删除重复点对

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "一对一删除重复点对后剩余点对数:" << correspondencesRejOneToOne->size() << std::endl;

	// 法向量夹角筛选重复点对
	pcl::CorrespondencesPtr  correspondencesRejNoraml(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorSurfaceNormal corrRejNormal;
	corrRejNormal.initializeDataContainer<pcl::PointNormal, pcl::PointNormal>();					// 初始化点类型和普通类型的数据容器对象

	pcl::PointCloud<pcl::PointNormal>::Ptr sourceNormals(new pcl::PointCloud<pcl::PointNormal>);
	computeNormal(source, sourceNormals);															// 计算源点云法线
	pcl::PointCloud<pcl::PointNormal>::Ptr targetNormals(new pcl::PointCloud<pcl::PointNormal>);
	computeNormal(target, targetNormals);															// 计算目标点云法线

	corrRejNormal.setInputSource<pcl::PointNormal>(sourceNormals);
	corrRejNormal.setInputTarget<pcl::PointNormal>(targetNormals);
	corrRejNormal.setInputNormals<pcl::PointNormal, pcl::PointNormal>(sourceNormals);
	corrRejNormal.setTargetNormals<pcl::PointNormal, pcl::PointNormal>(targetNormals);
	corrRejNormal.setInputCorrespondences(correspondences);

	double angle = 20;					// 夹角阈值
	corrRejNormal.setThreshold(cos(M_PI * angle / 180));					// 设置法线之间的夹角阈值,输入的是夹角余弦值
	corrRejNormal.getCorrespondences(*correspondencesRejNoraml);

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "法向量夹角筛选重复点对后剩余点对数:" << correspondencesRejNoraml->size() << std::endl;

	// 根据重叠率估计筛选对应点对
	pcl::CorrespondencesPtr  correspondencesRejTrimmed(new pcl::Correspondences);
	pcl::registration::CorrespondenceRejectorTrimmed corrRejTrimmed;
	corrRejTrimmed.setOverlapRatio(0.5);						// 设置两点云间的预估重叠率,范围为0-1
	corrRejTrimmed.getRemainingCorrespondences(*correspondences, *correspondencesRejTrimmed);		// 根据重叠率估计筛选对应点对

	std::cout << "对应点对数:" << correspondences->size() << std::endl;
	std::cout << "根据重叠率估计筛选对应点对后剩余点对数:" << correspondencesRejTrimmed->size() << std::endl;

	/****************展示********************/
	boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer(new pcl::visualization::PCLVisualizer("CorrespondenceEstimation"));
	viewer->addPointCloud<pcl::PointXYZ>(source, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(source, 0, 255, 0), "source");
	viewer->addPointCloud<pcl::PointXYZ>(target, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(target, 255, 0, 0), "target");
	viewer->addCorrespondences<pcl::PointXYZ>(source, target, *correspondences, "correspondence");

	boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer0(new pcl::visualization::PCLVisualizer("CorrespondenceRejectorDistance"));
	viewer0->addPointCloud<pcl::PointXYZ>(source, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(source, 0, 255, 0), "source");
	viewer0->addPointCloud<pcl::PointXYZ>(target, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(target, 255, 0, 0), "target");
	viewer0->addCorrespondences<pcl::PointXYZ>(source, target, *correspondencesRejDis, "correspondence");

	boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer1(new pcl::visualization::PCLVisualizer("correspondencesRejMedianDistance"));
	viewer1->addPointCloud<pcl::PointXYZ>(source, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(source, 0, 255, 0), "source");
	viewer1->addPointCloud<pcl::PointXYZ>(target, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(target, 255, 0, 0), "target");
	viewer1->addCorrespondences<pcl::PointXYZ>(source, target, *correspondencesRejMedianDistance, "correspondence");

	boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer2(new pcl::visualization::PCLVisualizer("correspondencesRejOneToOne"));
	viewer2->addPointCloud<pcl::PointXYZ>(source, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(source, 0, 255, 0), "source");
	viewer2->addPointCloud<pcl::PointXYZ>(target, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(target, 255, 0, 0), "target");
	viewer2->addCorrespondences<pcl::PointXYZ>(source, target, *correspondencesRejOneToOne, "correspondence");

	boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer3(new pcl::visualization::PCLVisualizer("correspondencesRejNoraml"));
	viewer3->addPointCloud<pcl::PointXYZ>(source, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(source, 0, 255, 0), "source");
	viewer3->addPointCloud<pcl::PointXYZ>(target, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(target, 255, 0, 0), "target");
	viewer3->addCorrespondences<pcl::PointXYZ>(source, target, *correspondencesRejNoraml, "correspondence");

	boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer4(new pcl::visualization::PCLVisualizer("correspondencesRejTrimmed"));
	viewer4->addPointCloud<pcl::PointXYZ>(source, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(source, 0, 255, 0), "source");
	viewer4->addPointCloud<pcl::PointXYZ>(target, pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(target, 255, 0, 0), "target");
	viewer4->addCorrespondences<pcl::PointXYZ>(source, target, *correspondencesRejTrimmed, "correspondence");

	while (!viewer->wasStopped() || !viewer0->wasStopped() || !viewer1->wasStopped() || !viewer2->wasStopped() || !viewer3->wasStopped() || !viewer4->wasStopped())
	{
		viewer->spinOnce(100);
		viewer0->spinOnce(100);
		viewer1->spinOnce(100);
		viewer2->spinOnce(100);
		viewer3->spinOnce(100);
		viewer4->spinOnce(100);
		boost::this_thread::sleep(boost::posix_time::microseconds(100000));
	}

	return 0;
}

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值