PCL_第12章_分割【2】

上面是上图像处理课程大湘老师PPT中的一个图,其实,我觉得点云中的很多技术都是从较为成熟的图像处理中借鉴过来的。就譬如之前关键点检测用到的Hough变换,以及上一篇分割笔记中有关区域生长的分割,还有这篇的最小割分割。

https://github.com/PointCloudLibrary/data  pcl点云数据下载。


六、最小割分割算法_min cut segmentation

参考:https://www.cnblogs.com/ironstark/p/5008258.html

最小割(min-cut)并不是一个什么很新鲜的东西。它早就用在网络规划,求解桥问题,图像分割等领域,被移植到点云分割上也不足为奇。最小割算法是图论中的一个概念,其作用是以某种方式,将两个点分开,当然这两个点中间可能是通过无数的点再相连的。

如果要分开最左边的点和最右边的点,红绿两种割法都是可行的,但是红线跨过了三条线,绿线只跨过了两条。单从跨线数量上来论可以得出绿线这种切割方法更优的结论。但假设线上有不同的权值,那么最优切割则和权值有关了。它到底是怎么找到那条绿线的暂且不论。总而言之,就是有那么一个算法,当你给出了点之间的 “图” (广义的),以及连线的权值时,最小割算法就能按照你的要求把图分开。

点云的“图”:

显而易见,切割有两个非常重要的因素,第一个是获得点与点之间的拓扑关系,也就是生成一张“图”。第二个是给图中的连线赋予合适的权值。只要这两个要素合适,最小割算法就会办好剩下的事情。点云是一种非常适合分割的对象,点云有天然分开的点。有了点之后,只要把点云中所有的点连起来就可以了。连接算法如下:

  1. 找到每个点最近的n个点
  2. 将这n个点和父点连接
  3. 找到距离最小的两个块(A块中某点与B块中某点距离最小),并连接
  4. 重复3,直至只剩一个块

现在已经有了“图”,只要给图附上合适的权值,就完成了所有任务。物体分割给人一个直观印象就是属于该物体的点,应该相互之间不会太远。也就是说,可以用点与点之间的欧式距离来构造权值。所有线的权值可映射为线长的函数。

**************************************************

pcl最小割算法:pcl::MinCutSegmentation,需要手动来设置center 等。

代码:

#include <iostream>
#include <vector>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/filters/passthrough.h>
#include <pcl/segmentation/min_cut_segmentation.h>
#include <pcl/console/print.h>
#include <pcl/console/parse.h>
#include <pcl/console/time.h>

using namespace pcl::console;
int main (int argc, char** argv)
{
	if(argc<2)
	{
		std::cout<<".exe xx.pcd -bc 1 -fc 1.0 -nc 0 -cx 68.97 -cy -18.55 -cz 0.57 -s 0.25 -r 3.0433856 -non 14 -sw 0.5"<<endl;

		return 0;
	}//如果输入参数小于1个,输出提示信息
	time_t start,end,diff[5],option;
	start = time(0); 
	int NumberOfNeighbours=8;//设置默认参数
	bool Bool_Cuting=false;//设置默认参数
	float far_cuting=1,near_cuting=0,C_x=0.071753,C_y= -0.309913,C_z=1.603000,Sigma=0.25,Radius=0.8,SourceWeight=0.5;//设置默认输入参数
	
	pcl::PointCloud <pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud <pcl::PointXYZ>);// 创建一个PointCloud <pcl::PointXYZRGB>共享指针并进行实例化
	if ( pcl::io::loadPCDFile <pcl::PointXYZ> (argv[1], *cloud) == -1 )// 加载点云数据
	{
		std::cout << "Cloud reading failed." << std::endl;
		return (-1);
	}

	parse_argument (argc, argv, "-bc", Bool_Cuting);
	parse_argument (argc, argv, "-fc", far_cuting);
	parse_argument (argc, argv, "-nc", near_cuting);

	parse_argument (argc, argv, "-cx", C_x);
	parse_argument (argc, argv, "-cy", C_y);
	parse_argument (argc, argv, "-cz", C_z);

	parse_argument (argc, argv, "-s", Sigma);
	parse_argument (argc, argv, "-r", Radius);
	parse_argument (argc, argv, "-non", NumberOfNeighbours);
	parse_argument (argc, argv, "-sw", SourceWeight);//设置输入参数方式

	pcl::IndicesPtr indices (new std::vector <int>);//创建一组索引
	if(Bool_Cuting)//判断是否需要直通滤波
	{
		pcl::PassThrough<pcl::PointXYZ> pass;//设置直通滤波器对象
		pass.setInputCloud (cloud);//设置输入点云
		pass.setFilterFieldName ("z");//设置指定过滤的维度
		pass.setFilterLimits (near_cuting, far_cuting);//设置指定纬度过滤的范围
		pass.filter (*indices);//执行滤波,保存滤波结果在上述索引中

	}
	pcl::MinCutSegmentation<pcl::PointXYZ> seg;//创建一个PointXYZRGB类型的区域生长分割对象
	seg.setInputCloud (cloud);//设置输入点云
	if(Bool_Cuting)seg.setIndices (indices);//设置输入点云的索引

	pcl::PointCloud<pcl::PointXYZ>::Ptr foreground_points(new pcl::PointCloud<pcl::PointXYZ> ());//创建一个PointCloud <pcl::PointXYZRGB>共享指针并进行实例化
	pcl::PointXYZ point;//定义中心点并赋值

	point.x =C_x;
	point.y = C_y;
	point.z = C_z;
	foreground_points->points.push_back(point);
	seg.setForegroundPoints (foreground_points);//输入前景点云(目标物体)的中心点

	seg.setSigma (Sigma);//设置平滑成本的Sigma值
	seg.setRadius (Radius);//设置背景惩罚权重的半径
	seg.setNumberOfNeighbours (NumberOfNeighbours);//设置临近点数目
	seg.setSourceWeight (SourceWeight);//设置前景惩罚权重

	std::vector <pcl::PointIndices> clusters;
	seg.extract (clusters);//获取分割的结果,分割结果保存在点云索引的向量中。

	std::cout << "Maximum flow is " << seg.getMaxFlow () << std::endl;//计算并输出分割期间所计算出的流值

	pcl::PointCloud <pcl::PointXYZRGB>::Ptr colored_cloud = seg.getColoredCloud ();//对前景点赋予红色,对背景点赋予白色。
	pcl::visualization::PCLVisualizer viewer ("点云库PCL学习教程第二版-最小割分割方法");
	viewer.addPointCloud(colored_cloud);
	viewer.addSphere(point,Radius,122,122,0,"sphere");
	viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY,0.2,"sphere");
	
	while (!viewer.wasStopped ())
	{
		viewer.spin();
	}//进行可视化

	return (0);
}

实验结果:

原始点云:

分割后点云(需要在命令行改参数):

-non 5

-sw 1.2

-non 5 -sw 0.8

最小割算法更注重分割的精确性而不是分割自动进行。最小割算法用于半自动分割识别有着巨大的优势,适合用于计算机视觉,城市场景点云分析一类。但对机器人来说,或许和特征点检测算法联合起来能获得较好的效果。

图中显示,最小割算法成功找到了靠的很近的汽车。显然欧式算法r取太大则无法区分左右汽车,r取太小则无法区分车头和车身(玻璃不反光,是没有点云的)。


七、DON(Difference of Normals) segmentation

参考:https://blog.csdn.net/zfjBIT/article/details/95188107

类 pcl::DifferenceOfNormalsEstimation提供了一种根据不同尺度下法向量特征的差异性的点云分割方法

DoN特征源于观察到基于所给半径估计的表面法向量可以反映曲面的内在几何特征 ,因此这种分割算法是基于法线估计的,需要计算点云中某一点的法线估计。而通常在计算法线估计的时候都会用到邻域信息,很明显邻域大小的选取会影响法线估计的结果。而在DoN算法中,邻域选择的大小就被称为support radius(支持半径)。对点云中某一点选取不同的支持半径,即可以得到不同的法线估计,而法线之间的差异,就是是所说的法线差异(Difference of Normals)。

流程说明:

1. 计算大小支撑半径;

2. 最对大小支撑半径进行点云法线估计;

3. 计算DoN特征向量;

4. 对曲率特征,进行条件滤波;

5. 基于欧式距离进行分割;


/**

 * @file don_segmentation.cpp

 * Difference of Normals Example for PCL Segmentation Tutorials.

 *

 * @author Yani Ioannou

 * @date 2012-09-24

 * @修改 2015-6-16

 */

#include <string>

 

#include <pcl/point_types.h>

#include <pcl/io/pcd_io.h>

#include <pcl/search/organized.h>

#include <pcl/search/kdtree.h>

#include <pcl/features/normal_3d_omp.h>

#include <pcl/filters/conditional_removal.h>

#include <pcl/segmentation/extract_clusters.h>

#include <pcl/segmentation/impl/extract_clusters.hpp>

 

#include <pcl/features/don.h>

// for visualization

#include <pcl/visualization/pcl_visualizer.h>

 

using namespace pcl;

using namespace std;

 

 

pcl::PointCloud<pcl::PointXYZRGB>::Ptr getColoredCloud (pcl::PointCloud<pcl::PointXYZ>::Ptr input_, std::vector <pcl::PointIndices> clusters_,float r,float g,float b)

{

  pcl::PointCloud<pcl::PointXYZRGB>::Ptr colored_cloud;

 

  if (!clusters_.empty ())

  {

    colored_cloud = (new pcl::PointCloud<pcl::PointXYZRGB>)->makeShared ();

 

    srand (static_cast<unsigned int> (time (0)));

    std::vector<unsigned char> colors;

    for (size_t i_segment = 0; i_segment < clusters_.size (); i_segment++)

    {

      colors.push_back (static_cast<unsigned char> (rand () % 256));

      colors.push_back (static_cast<unsigned char> (rand () % 256));

      colors.push_back (static_cast<unsigned char> (rand () % 256));

    }

 

    colored_cloud->width = input_->width;

    colored_cloud->height = input_->height;

    colored_cloud->is_dense = input_->is_dense;

    for (size_t i_point = 0; i_point < input_->points.size (); i_point++)

    {

      pcl::PointXYZRGB point;

      point.x = *(input_->points[i_point].data);

      point.y = *(input_->points[i_point].data + 1);

      point.z = *(input_->points[i_point].data + 2);

      point.r = r;

      point.g = g;

      point.b = b;

      colored_cloud->points.push_back (point);

    }

 

    std::vector< pcl::PointIndices >::iterator i_segment;

    int next_color = 0;

    for (i_segment = clusters_.begin (); i_segment != clusters_.end (); i_segment++)

    {

      std::vector<int>::iterator i_point;

      for (i_point = i_segment->indices.begin (); i_point != i_segment->indices.end (); i_point++)

      {

        int index;

        index = *i_point;

        colored_cloud->points[index].r = colors[3 * next_color];

        colored_cloud->points[index].g = colors[3 * next_color + 1];

        colored_cloud->points[index].b = colors[3 * next_color + 2];

      }

      next_color++;

    }

  }

 

  return (colored_cloud);

}

 

int

main(int argc, char *argv[])

{

	int VISUAL = 1, SAVE = 0;//0 indicate shows nothing, 1 indicate shows very step output 2 only shows the final results

  ///The smallest scale to use in the DoN filter.

	double scale1, mean_radius;

 

	///The largest scale to use in the DoN filter.

	double scale2;

 

	///The minimum DoN magnitude to threshold by

	double threshold;

 

	///segment scene into clusters with given distance tolerance using euclidean clustering

	double segradius;

 

	if (argc < 6)

	{

		cerr << "usage: " << argv[0] << " inputfile smallscale(5) largescale(10) threshold(0.1) segradius(1.5) VISUAL(1) SAVE(0)" << endl;

		cerr << "usage: " << "smallscale largescale  segradius :multiple with mean radius of point cloud " << endl;

		exit(EXIT_FAILURE);

	}

 

	/// the file to read from.

	string infile = argv[1];

	/// small scale

	istringstream(argv[2]) >> scale1;      

	/// large scale

	istringstream(argv[3]) >> scale2;

	istringstream(argv[4]) >> threshold;   // threshold for DoN magnitude

	istringstream(argv[5]) >> segradius;   // threshold for radius segmentation

	istringstream(argv[6]) >> VISUAL;

	istringstream(argv[7]) >> SAVE;

	// Load cloud in blob format

	pcl::PointCloud<PointXYZRGB>::Ptr cloud(new pcl::PointCloud<PointXYZRGB>);

	pcl::io::loadPCDFile(infile.c_str(), *cloud);

	// Create a search tree, use KDTreee for non-organized data.

	pcl::search::Search<PointXYZRGB>::Ptr tree;

	if (cloud->isOrganized())

	{

		tree.reset(new pcl::search::OrganizedNeighbor<PointXYZRGB>());

	}

	else

	{

		tree.reset(new pcl::search::KdTree<PointXYZRGB>(false));

	}

 

	// Set the input pointcloud for the search tree

	tree->setInputCloud(cloud);

	//caculate the mean radius of cloud and mutilply with corresponding input

	{

		int size_cloud = cloud->size();

		int step = size_cloud / 10;

		double total_distance = 0;

		int i, j = 1;

		for (i = 0; i < size_cloud; i += step, j++)

		{

			std::vector<int> pointIdxNKNSearch(2);

			std::vector<float> pointNKNSquaredDistance(2);

			tree->nearestKSearch(cloud->points[i], 2, pointIdxNKNSearch, pointNKNSquaredDistance);

			total_distance += pointNKNSquaredDistance[1] + pointNKNSquaredDistance[0];

		}

		mean_radius = sqrt((total_distance / j));

		cout << "mean radius of cloud is: " << mean_radius << endl;

		scale1 *= mean_radius;   //大尺度支撑半径

		scale2 *= mean_radius;   //小尺度支撑半径

		segradius *= mean_radius;//欧式距离聚类时近邻搜索时的搜索半径

	}

 

 

	if (scale1 >= scale2)

	{

		cerr << "Error: Large scale must be > small scale!" << endl;

		exit(EXIT_FAILURE);

	}

 

	// Compute normals using both small and large scales at each point

	//pcl::NormalEstimationOMP<PointXYZRGB, PointNormal> ne;

	pcl::NormalEstimation<PointXYZRGB, PointNormal> ne;

	ne.setInputCloud(cloud);

	ne.setSearchMethod(tree);

 

	/**

	 * NOTE: setting viewpoint is very important, so that we can ensure

	 * normals are all pointed in the same direction!

	 */

	ne.setViewPoint(std::numeric_limits<float>::max(), std::numeric_limits<float>::max(), std::numeric_limits<float>::max());

 

	// calculate normals with the small scale

	cout << "Calculating normals for scale..." << scale1 << endl;

	pcl::PointCloud<PointNormal>::Ptr normals_small_scale(new pcl::PointCloud<PointNormal>);

 

	ne.setRadiusSearch(scale1);

	ne.compute(*normals_small_scale);

 

	// calculate normals with the large scale

	cout << "Calculating normals for scale..." << scale2 << endl;

	pcl::PointCloud<PointNormal>::Ptr normals_large_scale(new pcl::PointCloud<PointNormal>);

 

	ne.setRadiusSearch(scale2);

	ne.compute(*normals_large_scale);

	//visualize the normals

	if (VISUAL = 1)

	{

		cout << "click q key to quit the visualizer and continue!!" << endl;

		boost::shared_ptr<pcl::visualization::PCLVisualizer> MView(new pcl::visualization::PCLVisualizer("Showing normals with different scale"));

		pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZRGB> green(cloud, 0, 255, 0);

		int v1(0), v2(0);

		MView->createViewPort(0.0, 0.0, 0.5, 1.0, v1);

		MView->createViewPort(0.5, 0.0, 1.0, 1.0, v2);

		MView->setBackgroundColor(1, 1, 1);

		MView->addPointCloud(cloud, green, "small_scale", v1);

		MView->addPointCloud(cloud, green, "large_scale", v2);

		MView->addPointCloudNormals<pcl::PointXYZRGB, pcl::PointNormal>(cloud, normals_small_scale, 100, mean_radius * 10, "small_scale_normal");

		MView->addPointCloudNormals<pcl::PointXYZRGB, pcl::PointNormal>(cloud, normals_large_scale, 100, mean_radius * 10, "large_scale_normal");

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "small_scale", v1);

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, 0.5, "small_scale", v1);

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "large_scale", v1);

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, 0.5, "large_scale", v1);

		MView->spin();

 

	}

	// Create output cloud for DoN results

	PointCloud<PointNormal>::Ptr doncloud(new pcl::PointCloud<PointNormal>);

	copyPointCloud<PointXYZRGB, PointNormal>(*cloud, *doncloud);

 

	cout << "Calculating DoN... " << endl;

	// Create DoN operator

	pcl::DifferenceOfNormalsEstimation<PointXYZRGB, PointNormal, PointNormal> don;

	don.setInputCloud(cloud);

	don.setNormalScaleLarge(normals_large_scale);

	don.setNormalScaleSmall(normals_small_scale);

 

	if (!don.initCompute())

	{

		std::cerr << "Error: Could not intialize DoN feature operator" << std::endl;

		exit(EXIT_FAILURE);

	}

 

	// Compute DoN

	don.computeFeature(*doncloud);

 

 

	//print some differencense of curvature

	{

		cout << "You may have some sense about the input threshold(curvature) next time for your data" << endl;

		int size_cloud = doncloud->size();

		int step = size_cloud / 10;

		for (int i = 0; i < size_cloud; i += step)cout << " " << doncloud->points[i].curvature << " " << endl;

 

	}

 

	//show the differences of curvature with both large and small scale 

	if (VISUAL = 1)

	{

		cout << "click q key to quit the visualizer and continue!!" << endl;

		boost::shared_ptr<pcl::visualization::PCLVisualizer> MView(new pcl::visualization::PCLVisualizer("Showing the difference of curvature of two scale"));

		pcl::visualization::PointCloudColorHandlerGenericField<pcl::PointNormal> handler_k(doncloud, "curvature");

		MView->setBackgroundColor(1, 1, 1);

		MView->addPointCloud(doncloud, handler_k);

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3);

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, 0.5);

		MView->spin();

	}

 

 

	// Save DoN features

	pcl::PCDWriter writer;

	if (SAVE == 1) writer.write<pcl::PointNormal>("don.pcd", *doncloud, false);

 

 

	// Filter by magnitude

	cout << "Filtering out DoN mag <= " << threshold << "..." << endl;

 

	//创建条件滤波函数

	pcl::ConditionOr<PointNormal>::Ptr range_cond(

		new pcl::ConditionOr<PointNormal>()

	);//确定点是否属于满足设定的条件

 

	range_cond->addComparison(pcl::FieldComparison<PointNormal>::ConstPtr(

		new pcl::FieldComparison<PointNormal>("curvature", pcl::ComparisonOps::GT, threshold))

	);//添加比较条件

 

	pcl::ConditionalRemoval<PointNormal> condrem(range_cond);//建立条件滤波器

	condrem.setInputCloud(doncloud);//设置输入点云

 

	pcl::PointCloud<PointNormal>::Ptr doncloud_filtered(new pcl::PointCloud<PointNormal>);

 

	// Apply filter

	condrem.filter(*doncloud_filtered);

 

	doncloud = doncloud_filtered;

 

	// Save filtered output

	std::cout << "Filtered Pointcloud: " << doncloud->points.size() << " data points." << std::endl;

 

	if (SAVE == 1)writer.write<pcl::PointNormal>("don_filtered.pcd", *doncloud, false);

 

 

	//show the results of keeping relative small curvature points 

	if (VISUAL == 1)

	{

		cout << "click q key to quit the visualizer and continue!!" << endl;

		boost::shared_ptr<pcl::visualization::PCLVisualizer> MView(new pcl::visualization::PCLVisualizer("Showing the results of keeping relative small curvature points"));

		pcl::visualization::PointCloudColorHandlerGenericField<pcl::PointNormal> handler_k(doncloud, "curvature");

		MView->setBackgroundColor(1, 1, 1);

		MView->addPointCloud(doncloud, handler_k);

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3);

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, 0.5);

		MView->spin();

	}

 

	// Filter by magnitude

	cout << "Clustering using EuclideanClusterExtraction with tolerance <= " << segradius << "..." << endl;

 

	pcl::search::KdTree<PointNormal>::Ptr segtree(new pcl::search::KdTree<PointNormal>);

	segtree->setInputCloud(doncloud);

 

	std::vector<pcl::PointIndices> cluster_indices;

	pcl::EuclideanClusterExtraction<PointNormal> ec;

 

	ec.setClusterTolerance(segradius);

	ec.setMinClusterSize(50);

	ec.setMaxClusterSize(100000);

	ec.setSearchMethod(segtree);

	ec.setInputCloud(doncloud);

	ec.extract(cluster_indices);

	if (VISUAL == 1)

	{//visualize the clustering results

		pcl::PointCloud <pcl::PointXYZ>::Ptr tmp_xyz(new pcl::PointCloud<pcl::PointXYZ>);

		copyPointCloud<pcl::PointNormal, pcl::PointXYZ>(*doncloud, *tmp_xyz);

		pcl::PointCloud <pcl::PointXYZRGB>::Ptr colored_cloud = getColoredCloud(tmp_xyz, cluster_indices, 0, 255, 0);

 

		cout << "click q key to quit the visualizer and continue!!" << endl;

		boost::shared_ptr<pcl::visualization::PCLVisualizer> MView(new pcl::visualization::PCLVisualizer("visualize the clustering results"));

		pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgbps(colored_cloud);

		MView->setBackgroundColor(1, 1, 1);

		MView->addPointCloud(colored_cloud, rgbps);

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3);

		MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, 0.5);

		MView->spin();

 

	}

	if (SAVE == 1)

	{

		int j = 0;

		for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin(); it != cluster_indices.end(); ++it, j++)

		{

			pcl::PointCloud<PointNormal>::Ptr cloud_cluster_don(new pcl::PointCloud<PointNormal>);

			for (std::vector<int>::const_iterator pit = it->indices.begin(); pit != it->indices.end(); ++pit)

			{

				cloud_cluster_don->points.push_back(doncloud->points[*pit]);

			}

 

			cloud_cluster_don->width = int(cloud_cluster_don->points.size());

			cloud_cluster_don->height = 1;

			cloud_cluster_don->is_dense = true;

 

			//Save cluster

			cout << "PointCloud representing the Cluster: " << cloud_cluster_don->points.size() << " data points." << std::endl;

			stringstream ss;

			ss << "don_cluster_" << j << ".pcd";

			writer.write<pcl::PointNormal>(ss.str(), *cloud_cluster_don, false);

		}

	}

}

分别为:曲率信息可视化、用曲率分类可视化、欧式聚类分割结果

 


八、超体素聚类super voxel clustering

 参考:https://www.cnblogs.com/ironstark/p/5013968.html

https://mp.weixin.qq.com/s?src=11&timestamp=1589335972&ver=2335&signature=OtP6ncAJHI96u7heCkUeo268k8LOe*izAmDP2xFfDPpLn1mQ8z6OGVwgqyFWc1mO-uOoNLJrQSpxAJHSRz3WO7n7deSHXOBE2iH31XYaN*r4k0fN7AWMu6RvbVD0MaLT&new=1 这是某公众号的一片相关的文章,其所展示论文的分割效果我觉得挺好。

超体聚类——一种来自图像的聚类方法

超体(supervoxel)是一种集合,集合的元素是“体”。与体素滤波器中的体类似,其本质是一个个的小方块。与之前提到的所有分割手段不同,超体聚类的目的并不是分割出某种特定物体,其对点云实施过分割(over segmentation),将场景点云化成很多小块,并研究每个小块之间的关系。这种将更小单元合并的分割思路已经出现了有些年份了,在图像分割中,像素聚类形成超像素,以超像素关系来理解图像已经广为研究。本质上这种方法是对局部的一种总结,纹理,材质,颜色类似的部分会被自动的分割成一块,有利于后续识别工作。比如对人的识别,如果能将头发,面部,四肢,躯干分开,则能更好的对各种姿态,性别的人进行识别。

点云和图像不一样,其不存在像素邻接关系。所以,超体聚类之前,必须以八叉树对点云进行划分,获得不同点团之间的邻接关系。与图像相似点云的邻接关系也有很多,如面邻接,线邻接,点邻接。

实现步骤

举个简单的例子来体会下超体聚类,其过程和结晶类似。但不是水结晶成冰,而是盐溶液过饱和状态下的多晶核结晶。所有的晶核(seed)同时开始生长,最终填满整个空间,使物质具有晶体结构。 超体聚类实际上是一种特殊的区域生长算法,和无限制的生长不同,超体聚类首先需要规律的布置区域生长“晶核”。晶核在空间中实际上是均匀分布的,并指定晶核距离(Rseed)。再指定粒子距离(Rvoxel)。再指定最小晶粒(MOV),过小的晶粒需要融入最近的大晶粒。

有了晶粒和结晶范围之后,我们只需要控制结晶过程,就能将整个空间划分开了。结晶过程的本质就是不断吸纳类似的粒子(八分空间)。类似是一个比较模糊的概念,关于类似的定义有以下公式:

公式中的Dc,表示颜色上的差异,Dn表示法线上的差异,Ds代表点距离上的差异。w_*表示一系列权重。用于控制结晶形状。在晶核周围寻找一圈,D最小的体素被认为是下一个“被发展的党员”。需要注意的是,结晶过程并不是长完一个晶核再长下一个,二是所有的晶核同时开始生长(虽然计算机计算时必然有先后,但从层次上来说是同时的)。其生长顺序如下图所示:

接下来所有晶核继续公平竞争,发展第二个“党员”,以此循环,最终所有晶体应该几乎同时完成生长。整个点云也被晶格所分割开来。并且保证了一个晶包里的粒子都是类似的。

实验结果:

pig.pcd

human_in_office.pcd


九、使用渐进形态滤波分割识别地面回波——Identifying ground returns using Progressive Morphological Filter segmentation

渐进形态学滤波器主要用于对点云数据进行地面与其他物体的分割。

在点云滤波中,可以基于模型进行平面、球、圆柱等进行分割,现采用渐进式形态学滤波进行地面分割。通过创建pcl::ProgressiveMorphologicalFilter滤波器对象和添加相关参数,如:增加滤波器的窗口大小和高差阈值将建筑、汽车和植被等非地面物体与地面进行分割。

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/segmentation/progressive_morphological_filter.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/console/parse.h>
int
	main (int argc, char** argv)
{
	int max_w_s (20);
	float slope (1.0f);
	float initial_d (0.5f);
	float max_d (3.0f);
	pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
	pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>),cloud_ground (new pcl::PointCloud<pcl::PointXYZ>);
	pcl::PointIndicesPtr ground (new pcl::PointIndices);
	if(argc<2)
	{
		std::cout << "Usage: " << argv[0] << " filename.pcd [Options]" << std::endl << std::endl;
		std::cout << "Options:" << std::endl;
		std::cout << "     -mw(20):                     Max window size." << std::endl;
		std::cout << "     -s(1.0):                     Slope." << std::endl;
		std::cout << "     -id(0.5):                    initial distance." << std::endl;
		std::cout << "     -md(3.0):                     Max distance" << std::endl;
		exit(1);
	}
	// Fill in the cloud data
	pcl::PCDReader reader;
	// Replace the path below with the path where you saved your file
	reader.read<pcl::PointXYZ> (argv[1], *cloud);
	pcl::console::parse_argument (argc, argv, "-mw", max_w_s);
	pcl::console::parse_argument (argc, argv, "-s", slope);
	pcl::console::parse_argument (argc, argv, "-id", initial_d);
	pcl::console::parse_argument (argc, argv, "-md", max_d);
	std::cerr << "Cloud before filtering: " << std::endl;
	std::cerr << *cloud << std::endl;

	// Create the filtering object
	pcl::ProgressiveMorphologicalFilter<pcl::PointXYZ> pmf;
	pmf.setInputCloud (cloud);
	pmf.setMaxWindowSize (max_w_s);
	pmf.setSlope (slope);
	pmf.setInitialDistance (initial_d);
	pmf.setMaxDistance (max_d);
	pmf.extract (ground->indices);

	// Create the filtering object
	pcl::ExtractIndices<pcl::PointXYZ> extract;
	extract.setInputCloud (cloud);
	extract.setIndices (ground);
	extract.filter (*cloud_ground);

	std::cerr << "Ground cloud after filtering: " << std::endl;
	std::cerr << *cloud_ground << std::endl;
	int v1,v2;
	pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("点云库PCL学习教程第二版-激光雷达点云地面提取"));

	viewer->createViewPort(0,0,0.5,1,v1);
	viewer->createViewPort(0.5,0,1,1,v2);
	viewer->setBackgroundColor(255,255,255,v1);
	viewer->setBackgroundColor(255,255,255,v2);
	pcl::PCDWriter writer;
	writer.write<pcl::PointXYZ> ("samp11-utm_ground.pcd", *cloud_ground, false);
	viewer->addPointCloud(cloud_ground,pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(cloud_ground,0,255,0),"cloud_ground",v1);
	// Extract non-ground returns
	extract.setNegative (true);
	extract.filter (*cloud_filtered);
	viewer->addPointCloud(cloud_filtered,pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>(cloud_filtered,0,0,255),"cloud_filtered",v2);
	viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,4,"cloud_ground",v1);
	viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,4,"cloud_filtered",v2);
	std::cerr << "Object cloud after filtering: " << std::endl;
	std::cerr << *cloud_filtered << std::endl;
	viewer->spin();
	writer.write<pcl::PointXYZ> ("samp11-utm_object.pcd", *cloud_filtered, false);

	return (0);
}

实验结果:

问题:不知道为啥,这里的点云可视化不了,代码看着也没问题,用其他写好的可视化代码直接读取pcd文件再显示也不行,有哪位道友知道原因,记得share哦。【谢谢.jpg】


 十、条件欧几里得聚类Conditional EuclideanClustering

https://blog.csdn.net/AmbitiousRuralDog/article/details/80278210


 

  • 1
    点赞
  • 4
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值