PCL_6---点云滤波

经典滤波算法:

  • 双边滤波
  • 高斯滤波
  • 条件滤波
  • 直通滤波
  • 基于随机采样一致性滤波

1、对点云进行滤波—直通滤波器

代码

#include <iostream>
#include <ctime>
#include <pcl/point_types.h>
#include <pcl/filters/passthrough.h>

int
 main (int argc, char** argv)
{ 
  srand(time(0));//种个种子
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);               //原始点云
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>);      //滤波后点云
  //填入原始点云数据
  cloud->width  = 5;
  cloud->height = 1;
  cloud->points.resize (cloud->width * cloud->height);
  for (size_t i = 0; i < cloud->points.size (); ++i)
  {
    cloud->points[i].x = rand () / (RAND_MAX + 1.0f)-0.5;
    cloud->points[i].y = rand () / (RAND_MAX + 1.0f)-0.5;
    cloud->points[i].z = rand () / (RAND_MAX + 1.0f)-0.5;
  }
  std::cerr << "Cloud before filtering: " << 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::PassThrough<pcl::PointXYZ> pass;         //设置滤波器对象
  pass.setInputCloud (cloud);                   //设置输入点云
  pass.setFilterFieldName ("z");                //设置滤波字段名儿为z轴方向
  pass.setFilterLimits (0.0, 1.0);              //设置在过滤字段上的范围
  pass.setFilterLimitsNegative (false);          //true--过滤掉范围内 false--设置保留范围内(默认)
  pass.filter (*cloud_filtered);                //执行过滤 保存过滤结果在cloud_filtered

  std::cerr << "Cloud after filtering: " << std::endl;
  for (size_t i = 0; i < cloud_filtered->points.size (); ++i)
    std::cerr << "    " << cloud_filtered->points[i].x << " " 
                        << cloud_filtered->points[i].y << " " 
                        << cloud_filtered->points[i].z << std::endl;
  return (0);
}

实验结果

  • 过滤z[0,1]外的点云
Cloud before filtering:
    -0.233795 0.146362 0.438141
    0.216827 -0.433472 0.0162048
    0.00241089 0.0435181 0.404877
    -0.0850525 -0.0426636 -0.452515
    -0.180054 -0.210419 0.27298
Cloud after filtering:
    -0.233795 0.146362 0.438141
    0.216827 -0.433472 0.0162048
    0.00241089 0.0435181 0.404877
    -0.180054 -0.210419 0.27298
  • 过滤z[0,1]内的点云
Cloud before filtering:
    -0.160645 -0.0903931 -0.406158
    0.232697 -0.388 -0.0254211
    -0.278992 0.47287 0.262909
    0.198822 -0.355743 -0.465881
    -0.271423 0.425659 0.375244
Cloud after filtering:
    -0.160645 -0.0903931 -0.406158
    0.232697 -0.388 -0.0254211
    0.198822 -0.355743 -0.465881

2、对点云进行下采样—VoxelGrid滤波器

代码

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/filters/voxel_grid.h>

int
main(int argc, char** argv)
{
    pcl::PCLPointCloud2::Ptr cloud(new pcl::PCLPointCloud2());
    pcl::PCLPointCloud2::Ptr cloud_filtered(new pcl::PCLPointCloud2());

    // 读取点云数据
    pcl::PCDReader reader;
    reader.read("table_scene_lms400.pcd", *cloud); //点云读取对象
    std::cerr << "PointCloud before filtering: " << cloud->width * cloud->height
        << " data points (" << pcl::getFieldsList(*cloud) << ")." << std::endl;

    // Create the filtering object
    pcl::VoxelGrid<pcl::PCLPointCloud2> sor;        //创建滤波对象
    sor.setInputCloud(cloud);                       //将点云加入到滤波器中
    sor.setLeafSize(0.01f, 0.01f, 0.01f);           //设置滤波时创建的体素大小
    sor.filter(*cloud_filtered);                    //执行滤波 存到cloud_filtered

    std::cerr << "PointCloud after filtering: " << cloud_filtered->width * cloud_filtered->height
        << " data points (" << pcl::getFieldsList(*cloud_filtered) << ")." << std::endl;

    // 写入点云数据
    pcl::PCDWriter writer;
    writer.write("table_scene_lms400_downsampled.pcd", *cloud_filtered,
        Eigen::Vector4f::Zero(), Eigen::Quaternionf::Identity(), false);

    return (0);
}

实验结果

对比滤波前后的数据量,确实过滤掉一部分点。

PointCloud before filtering: 460400 data points (x y z intensity distance sid).
PointCloud after filtering: 41049 data points (x y z intensity distance sid).
  • 滤波前
    在这里插入图片描述

  • 滤波后
    感觉点云真的精简了
    在这里插入图片描述

3、移除离群点—StatisticalOutlierRemoval滤波器(高斯滤波器)

就是对每个点统计分析,看看这个点是不是合群,不合群踢掉。

代码

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/filters/statistical_outlier_removal.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::PCDReader reader;										//定义读取对象 
  reader.read<pcl::PointXYZ> ("table_scene_lms400.pcd", *cloud);//读取点云文件
  std::cerr << "Cloud before filtering: " << std::endl;
  std::cerr << *cloud << std::endl;

  // 创建滤波器对象
  pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;			//创建滤波器对象
  sor.setInputCloud (cloud);									//把点云数据放进滤波器
  sor.setMeanK (50);											//统计时,每个点分析的临近点个数 50
  sor.setStddevMulThresh (1.0);									//标准差倍数设置为1  [alpha-delta,alpha+delta] 想象高斯分布那个图
  sor.filter (*cloud_filtered);									//执行滤波 保存到cloud_filtered
  std::cerr << "Cloud after filtering: " << std::endl;
  std::cerr << *cloud_filtered << std::endl;

  // 写点云数据 false:ASCII true:binary
  pcl::PCDWriter writer;
  writer.write<pcl::PointXYZ> ("table_scene_lms400_inliers.pcd", *cloud_filtered, false);
  sor.setNegative (true);										//设置取范围外的点 胳臂肘往外拐
  sor.filter (*cloud_filtered);
  writer.write<pcl::PointXYZ> ("table_scene_lms400_outliers.pcd", *cloud_filtered, false);

  return (0);
}

实验结果

  • 数据对比
    滤波前数据量:460400
    滤波后数据量:451410
Cloud before filtering:
header: seq: 0 stamp: 0 frame_id:

points[]: 460400
width: 460400
height: 1
is_dense: 1
sensor origin (xyz): [0, 0, 0] / orientation (xyzw): [0, 0, 0, 1]

Cloud after filtering:
header: seq: 0 stamp: 0 frame_id:

points[]: 451410
width: 451410
height: 1
is_dense: 1
sensor origin (xyz): [0, 0, 0] / orientation (xyzw): [0, 0, 0, 1]
  • (左图)滤波后保留内点 — 高斯分布中间
    (右图)滤波后保留外点,离群点 — 高斯分布两边儿
    在这里插入图片描述

4、参数化模型投影点云—投影滤波器

代码

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/ModelCoefficients.h>          //模型系数定义头文件
#include <pcl/filters/project_inliers.h>    //投影滤波类头文件

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

  // 填入点云数据 5个 前边儿学过这里不详细说了 都懂
  cloud->width  = 5;
  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 = 1024 * rand () / (RAND_MAX + 1.0f);
  }
  std::cerr << "Cloud before projection: " << 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;

  // 创建一个系数为X=Y=0,Z=1的平面 (ax+by+cz+d=0 a=b=d=0 c=1 ) 也可以定义圆球、圆柱、锥形
  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ()); //定义模型系数对象
  coefficients->values.resize (4);                                          //设置4个系数 并赋值
  coefficients->values[0] = coefficients->values[1] = 0;  
  coefficients->values[2] = 1.0;
  coefficients->values[3] = 0;

  // 创建滤波器对象
  pcl::ProjectInliers<pcl::PointXYZ> proj;          //创建投影滤波对象
  proj.setModelType (pcl::SACMODEL_PLANE);          //设置对象对应的投影模型 平面
  proj.setInputCloud (cloud);                       //把刚才的点云也投放进去
  proj.setModelCoefficients (coefficients);         //把刚才的平面模型投放进去
  proj.filter (*cloud_projected);                   //执行头像滤波 存储为cloud_projected
  std::cerr << "Cloud after projection: " << std::endl;
  for (size_t i = 0; i < cloud_projected->points.size (); ++i)
    std::cerr << "    " << cloud_projected->points[i].x << " " 
                        << cloud_projected->points[i].y << " " 
                        << cloud_projected->points[i].z << std::endl;

  return (0);
}

实验结果

5个点投影到了z=0的平面。

Cloud before projection:
    1.28125 577.094 197.938
    828.125 599.031 491.375
    358.688 917.438 842.562
    764.5 178.281 879.531
    727.531 525.844 311.281
Cloud after projection:
    1.28125 577.094 0
    828.125 599.031 0
    358.688 917.438 0
    764.5 178.281 0
    727.531 525.844 0

5、从一个点云中提取一个子集—ExtractIndices滤波器

代码

#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/filters/voxel_grid.h>
#include <pcl/filters/extract_indices.h>

int
main(int argc, char** argv)
{
    //定义多个点云对象
    pcl::PCLPointCloud2::Ptr cloud_blob(new pcl::PCLPointCloud2), cloud_filtered_blob(new pcl::PCLPointCloud2);
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>), cloud_p(new pcl::PointCloud<pcl::PointXYZ>), cloud_f(new pcl::PointCloud<pcl::PointXYZ>);

    // Fill in the cloud data
    pcl::PCDReader reader;
    reader.read("table_scene_lms400.pcd", *cloud_blob);         //先读个初始点云数据
    std::cerr << "PointCloud before filtering: " << cloud_blob->width * cloud_blob->height << " data points." << std::endl;

    // Create the filtering object: downsample the dataset using a leaf size of 1cm
    //先下采样 加速后边儿的处理过程
    pcl::VoxelGrid<pcl::PCLPointCloud2> sor;    //体素栅格下采样对象
    sor.setInputCloud(cloud_blob);              //把初始点云放进去
    sor.setLeafSize(0.01f, 0.01f, 0.01f);       //设置滤波时的体素大小
    sor.filter(*cloud_filtered_blob);           //执行滤波 存储给cloud_filtered_blob

    // Convert to the templated PointCloud
    //下采样完了 传给cloud_filtered展示一下吧
    pcl::fromPCLPointCloud2(*cloud_filtered_blob, *cloud_filtered);
    std::cerr << "PointCloud after filtering: " << cloud_filtered->width * cloud_filtered->height << " data points." << std::endl;
    // Write the downsampled version to disk
    pcl::PCDWriter writer;
    writer.write<pcl::PointXYZ>("table_scene_lms400_downsampled.pcd", *cloud_filtered, false);

    //分割部分暂不了解 后边儿章节会详细说明
    pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
    pcl::PointIndices::Ptr inliers(new pcl::PointIndices());     
    pcl::SACSegmentation<pcl::PointXYZ> seg;                        //创建分割对象
    seg.setOptimizeCoefficients(true);                              //设置对估计的模型参数进行优化处理
    seg.setModelType(pcl::SACMODEL_PLANE);                          //设置分割模型类别
    seg.setMethodType(pcl::SAC_RANSAC);                             //设置用哪个随机参数估计方法
    seg.setMaxIterations(1000);                                     //设置最大迭代次数
    seg.setDistanceThreshold(0.01);                                 //设置判断是否为模型内点的距离阈值

    pcl::ExtractIndices<pcl::PointXYZ> extract;                     //创建点云提取对象
    int i = 0, nr_points = (int)cloud_filtered->size();
    // While 30% of the original cloud is still there
    //小于30%时停止迭代
    while (cloud_filtered->size() > 0.3 * nr_points)
    {
        // Segment the largest planar component from the remaining cloud
        seg.setInputCloud(cloud_filtered);          //给分割对象输入点云
        seg.segment(*inliers, *coefficients);       //按照模型分割
        if (inliers->indices.size() == 0)
        {
            std::cerr << "Could not estimate a planar model for the given dataset." << std::endl;
            break;
        }

        // Extract the inliers
        extract.setInputCloud(cloud_filtered);      //设置输入点云
        extract.setIndices(inliers);                //设置分割后的内点为需要提取的对象
        extract.setNegative(false);                 //是否叛变 不 设置提取内点
        extract.filter(*cloud_p);                   //执行提取 存到cloud_p
        std::cerr << "PointCloud representing the planar component: " << cloud_p->width * cloud_p->height << " data points." << std::endl;

        std::stringstream ss;                       //字符串流
        ss << "table_scene_lms400_plane_" << i << ".pcd";
        writer.write<pcl::PointXYZ>(ss.str(), *cloud_p, false); //ASCII形式写点云数据

        // Create the filtering object
        extract.setNegative(true);
        extract.filter(*cloud_f);                   //提取外点 存给cloud_f
        cloud_filtered.swap(cloud_f);               //cloud_f将cloud_filtered更新 继续迭代 ??原来cloud_f是工具人
        i++;
    }

    return (0);
}

实验结果

//原始点云
PointCloud before filtering: 460400 data points.
//下采样后
PointCloud after filtering: 41049 data points.
//第一次迭代
PointCloud representing the planar component: 20161 data points.
//第二次迭代
PointCloud representing the planar component: 12114 data points.
  • 下采样后(左图),第一次迭代后(右图)
    在这里插入图片描述

  • 下采样后(左图),第二次迭代后(右图)
    在这里插入图片描述
    太神奇了,这是怎么提取的,害,或许,,,学到后边儿分割那一章就知道了。

6、移除离群点—ConditionalRemoval/RadiusOutlierRemoval滤波器

代码

#include <iostream>
#include <pcl/point_types.h>
#include <pcl/filters/radius_outlier_removal.h>
#include <pcl/filters/conditional_removal.h>
int
 main (int argc, char** argv)
{
  if (argc != 2)
  {
    std::cerr << "please specify command line arg '-r' or '-c'" << std::endl;
    exit(0);
  }
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>);
  // 填入点云数据
  cloud->width  = 5;
  cloud->height = 1;
  cloud->points.resize (cloud->width * cloud->height);
  for (size_t i = 0; i < cloud->points.size (); ++i)
  {
    cloud->points[i].x = rand () / (RAND_MAX + 1.0f);
    cloud->points[i].y = rand () / (RAND_MAX + 1.0f);
    cloud->points[i].z = rand () / (RAND_MAX + 1.0f);
  }
  if (strcmp(argv[1], "-r") == 0){                                                      //使用ConditionalRemoval滤波器
    pcl::RadiusOutlierRemoval<pcl::PointXYZ> outrem;                                    //创建半径滤波器对象
    // 创建滤波器
    outrem.setInputCloud(cloud);                                                        //设置输入点云
    outrem.setRadiusSearch(0.6);                                                        //设置在半径0.6半径的范围内找邻近点
    outrem.setMinNeighborsInRadius (2);                                                 //设置查询点的邻近点集数小于2的删除
    outrem.filter (*cloud_filtered);                                                    //执行滤波器 存给cloud_filtered
  }
  else if (strcmp(argv[1], "-c") == 0){                                                 //使用ConditionalRemoval滤波器
    // 创建环境
    pcl::ConditionAnd<pcl::PointXYZ>::Ptr range_cond (new
      pcl::ConditionAnd<pcl::PointXYZ> ());                                             //创建条件定义对象
    range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new
      pcl::FieldComparison<pcl::PointXYZ> ("z", pcl::ComparisonOps::GT, 0.0)));         //为条件对象添加比较算子 添加z字段上大于0的比较算子
    range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new
      pcl::FieldComparison<pcl::PointXYZ> ("z", pcl::ComparisonOps::LT, 0.8)));         //为条件对象添加比较算子 添加z字段上小于0.8的比较算子
    // 创建滤波器
    pcl::ConditionalRemoval<pcl::PointXYZ> condrem;                                     //创建条件滤波器对象
    condrem.setCondition(range_cond);                                                   //设置输入条件对象
    condrem.setInputCloud (cloud);                                                      //设置输入点云
    condrem.setKeepOrganized(true);                                                     //设置保持点云的结构
    condrem.filter (*cloud_filtered);                                                   //执行滤波器 存给cloud_filtered
  }
  else{
    std::cerr << "please specify command line arg '-r' or '-c'" << std::endl;
    exit(0);
  }


  std::cerr << "Cloud before filtering: " << 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;
  // 显示滤波后的点云
  std::cerr << "Cloud after filtering: " << std::endl;
  for (size_t i = 0; i < cloud_filtered->points.size (); ++i)
    std::cerr << "    " << cloud_filtered->points[i].x << " "
                        << cloud_filtered->points[i].y << " "
                        << cloud_filtered->points[i].z << std::endl;
  return (0);
}

实验结果

  • ConditionalRemoval滤波器
Cloud before filtering:
    0.00125122 0.563568 0.193298
    0.808716 0.584991 0.479858
    0.350281 0.895935 0.822815
    0.746582 0.174103 0.858917
    0.71048 0.513519 0.303986
Cloud after filtering:
    0.00125122 0.563568 0.193298
    0.808716 0.584991 0.479858
    nan nan nan
    nan nan nan
    0.71048 0.513519 0.303986
  • RadiusOutlierRemoval滤波器
Cloud before filtering:
    0.00125122 0.563568 0.193298
    0.808716 0.584991 0.479858
    0.350281 0.895935 0.822815
    0.746582 0.174103 0.858917
    0.71048 0.513519 0.303986
Cloud after filtering:
    0.808716 0.584991 0.479858

6、任意多边形提取内部点云—CropHull滤波器

个人理解:用多边形把点云切下来一块儿。

代码

#include <pcl/visualization/cloud_viewer.h>
#include <iostream>
#include <pcl/io/io.h>
#include <pcl/io/pcd_io.h>
#include <vector>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/filters/crop_hull.h>
#include <pcl/surface/concave_hull.h>

int main(int argc, char** argv)
{
	pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
	pcl::PCDReader reader;
	reader.read(argv[1],*cloud);

	//创建点云对象指针 输入2D平面点云
	pcl::PointCloud<pcl::PointXYZ>::Ptr boundingbox_ptr (new pcl::PointCloud<pcl::PointXYZ>);
	boundingbox_ptr->push_back(pcl::PointXYZ(0.1, 0.1, 0));
	boundingbox_ptr->push_back(pcl::PointXYZ(0.1, -0.1,0 ));
	boundingbox_ptr->push_back(pcl::PointXYZ(-0.1, 0.1,0 ));
	boundingbox_ptr->push_back(pcl::PointXYZ(-0.1, -0.1,0 ));
	boundingbox_ptr->push_back(pcl::PointXYZ(0.15, 0.1,0 ));

	//构造2D凸包
	pcl::ConvexHull<pcl::PointXYZ> hull;														//创建凸包对象
	hull.setInputCloud(boundingbox_ptr);														//设置输入点云
	hull.setDimension(2);																		//设置凸包维度
	std::vector<pcl::Vertices> polygons;														//设置向量对象 保存凸包顶点
	pcl::PointCloud<pcl::PointXYZ>::Ptr surface_hull (new pcl::PointCloud<pcl::PointXYZ>);		//创建点云对象指针 用于描述凸包形状
	hull.reconstruct(*surface_hull, polygons);													//计算2D凸包结果

	//CropHull滤波
	pcl::PointCloud<pcl::PointXYZ>::Ptr objects (new pcl::PointCloud<pcl::PointXYZ>);	
	pcl::CropHull<pcl::PointXYZ> bb_filter;														//创建CropHull对象
	bb_filter.setDim(2);																		//设置维度
	bb_filter.setInputCloud(cloud);																//设置需要滤波的点云
	bb_filter.setHullIndices(polygons);															//输入封闭多边形的顶点
	bb_filter.setHullCloud(surface_hull);														//输入封闭多边形的形状
	bb_filter.filter(*objects);																	//执行滤波 存为objects
	std::cout << objects->size() << std::endl;

	//visualize
	boost::shared_ptr<pcl::visualization::PCLVisualizer> for_visualizer_v (new pcl::visualization::PCLVisualizer ("crophull display"));
	for_visualizer_v->setBackgroundColor(255,255,255);

	//原始点云
	int v1(0);
	for_visualizer_v->createViewPort (0.0, 0.0, 0.33, 1, v1);
	for_visualizer_v->setBackgroundColor (255, 255, 255, v1);
	for_visualizer_v->addPointCloud (cloud,"cloud",v1);
	for_visualizer_v->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR,255,0,0,"cloud");
	for_visualizer_v->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,3,"cloud");
	for_visualizer_v->addPolygon<pcl::PointXYZ>(surface_hull,0,.069*255,0.2*255,"backview_hull_polyline1",v1);	//添加多边形

	//凸包多边形形状
	int v2(0);
	for_visualizer_v->createViewPort (0.33, 0.0, 0.66, 1, v2);	
	for_visualizer_v->setBackgroundColor (255, 255, 255, v2);
	for_visualizer_v->addPointCloud (surface_hull,"surface_hull",v2);
	for_visualizer_v->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR,255,0,0,"surface_hull");
	for_visualizer_v->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,8,"surface_hull");
	for_visualizer_v->addPolygon<pcl::PointXYZ>(surface_hull,0,.069*255,0.2*255,"backview_hull_polyline",v2);

	//提取后结果
	int v3(0);
	for_visualizer_v->createViewPort (0.66, 0.0, 1, 1, v3);
	for_visualizer_v->setBackgroundColor (255, 255, 255, v3);
	for_visualizer_v->addPointCloud (objects,"objects",v3);
	for_visualizer_v->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR,255,0,0,"objects");
	for_visualizer_v->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,3,"objects");

	while (!for_visualizer_v->wasStopped())
	{

		for_visualizer_v->spinOnce(1000);
	}
	system("pause");

	return 0;
}

实验结果

就是从猪身上切下来一块儿肉。
在这里插入图片描述

滤波的学习就到这儿,后期用到什么滤波再深究。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值