PCL 点云分割与分类 Segmentation RANSAC随机采样一致性 平面模型分割 欧氏距离分割 区域聚类分割算法 最小分割算法 超体聚类 渐进式形态学滤波器

点云分割

点云分割是根据空间,几何和纹理等特征对点云进行划分,
使得同一划分内的点云拥有相似的特征,点云的有效分割往往是许多应用的前提,
例如逆向工作,CAD领域对零件的不同扫描表面进行分割,
然后才能更好的进行空洞修复曲面重建,特征描述和提取,
进而进行基于3D内容的检索,组合重用等。

点云的分割与分类也算是一个大Topic了,这里因为多了一维就和二维图像比多了许多问题,
点云分割又分为区域提取、线面提取、语义分割与聚类等。
同样是分割问题,点云分割涉及面太广,确实是三言两语说不清楚的。
只有从字面意思去理解了,遇到具体问题再具体归类。
一般说来,点云分割是目标识别分类的基础。

分割:

区域声场、
Ransac线面提取、
NDT-RANSAC、
K-Means、
Normalize Cut、
3D Hough Transform(线面提取)、
连通分析。

分类:

基于点的分类,
基于分割的分类,
监督分类与非监督分类

语义分类:

获取场景点云之后,如何有效的利用点云信息,如何理解点云场景的内容,
进行点云的分类很有必要,需要为每个点云进行Labeling。
可以分为基于点的分类方法和基于分割的分类方法。
从方法上可以分为基于监督分类的技术或者非监督分类技术,
深度学习也是一个很有希望应用的技术


随机采样一致性 采样一致性算法 sample_consensus

在计算机视觉领域广泛的使用各种不同的采样一致性参数估计算法用于排除错误的样本,
样本不同对应的应用不同,例如剔除错误的配准点对,分割出 处在模型上的点集,
PCL中以随机采样一致性算法(RANSAC)为核心,

同时实现了五种类似与随机采样一致形算法的随机参数估计算法:
    1. 例如随机采样一致性算法(RANSAC)、
    2. 最大似然一致性算法(MLESAC)、
    3. 最小中值方差一致性算法(LMEDS)等,
所有估计参数算法都符合一致性原则。
在PCL中设计的采样一致性算法的应用主要就是对点云进行分割,根据设定的不同的几个模型,
估计对应的几何参数模型的参数,在一定容许的范围内分割出在模型上的点云。 

RANSAC随机采样一致性算法的介绍

RANSAC是“RANdom SAmple Consensus(随机抽样一致)”的缩写。

它可以从一组包含“局外点”的观测数据集中,通过迭代方式估计数学模型的参数。

它是一种不确定的算法——它有一定的概率得出一个合理的结果;

为了提高概率必须提高迭代次数。
数据分两种:
   有效数据(inliers)和
   无效数据(outliers)。
   
 偏差不大的数据称为有效数据,
 偏差大的数据是无效数据。
 
 如果有效数据占大多数,无效数据只是少量时,
 我们可以通过最小二乘法或类似的方法来确定模型的参数和误差;
 如果无效数据很多(比如超过了50%的数据都是无效数据),
 最小二乘法就 失效了,我们需要新的算法。


一个简单的例子是从一组观测数据中找出合适的2维直线。
假设观测数据中包含局内点和局外点,
其中局内点近似的被直线所通过,而局外点远离于直线。
简单的最 小二乘法不能找到适应于局内点的直线,原因是最小二乘法尽量去适应包括局外点在内的所有点。
相反,RANSAC能得出一个仅仅用局内点计算出模型,并且概 率还足够高。
但是,RANSAC并不能保证结果一定正确,为了保证算法有足够高的合理概率,我们必须小心的选择算法的参数。
包含很多局外点的数据集   RANSAC找到的直线(局外点并不影响结果)

RANSAC算法概述

RANSAC算法的输入是一组观测数据,一个可以解释或者适应于观测数据的参数化模型,一些可信的参数。
RANSAC通过反复选择数据中的一组随机子集来达成目标。被选取的子集被假设为局内点,
并用下述方法进行验证:

1.有一个模型适应于假设的局内点,即所有的未知参数都能从假设的局内点计算得出。
2.用1中得到的模型去测试所有的其它数据,如果某个点适用于估计的模型,认为它也是局内点。
3.如果有足够多的点被归类为假设的局内点,那么估计的模型就足够合理。
4.然后,用所有假设的局内点去重新估计模型,因为它仅仅被初始的假设局内点估计过。
5.最后,通过估计局内点与模型的错误率来评估模型。

算法

伪码形式的算法如下所示:
输入:
data —— 一组观测数据
model —— 适应于数据的模型
n —— 适用于模型的最少数据个数
k —— 算法的迭代次数
t —— 用于决定数据是否适应于模型的阀值
d —— 判定模型是否适用于数据集的数据数目
输出:
best_model —— 跟数据最匹配的模型参数(如果没有找到好的模型,返回null)
best_consensus_set —— 估计出模型的数据点
best_error —— 跟数据相关的估计出的模型错误

      开始:
iterations = 0
best_model = null
best_consensus_set = null
best_error = 无穷大
while ( iterations < k )
    maybe_inliers = 从数据集中随机选择n个点
    maybe_model = 适合于maybe_inliers的模型参数
    consensus_set = maybe_inliers

    for ( 每个数据集中不属于maybe_inliers的点 )
    if ( 如果点适合于maybe_model,且错误小于t )
      将点添加到consensus_set
    if ( consensus_set中的元素数目大于d )
    已经找到了好的模型,现在测试该模型到底有多好
    better_model = 适合于consensus_set中所有点的模型参数
    this_error = better_model究竟如何适合这些点的度量
    if ( this_error < best_error )
      我们发现了比以前好的模型,保存该模型直到更好的模型出现
      best_model =  better_model
      best_consensus_set = consensus_set
      best_error =  this_error
    增加迭代次数
返回 best_model, best_consensus_set, best_error    

最小中值法(LMedS)

LMedS的做法很简单,就是从样本中随机抽出N个样本子集,使用最大似然(通常是最小二乘)
对每个子集计算模型参数和该模型的偏差,记录该模型参
数及子集中所有样本中偏差居中的那个样本的偏差(即Med偏差),
最后选取N个样本子集中Med偏差最小的所对应的模型参数作为我们要估计的模型参数。

在PCL中sample_consensus模块支持的几何模型:

1.平面模型   SACMODEL_PLANE  参数  [normal_x normal_y normal_z d]

2.线模型     SACMODEL_LINE   参数   
[point_on_line.x point_on_line.y point_on_line.z line_direction.x line_direction.y line_direction.z]

3.平面圆模型 SACMODEL_CIRCLE2D  参数 [center.x center.y radius]

4.三维圆模型 SACMODEL_CIRCLE3D
    参数  [center.x, center.y, center.z, radius, normal.x, normal.y, normal.z]
    
5.球模型    SACMODEL_SPHERE

6.圆柱体模型 SACMODEL_CYLINDER 参数
[point_on_axis.x point_on_axis.y point_on_axis.z axis_direction.x axis_direction.y axis_direction.z radius]

7.圆锥体模型 SACMODEL_CONE  参数
[apex.x, apex.y, apex.z, axis_direction.x, axis_direction.y, axis_direction.z, opening_angle]

8.平行线     SACMODEL_PARALLEL_LINE 参数同 线模型 

PCL中Sample_consensus模块及类的介绍

PCL中Sample_consensus库实现了随机采样一致性及其泛化估计算法,
例如平面,柱面,等各种常见的几何模型,用不同的估计算法和不同的
几何模型自由的结合估算点云中隐含的具体几何模型的系数,
实现对点云中所处的几何模型的分割,线,平面,柱面 ,和球面都可以在PCL 库中实现,
平面模型经常被用到常见的室内平面的分割提取中, 比如墙,地板,桌面,
其他模型常应用到根据几何结构检测识别和分割物体中,
一共可以分为两类:
  一类是针对采样一致性及其泛化函数的实现,
  一类是几个不同模型的具体实现,例如:平面,直线,圆球等


pcl::SampleConsensusModel< PointT >是随机采样一致性估计算法中不同模型实现的基类,
所有的采样一致性估计模型都继承于此类,定义了采样一致性模型的相关的一般接口,具体实现由子类完成,其继承关系

模型

pcl::SampleConsensusModel< PointT >
  |
  |
  |
  |_______________->pcl::SampleConsensusModelPlane< PointT >
      ->pcl::SampleConsensusModelLine< PointT >
      ->pcl::SampleConsensusModelCircle2D< PointT > 实现采样一致性 计算二维平面圆周模型
      ->pcl::SampleConsensusModelCircle3D< PointT >  实现采样一致性计算的三维椎体模型
      ->pcl::SampleConsensusModelSphere< PointT >
      ->pcl::SampleConsensusModelCone< PointT ,PointNT >
      ->pcl::SampleConsensusModelCylinder< PointT ,PointNT >
      ->pcl::SampleConsensusModelRegistration< PointT >			
      ->pcl::SampleConsensusModelStick< PointT >

pcl::SampleConsensus< T > 是采样一致性算法的基类

1. SampleConsensus (const SampleConsensusModelPtr &model, double threshold, bool random=false)
  其中model设置随机采样性算法使用的模型,threshold 阀值 
2.设置模型      void     setSampleConsensusModel (const SampleConsensusModelPtr &model)
3.设置距离阈值  void     setDistanceThreshold (double threshold)
4.获取距离阈值  double   getDistanceThreshold ()
5.设置最大迭代次数 void  setMaxIterations (int max_iterations)
6.获取最大迭代次数 int   getMaxIterations ()

1.随机采样一致性 球模型 和 平面模型

pcl::SampleConsensusModelSphere pcl::SampleConsensusModelPlane

在没有任何参数的情况下,三维窗口显示创建的原始点云(含有局内点和局外点),
如图所示,很明显这是一个带有噪声的菱形平面,
噪声点是立方体,自己要是我们在产生点云是生成的是随机数生在(0,1)范围内。

github
#include <iostream>
#include <pcl/console/parse.h>
#include <pcl/filters/extract_indices.h>          // 由索引提取点云
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/sample_consensus/ransac.h>          // 采样一致性
#include <pcl/sample_consensus/sac_model_plane.h> // 平面模型
#include <pcl/sample_consensus/sac_model_sphere.h>// 球模型
#include <pcl/visualization/pcl_visualizer.h>     // 可视化
#include <boost/thread/thread.hpp>

/*
输入点云
返回一个可视化的对象
*/
boost::shared_ptr<pcl::visualization::PCLVisualizer>
simpleVis (pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud)
{
  // --------------------------------------------
  // -----打开3维可视化窗口 加入点云----
  // --------------------------------------------
  boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
  viewer->setBackgroundColor (0, 0, 0);//背景颜色 黑se
  viewer->addPointCloud<pcl::PointXYZ> (cloud, "sample cloud");//添加点云
  viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "sample cloud");//点云对象大小
  //viewer->addCoordinateSystem (1.0, "global");//添加坐标系
  viewer->initCameraParameters ();//初始化相机参数
  return (viewer);
}

/******************************************************************************
 对点云进行初始化,并对其中一个点云填充点云数据作为处理前的的原始点云,
 其中大部分点云数据是基于设定的圆球和平面模型计算
  而得到的坐标值作为局内点,有1/5的点云数据是被随机放置的组委局外点。
 ******************************************************************************/
int
main(int argc, char** argv)
{
  // 初始化点云对象
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);  //存储源点云
  pcl::PointCloud<pcl::PointXYZ>::Ptr final1 (new pcl::PointCloud<pcl::PointXYZ>);  //存储提取的局内点

  // 填充点云数据
  cloud->width    = 500;                //填充点云数目
  cloud->height   = 1;                  //无序点云
  cloud->is_dense = false;
  cloud->points.resize (cloud->width * cloud->height);
  for (size_t i = 0; i < cloud->points.size (); ++i)
  {
    if (pcl::console::find_argument (argc, argv, "-s") >= 0 || pcl::console::find_argument (argc, argv, "-sf") >= 0)
    {
//根据命令行参数用 x^2 + y^2 + Z^2 = 1 设置一部分点云数据,此时点云组成 1/4 个球体 作为内点
      cloud->points[i].x = 1024 * rand () / (RAND_MAX + 1.0);
      cloud->points[i].y = 1024 * rand () / (RAND_MAX + 1.0);
      if (i % 5 == 0)
        cloud->points[i].z = 1024 * rand () / (RAND_MAX + 1.0);   //此处对应的点为局外点
      else if(i % 2 == 0)//正值
        cloud->points[i].z =  sqrt( 1 - (cloud->points[i].x * cloud->points[i].x)
                                      - (cloud->points[i].y * cloud->points[i].y));
      else//负值
        cloud->points[i].z =  - sqrt( 1 - (cloud->points[i].x * cloud->points[i].x)
                                        - (cloud->points[i].y * cloud->points[i].y));
    }
    else
    { //用x+y+z=1设置一部分点云数据,此时 用点云组成的菱形平面作为内点
      cloud->points[i].x = 1024 * rand () / (RAND_MAX + 1.0);
      cloud->points[i].y = 1024 * rand () / (RAND_MAX + 1.0);
      if( i % 2 == 0)
        cloud->points[i].z = 1024 * rand () / (RAND_MAX + 1.0);   //对应的局外点
      else
        cloud->points[i].z = -1 * (cloud->points[i].x + cloud->points[i].y);
    }
  }

  std::vector<int> inliers;  //存储局内点集合的点的索引的向量

  //创建随机采样一致性对象
  pcl::SampleConsensusModelSphere<pcl::PointXYZ>::Ptr
    model_s(new pcl::SampleConsensusModelSphere<pcl::PointXYZ> (cloud));   //针对球模型的对象
  pcl::SampleConsensusModelPlane<pcl::PointXYZ>::Ptr
    model_p (new pcl::SampleConsensusModelPlane<pcl::PointXYZ> (cloud));   //针对平面模型的对象
  if(pcl::console::find_argument (argc, argv, "-f") >= 0)
  {  //根据命令行参数,来随机估算对应平面模型,并存储估计的局内点
    pcl::RandomSampleConsensus<pcl::PointXYZ> ransac (model_p);
    ransac.setDistanceThreshold (.01);    //与平面距离小于0.01 的点称为局内点考虑
    ransac.computeModel();                //执行随机参数估计
    ransac.getInliers(inliers);           //存储估计所得的局内点
  }
  else if (pcl::console::find_argument (argc, argv, "-sf") >= 0 )
  { 
   //根据命令行参数  来随机估算对应的圆球模型,存储估计的内点
    pcl::RandomSampleConsensus<pcl::PointXYZ> ransac (model_s);
    ransac.setDistanceThreshold (.01);
    ransac.computeModel();
    ransac.getInliers(inliers);
  }

  // 复制估算模型的所有的局内点到final中
  pcl::copyPointCloud<pcl::PointXYZ>(*cloud, inliers, *final1);

  // 创建可视化对象并加入原始点云或者所有的局内点
  boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer;
  if (pcl::console::find_argument (argc, argv, "-f") >= 0 || pcl::console::find_argument (argc, argv, "-sf") >= 0)
    viewer = simpleVis(final1);
  else
    viewer = simpleVis(cloud);
  while (!viewer->wasStopped ())
  {
    viewer->spinOnce (100);
    boost::this_thread::sleep (boost::posix_time::microseconds (100000));
  }
  return 0;
}

2.分割平面 平面模型分割 基于随机采样一致性

 pcl::SACSegmentation pcl::SACMODEL_PLANE

github

#include <iostream>
#include <pcl/ModelCoefficients.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl/visualization/pcl_visualizer.h>     // 可视化
#include <pcl/filters/extract_indices.h>//按索引提取点云
#include <boost/make_shared.hpp>
int
 main (int argc, char** argv)
{
 // 新建点云 
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  // 随机生成点云
  cloud->width  = 15;
  cloud->height = 1;//无序点云
  cloud->points.resize (cloud->width * cloud->height);
  // 生成
  for (size_t i = 0; i < cloud->points.size (); ++i)
  {
    cloud->points[i].x = 1024 * rand () / (RAND_MAX + 1.0f);
    cloud->points[i].y = 1024 * rand () / (RAND_MAX + 1.0f);
    cloud->points[i].z = 1.0;//都在z=1平面上
  }

  // 设置一些外点 , 即重新设置几个点的z值,使其偏离z为1的平面
  cloud->points[0].z = 2.0;
  cloud->points[3].z = -2.0;
  cloud->points[6].z = 4.0;
  // 打印点云信息
  std::cerr << "Point cloud data: " << cloud->points.size () << " points" << std::endl;
  for (size_t i = 0; i < cloud->points.size (); ++i)
    std::cerr << "    " << cloud->points[i].x << " "
                        << cloud->points[i].y << " "
                        << cloud->points[i].z << std::endl;
// 模型系数
  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);//内点索引
 // pcl::PointIndices::Ptr outliers (new pcl::PointIndices);//外点索引
// 创建一个点云分割对象
  pcl::SACSegmentation<pcl::PointXYZ> seg;
  // 是否优化模型系数
  seg.setOptimizeCoefficients (true);
  // 设置模型 和 采样方法
  seg.setModelType (pcl::SACMODEL_PLANE);// 平面模型
  seg.setMethodType (pcl::SAC_RANSAC);// 随机采样一致性算法
  seg.setDistanceThreshold (0.01);//是否在平面上的阈值

  seg.setInputCloud (cloud);//输入点云
  seg.segment (*inliers, *coefficients);//分割 得到平面系数 已经在平面上的点的 索引
 // seg.setNegative(true);//设置提取内点而非外点
  //seg.segment(*inliers, *coefficients);//分割 得到平面系数 已经在平面上的点的 索引

  if (inliers->indices.size () == 0)
  {
    PCL_ERROR ("Could not estimate a planar model for the given dataset.");
    return (-1);
  }
// 打印平面系数
  std::cerr << "Model coefficients: " << coefficients->values[0] << " " 
                                      << coefficients->values[1] << " "
                                      << coefficients->values[2] << " " 
                                      << coefficients->values[3] << std::endl;
//打印平面上的点
  std::cerr << "Model inliers: " << inliers->indices.size () << std::endl;
  for (size_t i = 0; i < inliers->indices.size (); ++i)
    std::cerr << inliers->indices[i] << "    " << cloud->points[inliers->indices[i]].x << " "
                                               << cloud->points[inliers->indices[i]].y << " "
                                               << cloud->points[inliers->indices[i]].z << std::endl;


// 3D点云显示 源点云 绿色
  pcl::visualization::PCLVisualizer viewer ("3D Viewer");
  viewer.setBackgroundColor (255, 255, 255);//背景颜色 白色
  //pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> color_handler(cloud, 1.0, 1.0, 0.0);
  //viewer.addPointCloud (cloud, color_handler, "raw point");//添加点云
  //viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "raw point");
  //viewer.addCoordinateSystem (1.0);
  viewer.initCameraParameters ();

//按照索引提取点云  内点
  pcl::ExtractIndices<pcl::PointXYZ> extract_indices;//索引提取器
  extract_indices.setIndices (boost::make_shared<const pcl::PointIndices> (*inliers));//设置索引
  extract_indices.setInputCloud (cloud);//设置输入点云
  pcl::PointCloud<pcl::PointXYZ>::Ptr output (new pcl::PointCloud<pcl::PointXYZ>);
  extract_indices.filter (*output);//提取对于索引的点云 内点
  std::cerr << "output point size : " << output->points.size () << std::endl;

//平面上的点云 红色
  pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> output_handler(output, 255, 0, 0);
  viewer.addPointCloud (output, output_handler, "plan point");//添加点云
  viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "plan point");


// 外点 绿色
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_other(new pcl::PointCloud<pcl::PointXYZ>);
  // *cloud_other = *cloud - *output;
  // 移去平面局内点,提取剩余点云
  extract_indices.setNegative (true);
  extract_indices.filter (*cloud_other);
  std::cerr << "other point size : " << cloud_other->points.size () << std::endl;

  pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> cloud_other_handler(cloud_other, 0, 255, 0);
  viewer.addPointCloud (cloud_other, cloud_other_handler, "other point");//添加点云
  viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "other point");


    while (!viewer.wasStopped()){
        viewer.spinOnce(100);
        boost::this_thread::sleep(boost::posix_time::microseconds(100000));
    }

  return (0);
}

3.圆柱体分割依据法线信息分割 平面上按圆柱体模型分割得到圆柱体点云

pcl::SACSegmentationFromNormals

圆柱体分割 依据法线信息分割
先分割平面 得到平面上的点云
在平面上的点云中 分割圆柱体点云
实现圆柱体模型的分割:
采用随机采样一致性估计从带有噪声的点云中提取一个圆柱体模型。
github
#include <pcl/ModelCoefficients.h>//模型系数
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/filters/extract_indices.h>//按索引提取点云
#include <pcl/filters/passthrough.h>// 直通滤波器
#include <pcl/features/normal_3d.h>// 法线特征
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>//随机采用分割
#include <pcl/visualization/pcl_visualizer.h> // 可视化

typedef pcl::PointXYZ PointT;
int main (int argc, char** argv)
{
  // 所需要的对象 All the objects needed
  pcl::PCDReader reader;//PCD文件读取对象
  pcl::PassThrough<PointT> pass;//直通滤波对象
  pcl::NormalEstimation<PointT, pcl::Normal> ne;//法线估计对象
  pcl::SACSegmentationFromNormals<PointT, pcl::Normal> seg;//依据法线 分割对象
  pcl::PCDWriter writer;//PCD文件写对象
  pcl::ExtractIndices<PointT> extract;//点 提取对象
  pcl::ExtractIndices<pcl::Normal> extract_normals;    ///点法线特征 提取对象
  pcl::search::KdTree<PointT>::Ptr tree (new pcl::search::KdTree<PointT> ());

  // 数据对象 Datasets
  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
  pcl::PointCloud<PointT>::Ptr cloud_filtered (new pcl::PointCloud<PointT>);
  pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);//法线特征
  pcl::PointCloud<PointT>::Ptr cloud_filtered2 (new pcl::PointCloud<PointT>);
  pcl::PointCloud<pcl::Normal>::Ptr cloud_normals2 (new pcl::PointCloud<pcl::Normal>);//法线特征
  pcl::ModelCoefficients::Ptr coefficients_plane (new pcl::ModelCoefficients), coefficients_cylinder (new pcl::ModelCoefficients);//模型系数
  pcl::PointIndices::Ptr inliers_plane (new pcl::PointIndices), inliers_cylinder (new pcl::PointIndices);//内点索引

  // 读取桌面场景点云 Read in the cloud data
  reader.read ("../../surface/table_scene_mug_stereo_textured.pcd", *cloud);
  std::cerr << "PointCloud has: " << cloud->points.size () << " data points." << std::endl;

  // 直通滤波,将Z轴不在(0,1.5)范围的点过滤掉,将剩余的点存储到cloud_filtered对象中
  pass.setInputCloud (cloud);
  pass.setFilterFieldName ("z");// Z轴
  pass.setFilterLimits (0, 1.5);// 范围
  pass.filter (*cloud_filtered);
  std::cerr << "PointCloud after filtering has: " << cloud_filtered->points.size () << " data points." << std::endl;

  // 过滤后的点云进行法线估计,为后续进行基于法线的分割准备数据
  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 (0.03);    //设置内点到模型的距离允许最大值
  seg.setInputCloud (cloud_filtered); //输入点云
  seg.setInputNormals (cloud_normals);//输入法线特征
  //获取平面模型的系数和处在平面的内点
  seg.segment (*inliers_plane, *coefficients_plane);//分割 得到内点索引 和模型系数
  std::cerr << "Plane coefficients: " << *coefficients_plane << std::endl;

  // 从点云中抽取分割 处在平面上的点集 内点
  extract.setInputCloud (cloud_filtered);
  extract.setIndices (inliers_plane);
  extract.setNegative (false);
  // 存储分割得到的平面上的点到点云文件
  pcl::PointCloud<PointT>::Ptr cloud_plane (new pcl::PointCloud<PointT> ());
  extract.filter (*cloud_plane);//平面上的点云
  std::cerr << "PointCloud representing the planar component: " << cloud_plane->points.size () << " data points." << std::endl;
  writer.write ("table_scene_mug_stereo_textured_plane.pcd", *cloud_plane, false);

  // 提取 得到平面上的点云 (外点) 以及其法线特征
  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);//提取外点对应的法线特征

  // 在平面上的点云 分割 圆柱体 
  seg.setOptimizeCoefficients (true);   //设置对估计模型优化
  seg.setModelType (pcl::SACMODEL_CYLINDER);//设置分割模型为圆柱形
  seg.setMethodType (pcl::SAC_RANSAC);      //参数估计方法 随机采样一致性算法
  seg.setNormalDistanceWeight (0.1);        //设置表面法线权重系数
  seg.setMaxIterations (10000);             //设置迭代的最大次数10000
  seg.setDistanceThreshold (0.05);          //设置内点到模型的距离允许最大值
  seg.setRadiusLimits (0, 0.1);             //设置估计出的圆柱模型的半径的范围
  seg.setInputCloud (cloud_filtered2);      //输入点云
  seg.setInputNormals (cloud_normals2);     //输入点云对应的法线特征

  // 获取符合圆柱体模型的内点 和 对应的系数
  seg.segment (*inliers_cylinder, *coefficients_cylinder);
  std::cerr << "Cylinder coefficients: " << *coefficients_cylinder << std::endl;

  // 写文件到
  extract.setInputCloud (cloud_filtered2);
  extract.setIndices (inliers_cylinder);
  extract.setNegative (false);//得到圆柱体点云
  pcl::PointCloud<PointT>::Ptr cloud_cylinder (new pcl::PointCloud<PointT> ());
  extract.filter (*cloud_cylinder);
  if (cloud_cylinder->points.empty ()) 
    std::cerr << "Can't find the cylindrical component." << std::endl;
  else
  {
      std::cerr << "PointCloud representing the cylindrical component: " << cloud_cylinder->points.size () << " data points." << std::endl;
      writer.write ("table_scene_mug_stereo_textured_cylinder.pcd", *cloud_cylinder, false);
  }

// 3D点云显示 绿色
  pcl::visualization::PCLVisualizer viewer ("3D Viewer");
  viewer.setBackgroundColor (255, 255, 255);//背景颜色 白色
  //viewer.addCoordinateSystem (1.0);
  viewer.initCameraParameters ();
//平面上的点云 红色
  pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> cloud_plane_handler(cloud_plane, 255, 0, 0);
  viewer.addPointCloud (cloud_plane, cloud_plane_handler, "plan point");//添加点云
  viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "plan point");
//  圆柱体模型的内点 绿色
  pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> cloud_cylinder_handler(cloud_cylinder, 0, 255, 0);
  viewer.addPointCloud (cloud_cylinder, cloud_cylinder_handler, "cylinder point");//添加点云
  viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "cylinder point");

    while (!viewer.wasStopped()){
        viewer.spinOnce(100);
        boost::this_thread::sleep(boost::posix_time::microseconds(100000));
    }

  return (0);
}


4 .欧氏距离分割 平面模型分割平面 平面上按 聚类得到 多个点云团

具体的实现方法大致是(原理是将一个点云团聚合成一类):
    1. 找到空间中某点p10,用kdTree找到离他最近的n个点,判断这n个点到p10的距离。
	将距离小于阈值r的点p12,p13,p14....放在类Q里
    2. 在 Q\p10 里找到一点p12,重复1
    3. 在 Q\p10,p12 找到一点,重复1,找到p22,p23,p24....全部放进Q里
    4. 当 Q 再也不能有新点加入了,则完成搜索了

因为点云总是连成片的,很少有什么东西会浮在空中来区分。
但是如果结合此算法可以应用很多东东。

   1. 半径滤波(统计学滤波)删除离群点 体素格下采样等
   2. 采样一致找到桌面(平面)或者除去滤波
   3. 提取除去平面内点的 外点 (桌上的物体就自然成了一个个的浮空点云团)
   4. 欧式聚类 提取出我们想要识别的东西
github
#include <pcl/ModelCoefficients.h>//模型系数
#include <pcl/point_types.h>//点云基本类型
#include <pcl/io/pcd_io.h>//io
#include <pcl/filters/extract_indices.h>//根据索引提取点云
#include <pcl/filters/voxel_grid.h>//体素格下采样
#include <pcl/features/normal_3d.h>//点云法线特征
#include <pcl/kdtree/kdtree.h>//kd树搜索算法
#include <pcl/sample_consensus/method_types.h>//采样方法
#include <pcl/sample_consensus/model_types.h>//采样模型
#include <pcl/segmentation/sac_segmentation.h>//随机采用分割
#include <pcl/segmentation/extract_clusters.h>//欧式聚类分割
#include <pcl/visualization/pcl_visualizer.h> // 可视化

/******************************************************************************
 打开点云数据,并对点云进行滤波重采样预处理,然后采用平面分割模型对点云进行分割处理
 提取出点云中所有在平面上的点集,并将其存盘
******************************************************************************/
int 
main (int argc, char** argv)
{
  // 读取桌面场景点云
  pcl::PCDReader reader;
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>), cloud_f (new pcl::PointCloud<pcl::PointXYZ>);
  reader.read ("../../Filtering/table_scene_lms400.pcd", *cloud);
  std::cout << "PointCloud before filtering has: " << cloud->points.size () << " data points." << std::endl; //*
// 之前可进行 统计学滤波去除外点
  // //体素格滤波下采样 1cm×1cm×1cm
  pcl::VoxelGrid<pcl::PointXYZ> vg;//体素格滤波下采样
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>);
  vg.setInputCloud (cloud);
  vg.setLeafSize (0.01f, 0.01f, 0.01f);
  vg.filter (*cloud_filtered);
  std::cout << 	"PointCloud after filtering has: " << 
	       	cloud_filtered->points.size ()     << 
		" data points." << std::endl; //*
   //创建平面模型分割的对象并设置参数
  pcl::SACSegmentation<pcl::PointXYZ> seg;
  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);//系数
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_plane (new pcl::PointCloud<pcl::PointXYZ> ());
  pcl::PCDWriter writer;
  seg.setOptimizeCoefficients (true);
  seg.setModelType (pcl::SACMODEL_PLANE);    //分割模型 平面模型
  seg.setMethodType (pcl::SAC_RANSAC);       //随机采样一致性 参数估计方法
  seg.setMaxIterations (100);                //最大的迭代的次数
  seg.setDistanceThreshold (0.02);           //设置符合模型的内点 阀值

  int i=0, nr_points = (int) cloud_filtered->points.size ();//下采样前点云数量

  while (cloud_filtered->points.size () > 0.3 * nr_points)
// 模型分割 直到 剩余点云数量在30%以上 确保模型点云较好
  {
    // Segment the largest planar component from the remaining cloud
    seg.setInputCloud (cloud_filtered);
    seg.segment (*inliers, *coefficients);//分割
    if (inliers->indices.size () == 0)
    {
      std::cout << "Could not estimate a planar model for the given dataset." << std::endl;
      break;
    }

    pcl::ExtractIndices<pcl::PointXYZ> extract;//按索引提取点云
    extract.setInputCloud (cloud_filtered);
    extract.setIndices (inliers);//提取符合平面模型的内点
    extract.setNegative (false);
    // 平面模型内点
    extract.filter (*cloud_plane);
    std::cout << "PointCloud representing the planar component: " << 
		  cloud_plane->points.size () << 
		  " data points." << std::endl;
    // 移去平面局内点,提取剩余点云
    extract.setNegative (true);
    extract.filter (*cloud_f);
    *cloud_filtered = *cloud_f;//剩余点云
  }

  // 桌子平面上 的点云团 使用 欧式聚类的算法 kd树搜索 对点云聚类分割
  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
  tree->setInputCloud (cloud_filtered);// 桌子平面上其他的点云
  std::vector<pcl::PointIndices> cluster_indices;// 点云团索引
  pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;// 欧式聚类对象
  ec.setClusterTolerance (0.02);                    // 设置近邻搜索的搜索半径为2cm
  ec.setMinClusterSize (100);                       // 设置一个聚类需要的最少的点数目为100
  ec.setMaxClusterSize (25000);                     // 设置一个聚类需要的最大点数目为25000
  ec.setSearchMethod (tree);                        // 设置点云的搜索机制
  ec.setInputCloud (cloud_filtered);
  ec.extract (cluster_indices);           //从点云中提取聚类,并将点云索引保存在cluster_indices中

  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster_all (new pcl::PointCloud<pcl::PointXYZ>);
  //迭代访问点云索引cluster_indices,直到分割处所有聚类
  int j = 0;
  for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
  {
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>);
    for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit)
    	cloud_cluster->points.push_back (cloud_filtered->points[*pit]); //获取每一个点云团 的 点

    cloud_cluster->width = cloud_cluster->points.size ();
    cloud_cluster->height = 1;
    cloud_cluster->is_dense = true;

    std::cout << "PointCloud representing the Cluster: " << cloud_cluster->points.size () << " data points." << std::endl;
    std::stringstream ss;
    ss << "cloud_cluster_" << j << ".pcd";
    // writer.write<pcl::PointXYZ> (ss.str (), *cloud_cluster, false); //*
    j++;

  *cloud_cluster_all += *cloud_cluster;
  }
  pcl::io::savePCDFileASCII("cloud_cluster_all", *cloud_cluster_all);


// 3D点云显示 绿色
  pcl::visualization::PCLVisualizer viewer ("3D Viewer");
  viewer.setBackgroundColor (255, 255, 255);//背景颜色 白色
  //viewer.addCoordinateSystem (1.0);
  viewer.initCameraParameters ();
//平面上的点云 红色
  pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> cloud_plane_handler(cloud_plane, 255, 0, 0);
  viewer.addPointCloud (cloud_plane, cloud_plane_handler, "plan point");//添加点云
  viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "plan point");

//  桌上的物体就自然成了一个个的浮空点云团 绿色
  pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> cloud_cluster_handler(cloud_cluster_all, 0, 255, 0);
  viewer.addPointCloud (cloud_cluster_all, cloud_cluster_handler, "cloud_cluster point");//添加点云
  viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "cloud_cluster point");

    while (!viewer.wasStopped()){
        viewer.spinOnce(100);
        boost::this_thread::sleep(boost::posix_time::microseconds(100000));
    }
  return (0);
}

5 .基于法线差值和曲率差值的区域聚类分割算法

pcl::RegionGrowing

区域生成的分割法
区 域生长的基本 思想是: 将具有相似性的像素集合起来构成区域。
首先对每个需要分割的区域找出一个种子像素作为生长的起点,
然后将种子像素周围邻域中与种子有相同或相似性质的像素 
(根据事先确定的生长或相似准则来确定)合并到种子像素所在的区域中。
而新的像素继续作为种子向四周生长,
直到再没有满足条件的像素可以包括进来,一个区 域就生长而成了。

区域生长算法直观感觉上和欧几里德算法相差不大,
都是从一个点出发,最终占领整个被分割区域,
欧几里德算法是通过距离远近,
对于普通点云的区域生长,其可由法线、曲率估计算法获得其法线和曲率值。
通过法线和曲率来判断某点是否属于该类。

算法的主要思想是:

	首先依据点的曲率值对点进行排序,之所以排序是因为,
	区域生长算法是从曲率最小的点开始生长的,这个点就是初始种子点,
	初始种子点所在的区域即为最平滑的区域,
	从最平滑的区域开始生长可减少分割片段的总数,提高效率,
	设置一空的种子点序列和空的聚类区域,选好初始种子后,
	将其加入到种子点序列中,并搜索邻域点,
	对每一个邻域点,比较邻域点的法线与当前种子点的法线之间的夹角,
	小于平滑阀值的将当前点加入到当前区域,
	然后检测每一个邻域点的曲率值,小于曲率阀值的加入到种子点序列中,
	删除当前的种子点,循环执行以上步骤,直到种子序列为空.

其算法可以总结为:

    0. 计算 法线normal 和 曲率curvatures,依据曲率升序排序;
    1. 选择曲率最低的为初始种子点,种子周围的临近点和种子点云相比较;
    2. 法线的方向是否足够相近(法线夹角足够 r p y),法线夹角阈值;
    3. 曲率是否足够小( 表面处在同一个弯曲程度 ),区域差值阈值;
    4. 如果满足2,3则该点可用做种子点;
    5. 如果只满足2,则归类而不做种;
    从某个种子出发,其“子种子”不再出现,则一类聚集完成
    类的规模既不能太大也不能太小.


  显然,上述算法是针对小曲率变化面设计的。
尤其适合对连续阶梯平面进行分割:比如SLAM算法所获得的建筑走廊。
github
#include <iostream>
#include <vector>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>//文件io
#include <pcl/search/search.h>
#include <pcl/search/kdtree.h>//搜索 kd树
#include <pcl/features/normal_3d.h>//计算点云法线曲率特征
#include <pcl/visualization/cloud_viewer.h>//可视化
#include <pcl/filters/passthrough.h>//直通滤波器
#include <pcl/segmentation/region_growing.h>//区域增长点云分割算法

int
main (int argc, char** argv)
{ 
  //点云的类型
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
  //打开点云pdc文件 载入点云
  if ( pcl::io::loadPCDFile <pcl::PointXYZ> ("../region_growing_tutorial.pcd", *cloud) == -1)
  {
    std::cout << "Cloud reading failed." << std::endl;
    return (-1);
  }
 //设置搜索的方式或者说是结构 kd树 搜索
  pcl::search::Search<pcl::PointXYZ>::Ptr tree = boost::shared_ptr<pcl::search::Search<pcl::PointXYZ> > (new pcl::search::KdTree<pcl::PointXYZ>);
   //求法线 和 曲率 
  pcl::PointCloud <pcl::Normal>::Ptr normals (new pcl::PointCloud <pcl::Normal>);
  pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> normal_estimator;
  normal_estimator.setSearchMethod (tree);
  normal_estimator.setInputCloud (cloud);
  normal_estimator.setKSearch (50);//临近50个点
  normal_estimator.compute (*normals);

   //直通滤波在Z轴的0到1米之间 剔除 nan 和 噪点
  pcl::IndicesPtr indices (new std::vector <int>);
  pcl::PassThrough<pcl::PointXYZ> pass;
  pass.setInputCloud (cloud);
  pass.setFilterFieldName ("z");
  pass.setFilterLimits (0.0, 1.0);
  pass.filter (*indices);
  //区域增长聚类分割对象 <点,法线>
  pcl::RegionGrowing<pcl::PointXYZ, pcl::Normal> reg;
  reg.setMinClusterSize (50);     //最小的聚类的点数
  reg.setMaxClusterSize (1000000);//最大的聚类的点数
  reg.setSearchMethod (tree);     //搜索方式
  reg.setNumberOfNeighbours (30); //设置搜索的邻域点的个数
  reg.setInputCloud (cloud);      //输入点
  //reg.setIndices (indices);
  reg.setInputNormals (normals);  //输入的法线
  reg.setSmoothnessThreshold (3.0 / 180.0 * M_PI);//设置平滑度 法线差值阈值
  reg.setCurvatureThreshold (1.0);                //设置曲率的阀值

  std::vector <pcl::PointIndices> clusters;
  reg.extract (clusters);//提取点的索引

  std::cout << "点云团数量 Number of clusters is equal to " << clusters.size () << std::endl;//点云团 个数
  std::cout << "First cluster has " << clusters[0].indices.size () << " points." << endl;
  std::cout << "These are the indices of the points of the initial" <<
    std::endl << "cloud that belong to the first cluster:" << std::endl;
/* 
 int counter = 0;
  while (counter < clusters[0].indices.size ())
  {
    std::cout << clusters[0].indices[counter] << ", ";//索引
    counter++;
    if (counter % 10 == 0)
      std::cout << std::endl;
  }
  std::cout << std::endl;
 */ 
  //可视化聚类的结果
  pcl::PointCloud <pcl::PointXYZRGB>::Ptr colored_cloud = reg.getColoredCloud ();
  pcl::visualization::CloudViewer viewer ("Cluster viewer");
  viewer.showCloud(colored_cloud);
  while (!viewer.wasStopped ())
  {
  }

  return (0);
}

6.基于颜色差值的区域聚类分割算法 pcl::RegionGrowingRGB

基于颜色的区域生长分割法
除了普通点云之外,还有一种特殊的点云,成为RGB点云
。显而易见,这种点云除了结构信息之外,还存在颜色信息。
将物体通过颜色分类,是人类在辨认果实的 过程中进化出的能力,
颜色信息可以很好的将复杂场景中的特殊物体分割出来。
比如Xbox Kinect就可以轻松的捕捉颜色点云。
基于颜色的区域生长分割原理上和基于曲率,法线的分割方法是一致的。
只不过比较目标换成了颜色,去掉了点云规模上 限的限制。
可以认为,同一个颜色且挨得近,是一类的可能性很大,不需要上限来限制。
所以这种方式比较适合用于室内场景分割。
尤其是复杂室内场景,颜色分割 可以轻松的将连续的场景点云变成不同的物体。
哪怕是高低不平的地面,设法用采样一致分割器抽掉平面,
颜色分割算法对不同的颜色的物体实现分割。

算法分为两步:

(1)分割,当前种子点和领域点之间色差小于色差阀值的视为一个聚类

(2)合并,聚类之间的色差小于色差阀值和并为一个聚类,
  且当前聚类中点的数量小于聚类点数量的与最近的聚类合并在一起
github
#include <iostream>
#include <vector>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/search/search.h>
#include <pcl/search/kdtree.h>//搜索 kd树
#include <pcl/visualization/cloud_viewer.h>//可视化
#include <pcl/filters/passthrough.h>//直通滤波器
#include <pcl/segmentation/region_growing_rgb.h>//基于颜色的区域增长点云分割算法

int
main (int argc, char** argv)
{
  // 搜索算法
  pcl::search::Search <pcl::PointXYZRGB>::Ptr tree = boost::shared_ptr<pcl::search::Search<pcl::PointXYZRGB> > (new pcl::search::KdTree<pcl::PointXYZRGB>);
  //点云的类型
  pcl::PointCloud <pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud <pcl::PointXYZRGB>);
  if ( pcl::io::loadPCDFile <pcl::PointXYZRGB> ("../region_growing_rgb_tutorial.pcd", *cloud) == -1 )
  {
    std::cout << "Cloud reading failed." << std::endl;
    return (-1);
  }
  //存储点云索引 的容器
  pcl::IndicesPtr indices (new std::vector <int>);
  //直通滤波在Z轴的0到1米之间 剔除 nan 和 噪点
  pcl::PassThrough<pcl::PointXYZRGB> pass;// 
  pass.setInputCloud (cloud);
  pass.setFilterFieldName ("z");
  pass.setFilterLimits (0.0, 1.0);
  pass.filter (*indices);//直通滤波后的的点云的索引 避免拷贝
  
 //基于颜色的区域生成的对象
  pcl::RegionGrowingRGB<pcl::PointXYZRGB> reg;
  reg.setInputCloud (cloud);
  reg.setIndices (indices);   //点云的索引
  reg.setSearchMethod (tree);
  reg.setDistanceThreshold (10);//距离的阀值
  reg.setPointColorThreshold (6);//点与点之间颜色容差
  reg.setRegionColorThreshold (5);//区域之间容差
  reg.setMinClusterSize (600);    //设置聚类的大小
  std::vector <pcl::PointIndices> clusters;
  reg.extract (clusters);//

  pcl::PointCloud <pcl::PointXYZRGB>::Ptr colored_cloud = reg.getColoredCloud ();
  pcl::visualization::CloudViewer viewer ("Cluster viewer");
  viewer.showCloud (colored_cloud);
  while (!viewer.wasStopped ())
  {
    boost::this_thread::sleep (boost::posix_time::microseconds (100));
  }

  return (0);
}

7.最小分割算法 (分割点云) 基于距离加权的最小图分割算法

pcl::MinCutSegmentation

最小分割算法  (分割点云)
该算法是将一幅点云图像分割为两部分:
前景点云(目标物体)和背景物体(剩余部分)
The Min-Cut (minimum cut) algorithm最小割算法是图论中的一个概念,
其作用是以某种方式,将两个点分开,当然这两个点中间可能是通过无数的点再相连的。

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


所以那么怎么来理解点云的图呢?
显而易见,切割有两个非常重要的因素,
第一个是获得点与点之间的拓扑关系,这种拓扑关系就是生成一张 “图”。
第二个是给图中的连线赋予合适的权值。
只要这两个要素合适,最小割算法就会正确的分割出想要的结果。
点云是分开的点。只要把点云中所有的点连起来就可以了。

连接算法如下:
	   1. 找到每个点临近的n个点
	   2. 将这n个点和父点连接
	   3. 找到距离最小的两个块(A块中某点与B块中某点距离最小),并连接
	   4. 重复3,直至只剩一个块
	   
经过上面的步骤现在已经有了点云的“图”,只要给图附上合适的权值,就满足了最小分割的前提条件。
物体分割比如图像分割给人一个直观印象就是属于该物体的点,应该相互之间不会太远。
也就是说,可以用点与点之间的欧式距离来构造权值。
所有线的权值可映射为线长的函数。 

cost = exp(-(dist/cet)^2)  距离越远 cost越小 越容易被分割

我们知道这种分割是需要指定对象的,也就是我们指定聚类的中心点(center)以及聚类的半径(radius),
当然我们指定了中心点和聚类的半径,那么就要被保护起来,保护的方法就是增加它的权值.

dist2Center / radius

dist2Center = sqrt((x-x_center)^2+(y-y_center)^2)
github
#include <pcl/io/pcd_io.h>
#include <pcl/search/kdtree.h>
#include <pcl/features/normal_3d.h>
#include <pcl/segmentation/region_growing.h>
#include <pcl/segmentation/min_cut_segmentation.h>
#include <iostream>
#include <pcl/segmentation/region_growing_rgb.h>

int
main(int argc, char** argv)
{
    //申明点云的类型
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
    // 法线
    pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);

    if (pcl::io::loadPCDFile<pcl::PointXYZ>("../min_Cut_Based.pcd", *cloud) != 0)
    {
        return -1;
    }
       // 申明一个Min-cut的聚类对象
    pcl::MinCutSegmentation<pcl::PointXYZ> clustering;
    clustering.setInputCloud(cloud);//设置输入
    //创建一个点云,列出所知道的所有属于对象的点 
    // (前景点)在这里设置聚类对象的中心点(想想是不是可以可以使用鼠标直接选择聚类中心点的方法呢?)
    pcl::PointCloud<pcl::PointXYZ>::Ptr foregroundPoints(new pcl::PointCloud<pcl::PointXYZ>());
    pcl::PointXYZ point;
    point.x = 100.0;
    point.y = 100.0;
    point.z = 100.0;
    foregroundPoints->points.push_back(point);
    clustering.setForegroundPoints(foregroundPoints);//设置聚类对象的前景点
       
    //设置sigma,它影响计算平滑度的成本。它的设置取决于点云之间的间隔(分辨率)
    clustering.setSigma(0.02);// cet cost = exp(-(dist/cet)^2) 
    // 设置聚类对象的半径.
    clustering.setRadius(0.01);// dist2Center / radius

         //设置需要搜索的临近点的个数,增加这个也就是要增加边界处图的个数
    clustering.setNumberOfNeighbours(20);

        //设置前景点的权重(也就是排除在聚类对象中的点,它是点云之间线的权重,)
    clustering.setSourceWeight(0.6);

    std::vector <pcl::PointIndices> clusters;
    clustering.extract(clusters);

    std::cout << "Maximum flow is " << clustering.getMaxFlow() << "." << std::endl;

    int currentClusterNum = 1;
    for (std::vector<pcl::PointIndices>::const_iterator i = clusters.begin(); i != clusters.end(); ++i)
    {
        //设置聚类后点云的属性
        pcl::PointCloud<pcl::PointXYZ>::Ptr cluster(new pcl::PointCloud<pcl::PointXYZ>);
        for (std::vector<int>::const_iterator point = i->indices.begin(); point != i->indices.end(); point++)
            cluster->points.push_back(cloud->points[*point]);
        cluster->width = cluster->points.size();
        cluster->height = 1;
        cluster->is_dense = true;

           //保存聚类的结果
        if (cluster->points.size() <= 0)
            break;
        std::cout << "Cluster " << currentClusterNum << " has " << cluster->points.size() << " points." << std::endl;
        std::string fileName = "cluster" + boost::to_string(currentClusterNum) + ".pcd";
        pcl::io::savePCDFileASCII(fileName, *cluster);

        currentClusterNum++;
    }

}

8.基于不同领域半径估计的法线的差异类 欧氏聚类 分割 点云

pcl::DifferenceOfNormalsEstimation



基于不同领域半径估计的 法线的差异类分割点云
步骤:
	1. 估计大领域半径 r_l 下的 法线    
	2. 估计small领域半径 r_s 下的 法线 
	3. 法线的差异  det(n,r_l, r_s) = (n_l - n_s)/2
	4. 条件滤波器 
	5. 欧式聚类 法线的差异
github

#include <string>

#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/search/organized.h>
#include <pcl/search/kdtree.h>//搜索 kd树
#include <pcl/features/normal_3d_omp.h>//计算点云法线曲率特征
#include <pcl/filters/conditional_removal.h>//条件滤波器
#include <pcl/segmentation/extract_clusters.h>//根据点云索引提取对应的点云
#include <pcl/features/don.h>//基于不同领域半径估计的 法线的差异类
#include <pcl/segmentation/supervoxel_clustering.h>
using namespace pcl;
using namespace std;

int
main (int argc, char *argv[])
{
  //small领域半径 The smallest scale to use in the DoN filter.
  double scale1;

  //大领域半径 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 largescale threshold segradius" << 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

  // Load cloud in blob format
  pcl::PCLPointCloud2 blob;
  pcl::io::loadPCDFile (infile.c_str (), blob);
  pcl::PointCloud<PointXYZRGB>::Ptr cloud (new pcl::PointCloud<PointXYZRGB>);
  pcl::fromPCLPointCloud2 (blob, *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);

  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;
  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 ());
  
// 估计small领域半径 r_s 下的 法线 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);

  // 估计大领域半径 r_l 下的 法线  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);

  // 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 initialize DoN feature operator" << std::endl;
    exit (EXIT_FAILURE);
  }
  // Compute DoN
  don.computeFeature (*doncloud);

  // Save DoN features
  pcl::PCDWriter writer;
  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))
                             );
  // Build the filter
  // pcl::ConditionalRemoval<PointNormal> condrem(*range_cond);
  pcl::ConditionalRemoval<PointNormal> condrem;//创建条件滤波器
  condrem.setCondition (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;
  writer.write<pcl::PointNormal> ("don_filtered.pcd", *doncloud, false); 

  // 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);

  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);
  }
}

9.超体聚类是一种图像的分割方法 pcl::SupervoxelClustering

超体聚类  
超体聚类是一种图像的分割方法。

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

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

超体聚类实际上是一种特殊的区域生长算法,和无限制的生长不同,
超体聚类首先需要规律的布置区域生长“晶核”。晶核在空间中实际上是均匀分布的,
并指定晶核距离(Rseed)。再指定粒子距离(Rvoxel)。
再指定最小晶粒(MOV),过小的晶粒需要融入最近的大晶粒。
github

#include <pcl/console/parse.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/segmentation/supervoxel_clustering.h>

//VTK include needed for drawing graph lines
#include <vtkPolyLine.h>

// 数据类型
typedef pcl::PointXYZRGBA PointT;
typedef pcl::PointCloud<PointT> PointCloudT;
typedef pcl::PointNormal PointNT;
typedef pcl::PointCloud<PointNT> PointNCloudT;
typedef pcl::PointXYZL PointLT;
typedef pcl::PointCloud<PointLT> PointLCloudT;

//可视化
void addSupervoxelConnectionsToViewer (PointT &supervoxel_center,
                                       PointCloudT &adjacent_supervoxel_centers,
                                       std::string supervoxel_name,
                                       boost::shared_ptr<pcl::visualization::PCLVisualizer> & viewer);


int
main (int argc, char ** argv)
{
//解析命令行
 // if (argc < 2)
 // {
    pcl::console::print_error ("Syntax is: %s <pcd-file> \n "
                                "--NT Dsables the single cloud transform \n"
                                "-v <voxel resolution>\n-s <seed resolution>\n"
                                "-c <color weight> \n-z <spatial weight> \n"
                                "-n <normal_weight>\n", argv[0]);
  //  return (1);
  //}

  //打开点云
  PointCloudT::Ptr cloud = boost::shared_ptr <PointCloudT> (new PointCloudT ());
  pcl::console::print_highlight ("Loading point cloud...\n");
  if (pcl::io::loadPCDFile<PointT> ("../milk_cartoon_all_small_clorox.pcd", *cloud))
  {
    pcl::console::print_error ("Error loading cloud file!\n");
    return (1);
  }


  bool disable_transform = pcl::console::find_switch (argc, argv, "--NT");

  float voxel_resolution = 0.008f;  //分辨率
  bool voxel_res_specified = pcl::console::find_switch (argc, argv, "-v");
  if (voxel_res_specified)
    pcl::console::parse (argc, argv, "-v", voxel_resolution);

  float seed_resolution = 0.1f;
  bool seed_res_specified = pcl::console::find_switch (argc, argv, "-s");
  if (seed_res_specified)
    pcl::console::parse (argc, argv, "-s", seed_resolution);

  float color_importance = 0.2f;
  if (pcl::console::find_switch (argc, argv, "-c"))
    pcl::console::parse (argc, argv, "-c", color_importance);

  float spatial_importance = 0.4f;
  if (pcl::console::find_switch (argc, argv, "-z"))
    pcl::console::parse (argc, argv, "-z", spatial_importance);

  float normal_importance = 1.0f;
  if (pcl::console::find_switch (argc, argv, "-n"))
    pcl::console::parse (argc, argv, "-n", normal_importance);

//如何使用SupervoxelClustering函数
  pcl::SupervoxelClustering<PointT> super (voxel_resolution, seed_resolution);
  if (disable_transform)//如果设置的是参数--NT  就用默认的参数
  super.setUseSingleCameraTransform (false);
  super.setInputCloud (cloud);
  super.setColorImportance (color_importance); //0.2f
  super.setSpatialImportance (spatial_importance); //0.4f
  super.setNormalImportance (normal_importance); //1.0f

  std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr > supervoxel_clusters;

  pcl::console::print_highlight ("Extracting supervoxels!\n");
  super.extract (supervoxel_clusters);
  pcl::console::print_info ("Found %d supervoxels\n", supervoxel_clusters.size ());

  boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
  viewer->setBackgroundColor (0, 0, 0);

  PointCloudT::Ptr voxel_centroid_cloud = super.getVoxelCentroidCloud ();//获得体素中心的点云
  viewer->addPointCloud (voxel_centroid_cloud, "voxel centroids");
  viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE,2.0, "voxel centroids");     //渲染点云
  viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY,0.95, "voxel centroids");

  PointLCloudT::Ptr labeled_voxel_cloud = super.getLabeledVoxelCloud ();
  viewer->addPointCloud (labeled_voxel_cloud, "labeled voxels");
  viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY,0.8, "labeled voxels");

  PointNCloudT::Ptr sv_normal_cloud = super.makeSupervoxelNormalCloud (supervoxel_clusters);

  //We have this disabled so graph is easy to see, uncomment to see supervoxel normals
  //viewer->addPointCloudNormals<PointNormal> (sv_normal_cloud,1,0.05f, "supervoxel_normals");

  pcl::console::print_highlight ("Getting supervoxel adjacency\n");

  std::multimap<uint32_t, uint32_t> supervoxel_adjacency;
  super.getSupervoxelAdjacency (supervoxel_adjacency);
  //To make a graph of the supervoxel adjacency, we need to iterate through the supervoxel adjacency multimap
  //为了使整个超体形成衣服图,我们需要遍历超体的每个临近的个体
  std::multimap<uint32_t,uint32_t>::iterator label_itr = supervoxel_adjacency.begin ();
  for ( ; label_itr != supervoxel_adjacency.end (); )
  {
    //First get the label
    uint32_t supervoxel_label = label_itr->first;
    //Now get the supervoxel corresponding to the label
    pcl::Supervoxel<PointT>::Ptr supervoxel = supervoxel_clusters.at (supervoxel_label);

    //Now we need to iterate through the adjacent supervoxels and make a point cloud of them
    PointCloudT adjacent_supervoxel_centers;
    std::multimap<uint32_t,uint32_t>::iterator adjacent_itr = supervoxel_adjacency.equal_range (supervoxel_label).first;
    for ( ; adjacent_itr!=supervoxel_adjacency.equal_range (supervoxel_label).second; ++adjacent_itr)
    {
      pcl::Supervoxel<PointT>::Ptr neighbor_supervoxel = supervoxel_clusters.at (adjacent_itr->second);
      adjacent_supervoxel_centers.push_back (neighbor_supervoxel->centroid_);
    }
    //Now we make a name for this polygon
    std::stringstream ss;
    ss << "supervoxel_" << supervoxel_label;
    //This function is shown below, but is beyond the scope of this tutorial - basically it just generates a "star" polygon mesh from the points given
//从给定的点云中生成一个星型的多边形,
    addSupervoxelConnectionsToViewer (supervoxel->centroid_, adjacent_supervoxel_centers, ss.str (), viewer);
    //Move iterator forward to next label
    label_itr = supervoxel_adjacency.upper_bound (supervoxel_label);
  }

  while (!viewer->wasStopped ())
  {
    viewer->spinOnce (100);
  }
  return (0);
}

//VTK可视化构成的聚类图
void
addSupervoxelConnectionsToViewer (PointT &supervoxel_center,
                                  PointCloudT &adjacent_supervoxel_centers,
                                  std::string supervoxel_name,
                                  boost::shared_ptr<pcl::visualization::PCLVisualizer> & viewer)
{
  vtkSmartPointer<vtkPoints> points = vtkSmartPointer<vtkPoints>::New ();
  vtkSmartPointer<vtkCellArray> cells = vtkSmartPointer<vtkCellArray>::New ();
  vtkSmartPointer<vtkPolyLine> polyLine = vtkSmartPointer<vtkPolyLine>::New ();

  //Iterate through all adjacent points, and add a center point to adjacent point pair
  PointCloudT::iterator adjacent_itr = adjacent_supervoxel_centers.begin ();
  for ( ; adjacent_itr != adjacent_supervoxel_centers.end (); ++adjacent_itr)
  {
    points->InsertNextPoint (supervoxel_center.data);
    points->InsertNextPoint (adjacent_itr->data);
  }
  // Create a polydata to store everything in
  vtkSmartPointer<vtkPolyData> polyData = vtkSmartPointer<vtkPolyData>::New ();
  // Add the points to the dataset
  polyData->SetPoints (points);
  polyLine->GetPointIds  ()->SetNumberOfIds(points->GetNumberOfPoints ());
  for(unsigned int i = 0; i < points->GetNumberOfPoints (); i++)
    polyLine->GetPointIds ()->SetId (i,i);
  cells->InsertNextCell (polyLine);
  // Add the lines to the dataset
  polyData->SetLines (cells);
  viewer->addModelFromPolyData (polyData,supervoxel_name);
}

10.使用渐进式形态学滤波器 识别地面

pcl::ProgressiveMorphologicalFilter


github
#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>

int
main(int argc, char** argv)
{
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
    pcl::PointIndicesPtr ground(new pcl::PointIndices);

    pcl::PCDReader reader;
    reader.read<pcl::PointXYZ>("../samp11-utm.pcd", *cloud);

    std::cerr << "Cloud before filtering: " << std::endl;
    std::cerr << *cloud << std::endl;

    // 创建形态学滤波器对象
    pcl::ProgressiveMorphologicalFilter<pcl::PointXYZ> pmf;
    pmf.setInputCloud(cloud);
    // 设置过滤点最大的窗口尺寸
    pmf.setMaxWindowSize(20);
    // 设置计算高度阈值的斜率值
    pmf.setSlope(1.0f);
    // 设置初始高度参数被认为是地面点
    pmf.setInitialDistance(0.5f);
    // 设置被认为是地面点的最大高度
    pmf.setMaxDistance(3.0f);
    pmf.extract(ground->indices);

    //根据点云索引提取对应的点云
    pcl::ExtractIndices<pcl::PointXYZ> extract;
    extract.setInputCloud(cloud);
    extract.setIndices(ground);
    extract.filter(*cloud_filtered);

    std::cerr << "Ground cloud after filtering: " << std::endl;
    std::cerr << *cloud_filtered << std::endl;

    pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_filtered_RGB(new pcl::PointCloud<pcl::PointXYZRGB>);
    cloud_filtered_RGB->resize(cloud_filtered->size());
    cloud_filtered_RGB->is_dense = false;

    for (size_t i = 0 ; i < cloud_filtered->points.size() ; ++i)
    {
        cloud_filtered_RGB->points[i].x = cloud_filtered->points[i].x;
        cloud_filtered_RGB->points[i].y = cloud_filtered->points[i].y;
        cloud_filtered_RGB->points[i].z = cloud_filtered->points[i].z;

        cloud_filtered_RGB->points[i].r = 0;
        cloud_filtered_RGB->points[i].g = 255;
        cloud_filtered_RGB->points[i].b = 0;
    }

    pcl::io::savePCDFileBinary("cloud_groud.pcd", *cloud_filtered_RGB);

    // 提取非地面点
    extract.setNegative(true);
    extract.filter(*cloud_filtered);

    std::cerr << "Object cloud after filtering: " << std::endl;
    std::cerr << *cloud_filtered << std::endl;

    pcl::io::savePCDFileBinary("No_groud.pcd", *cloud_filtered);

    return (0);
}


猜你喜欢

转载自blog.csdn.net/xiaoxiaowenqiang/article/details/79873816