【PCL-6】PCL基于凹凸型的分割算法(LCCP)

平面分割与目标物提取参考【PCL-1】RANSAC平面分割_pcl平面分割_WXG1011的博客-CSDN博客

这篇博客主要记录LCCP算法,下面进入正题~~~

LCCP算法,又称基于凹凸型的分割,此算法适用于颜色类似、棱角分明的物体场景分割。LCCP方法不依赖点云颜色,只使用空间信息和法线信息。

算法流程:

1、基于超体聚类的过分割;

超体聚类首先规律的布置区域生长“晶核”,晶核在空间中是均匀分布的,并指定晶核距离(Rseed),再指定粒子距离(Rvoxel),最后指定最小晶粒(MOV)。

超体聚类不是进行目标点云分割的,而是将场景点云化成许多小块,并研究每个小块之间的关系。

Rseed确定超体素之间的距离,Rvoxel确定点云量化的分辨率,Rsearch用于确定是否有足够数量的种子占用体素。 

2、在超体聚类的基础上再聚类。

算法思路:

1、基于CC和SC判断凹凸性,CC是利用相邻两片中心连线向量与法向量的夹角来判断两片是凹还是凸,SC判别阈值与两体素的夹角。

 若α1>α2,则为凹,反之,则为凸。

2、在标记完各个小区域凹凸关系后,则采用区域增长算法将小区域聚类成较大物体。

3、滤除多余噪点,即可获得点云分割结果。

 示例代码:

//超体聚类+LCCP
//#include "stdafx.h"

#include <stdlib.h>  
#include <cmath>  
#include <limits.h>  
#include <boost/format.hpp>  
#include <fstream> 

#include<string>

#include <pcl/console/parse.h>  
#include <pcl/io/pcd_io.h>  
#include <pcl/visualization/pcl_visualizer.h>  
#include <pcl/visualization/point_cloud_color_handlers.h>  
#include <pcl/visualization/cloud_viewer.h>

#include <pcl/filters/passthrough.h>  
#include <pcl/segmentation/supervoxel_clustering.h>  
#include <pcl/segmentation/lccp_segmentation.h>  

#include <pcl/filters/statistical_outlier_removal.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl/filters/extract_indices.h>

#define Random(x) (rand() % x)
using namespace std;
typedef pcl::PointXYZRGBA PointT;
typedef pcl::LCCPSegmentation<PointT>::SupervoxelAdjacencyList SuperVoxelAdjacencyList;

int main(int argc, char ** argv)
{
	pcl::PCDWriter writer;
	//输入点云  
	pcl::PointCloud<PointT>::Ptr input_cloud_ptr(new pcl::PointCloud<PointT>);
	pcl::PCLPointCloud2 input_pointcloud2;
	if (pcl::io::loadPCDFile("..\\testdata\\test-Cloud.pcd", input_pointcloud2))
	{
		PCL_ERROR("ERROR: Could not read input point cloud ");
		return (3);
	}
	pcl::fromPCLPointCloud2(input_pointcloud2, *input_cloud_ptr);
	PCL_INFO("Done making cloud\n");

	//----------------------------------------统计滤波----------------------------
	// 创建统计学离群点移除过滤器
	pcl::PointCloud<PointT>::Ptr cloud_filtered(new pcl::PointCloud<PointT>);
	pcl::StatisticalOutlierRemoval<PointT> sor;
	sor.setInputCloud(input_cloud_ptr);
	// 设置过滤邻域K
	sor.setMeanK(50);
	// 设置标准差的系数, 值越大,丢掉的点越少
	sor.setStddevMulThresh(1.0f);
	sor.filter(*cloud_filtered);
	pcl::io::savePCDFileASCII("..\\testdata\\statistical.pcd", *cloud_filtered);

	//-----------------------------------平面拟合----------------------------------
	pcl::NormalEstimation<PointT, pcl::Normal> ne;
	pcl::ExtractIndices<PointT> extract;
	pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>());
	pcl::PointCloud<pcl::Normal>::Ptr cloud_normals(new pcl::PointCloud<pcl::Normal>);
	pcl::SACSegmentationFromNormals<PointT, pcl::Normal> seg;
	pcl::PointIndices::Ptr inliers_plane(new pcl::PointIndices), inliers_cylinder(new pcl::PointIndices);
	pcl::ModelCoefficients::Ptr coefficients_plane(new pcl::ModelCoefficients), coefficients_cylinder(new pcl::ModelCoefficients);

	// Estimate point normals
	ne.setSearchMethod(tree);
	ne.setInputCloud(cloud_filtered);
	ne.setKSearch(50);
	ne.compute(*cloud_normals);
	// Create the segmentation object for the planar model and set all the parameters
	seg.setOptimizeCoefficients(true);
	seg.setModelType(pcl::SACMODEL_NORMAL_PLANE);
	seg.setNormalDistanceWeight(0.1);
	seg.setMethodType(pcl::SAC_RANSAC);
	seg.setMaxIterations(100);
	seg.setDistanceThreshold(12.0);
	seg.setInputCloud(cloud_filtered);
	seg.setInputNormals(cloud_normals);
	// Obtain the plane inliers and coefficients
	seg.segment(*inliers_plane, *coefficients_plane);
	std::cerr << "Plane coefficients: " << *coefficients_plane << std::endl;

	// Extract the planar inliers from the input cloud
	extract.setInputCloud(cloud_filtered);
	extract.setIndices(inliers_plane);
	extract.setNegative(false);

	// Write the planar inliers to disk
	pcl::PointCloud<PointT>::Ptr cloud_plane(new pcl::PointCloud<PointT>());
	extract.filter(*cloud_plane);
	std::cerr << "plane: " << cloud_plane->size() << " data points." << std::endl;
	writer.write("..\\testdata\\plane.pcd", *cloud_plane, false);

	//-----------------------------------目标物提取-----------------------------------
	pcl::PointCloud<PointT>::Ptr cloud_filtered2(new pcl::PointCloud<PointT>);
	pcl::ExtractIndices<pcl::Normal> extract_normals;
	pcl::PointCloud<pcl::Normal>::Ptr cloud_normals2(new pcl::PointCloud<pcl::Normal>);
	extract.setNegative(true);
	extract.filter(*cloud_filtered2);
	extract_normals.setNegative(true);
	extract_normals.setInputCloud(cloud_normals);
	extract_normals.setIndices(inliers_plane);
	extract_normals.filter(*cloud_normals2);
	std::cerr << "cylinder: " << cloud_filtered2->size() << " data points." << std::endl;
	writer.write("..\\testdata\\cylinder.pcd", *cloud_filtered2, false);

	//---------------------------------------超体聚类----------------------------------------
	//粒子距离,体素大小,空间八叉树的分辨率,即点云下采样的分辨率
	float voxel_resolution = 2.0f;
	//晶核距离,种子的分辨率,一般可设置为体素分辨率的50倍以上
	float seed_resolution = 100.0f;
	//颜色容差,针对分割场景,如果分割场景中各个物体之间的颜色特征差异明显,可设置较大
	float color_importance = 0.1f;
	//设置较大且其他影响较小时,基本按照空间分辨率来决定体素分割
	float spatial_importance = 1.0f;
	//针对分割场景,如果分割场景中各个物体连通处的法线特征差异明显,可设置较大,
	//但在实际使用中,需要针对数据的结构适当考虑,发现估计的准确性等因素
	float normal_importance = 4.0f;
	bool use_single_cam_transform = false;
	bool use_supervoxel_refinement = false;

	unsigned int k_factor = 0;

	//进行超体素分割,voxel_resolution 点云体素分辨率;seed_resolution网格分辨率
	pcl::SupervoxelClustering<PointT> super(voxel_resolution, seed_resolution);
    //setUseSingleCameraTransform,用于有序点云,即通过结构光相机等设备产生的点云,如果设置        
    //为true,则会对点云进行如下变换:x /= z; y /= z; z = ln(z),点云会按照z的大小进行压缩,激 
    //光雷达等产生的无需点云默认设置false
	super.setUseSingleCameraTransform(use_single_cam_transform);
	super.setInputCloud(cloud_filtered2);
	//设置颜色在聚类时所占的权重
	super.setColorImportance(color_importance);
	//设置超体素空间距离
	super.setSpatialImportance(spatial_importance);
	//设置法向量在聚类时所占的权重
	super.setNormalImportance(normal_importance);
	std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr> supervoxel_clusters;

	PCL_INFO("Extracting supervoxels\n");
	super.extract(supervoxel_clusters);

	PCL_INFO("Getting supervoxel adjacency\n");
	std::multimap<uint32_t, uint32_t> supervoxel_adjacency;
	super.getSupervoxelAdjacency(supervoxel_adjacency);
	pcl::PointCloud<pcl::PointNormal>::Ptr sv_centroid_normal_cloud = pcl::SupervoxelClustering<PointT>::makeSupervoxelNormalCloud(supervoxel_clusters);

	//---------------------------------LCCP分割-----------------------------------
	//生成LCCP分割器
	pcl::LCCPSegmentation<PointT> lccp;
	float concavity_tolerance_threshold = 20;
	float smoothness_threshold = 0.2;
	uint32_t min_segment_size = 0;
	bool use_extended_convexity = false;
	bool use_sanity_criterion = false;
	PCL_INFO("Starting Segmentation\n");
	
	//设置CC判断的依据,CC校验的beta值
	lccp.setConcavityToleranceThreshold(concavity_tolerance_threshold);
	//设置是否使用阶梯检测,这个条件会检测两个超体素之间是否是一个step。
	//如果两个超体素之间的面到面距离>expected_distance + smoothness_threshold_*voxel_resolution_则这个两个超体素被判定为unsmooth并被标记为凹。
	lccp.setSmoothnessCheck(true, voxel_resolution, seed_resolution, smoothness_threshold);
	//CC校验的K邻点,设置CC判断中公共距离被判定为凸的个数
	lccp.setKFactor(k_factor);
	//输入超体聚类结果
	lccp.setInputSupervoxels(supervoxel_clusters, supervoxel_adjacency);
	//最小分割尺寸
	lccp.setMinSegmentSize(min_segment_size);
	lccp.segment();

	PCL_INFO("Interpolation voxel cloud -> input cloud and relabeling\n");
	//super.getLabeledCloud()
	pcl::PointCloud<pcl::PointXYZL>::Ptr sv_labeled_cloud = super.getLabeledCloud();
	pcl::PointCloud<pcl::PointXYZL>::Ptr lccp_labeled_cloud = sv_labeled_cloud->makeShared();
	lccp.relabelCloud(*lccp_labeled_cloud);
	SuperVoxelAdjacencyList sv_adjacency_list;
	lccp.getSVAdjacencyList(sv_adjacency_list);
	writer.write("..\\testdata\\pccl.pcd", *lccp_labeled_cloud, false);
	
	
	//-------------------------------------获取最大label值--------------------------------
	int label_max = 0;
	for (int i = 0; i < lccp_labeled_cloud->size(); i++) {
		if (lccp_labeled_cloud->points[i].label > label_max)
		{
			label_max = lccp_labeled_cloud->points[i].label;

		}
	}

	// ----------------------------根据label值提取点云--------------------------------
	for (int j = 0; j <= label_max; j++)
	{
		int num = 0;
		pcl::PointCloud<pcl::PointXYZL>::Ptr ColoredCloud2(new pcl::PointCloud<pcl::PointXYZL>);
		ColoredCloud2->height = 1;
		ColoredCloud2->width = lccp_labeled_cloud->size();
		ColoredCloud2->resize(lccp_labeled_cloud->size());
		for (int p = 0; p < lccp_labeled_cloud->size(); p++) {
			if (lccp_labeled_cloud->points[p].label == j) {
				ColoredCloud2->points[p].x = lccp_labeled_cloud->points[p].x;
				ColoredCloud2->points[p].y = lccp_labeled_cloud->points[p].y;
				ColoredCloud2->points[p].z = lccp_labeled_cloud->points[p].z;
				ColoredCloud2->points[p].label = lccp_labeled_cloud->points[p].label;
				num++;
			}
		}
		//为了过滤掉一些数量较少的点
		if (num > 100)
		{
			pcl::io::savePCDFileASCII("..\\testdata\\" + to_string(j) + ".pcd", *ColoredCloud2);
		}
	}

	// ----------------------------点云可视化--------------------------------
	//pcl::visualization::PCLVisualizer viewer = pcl::visualization::PCLVisualizer("3D Viewer", false);
	//viewer.addPointCloud(lccp_labeled_cloud, "Segmented point cloud");
	
	return 0;
}

参考链接  官方文档

PCL中的点云分割详解(1) - 知乎 

  • 1
    点赞
  • 7
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值