一、引言
在降采样中想要充分保留边界信息,但是采用体素降采样,均匀降采样等,都是对全局的点云信息进行降采样,无法做到分区域的降采样。因此对点云的曲率
进行估计,作为额外的补充信息对点云进行降采样。即对点云做条件滤波。曲率信息作为滤波条件。
运行环境:Ubuntu18.04
+ PCL1.11
二、实现
主要步骤如下:
- 估计点云的法向量和曲率
- 对点云法向量和曲率进行字段连接
- 根据曲率大小进行分区域降采样
2.1估计点云的法向量和曲率
利用PCL库对点云的法向量和曲率进行估计。要注意根据实际的情况设置合适的点云邻域半径
。
1 2 3 4 5 6 7 8 9 10
| pcl::NormalEstimationOMP<pcl::PointXYZ,pcl::Normal>n; pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>); pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>); tree->setInputCloud(cloud); n.setViewPoint(10,10,10); n.setInputCloud(cloud); n.setNumberOfThreads(4); n.setSearchMethod(tree); n.setRadiusSearch(1); n.compute(*normals);
|
2.2字段连接
利用concatenateFields
将点云的法向量与曲率信息连接。
1 2
| pcl::PointCloud<pcl::PointNormal>::Ptr cnormals(new pcl::PointCloud<pcl::PointNormal>); pcl::concatenateFields(*cloud,*normals,*cnormals);
|
2.3分区域滤波
设置合理的曲率阈值cur_threshold
,遍历点云,将点云放入不同的点云集合clouddownsample_1
和clouddownsample_2
,分别设置不同的降采样尺度。
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26
| pcl::PointCloud<pcl::PointXYZ>::Ptr clouddownsample_1(new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr clouddownsample_2(new pcl::PointCloud<pcl::PointXYZ>); for (size_t i = 0; i < cnormals->points.size(); i++){ if (cnormals->at(i).curvature > cur_threshold){ clouddownsample_1->points.emplace_back(cloud->points[i]); }else{ clouddownsample_2->points.emplace_back(cloud->points[i]); } }
clouddownsample_1->width = clouddownsample_1->points.size(); clouddownsample_1->height = 1; clouddownsample_1->is_dense = true; clouddownsample_2->width = clouddownsample_2->points.size(); clouddownsample_2->height = 1; clouddownsample_2->is_dense = true;
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_add(new pcl::PointCloud<pcl::PointXYZ>); float leftSize = 0.25f; pcl::VoxelGrid<pcl::PointXYZ> down; down.setInputCloud (clouddownsample_2); down.setLeafSize (leftSize, leftSize, leftSize); down.filter (*clouddownsample_2);
*cloud_add = *clouddownsample_1 + *clouddownsample_2;
|
三、结果
3.1原始图像
3.2曲率估计图像
曲率高的地方为边界。
3.3降采样图像
边界信息较好的保留了下来
3.4不足
整体对曲率估计时的邻域半径设置
比较敏感,若设置过小,极易受到噪声点的干扰,如下图的曲率估计。