PCL_13---点云曲面重建

相关算法

  • 凸包算法
  • Ear Clipping 三角化算法
  • 贪婪投影三角化算法
  • 移动立方体算法
  • 泊松曲面重建算法

pcl中的surface模块:17个类、2个函数。

入门实验

多项式平滑点云及法线估计的曲面重建

重采样、平滑方法:移动最小二乘法。
目的:使法线方向更准确,曲率特征方差更小。

  • 代码
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/search/kdtree.h>
//#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/surface/mls.h>                      //移动最小二乘法平滑处理头文件

int main (int argc, char** argv)
{
  // 将一个适当类型的输入文件加载到对象PointCloud中
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ> ());
  // 加载bun0.pcd文件,加载的文件在 PCL的测试数据中是存在的 
  pcl::io::loadPCDFile ("table_scene_lms400_downsampled.pcd", *cloud);
  // 创建一个KD树
  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
  // 输出文件中有PointNormal类型,用来存储移动最小二乘法算出的法线
  pcl::PointCloud<pcl::PointNormal> mls_points;
  // 定义对象 (第二种定义类型是为了存储法线, 即使用不到也需要定义出来)
  pcl::MovingLeastSquares<pcl::PointXYZ, pcl::PointNormal> mls;
  mls.setComputeNormals (true);       //设置需要进行法线估计
  //设置参数
  mls.setInputCloud (cloud);
 // mls.setPolynomialFit (true);              //采用多项式拟合来提高精度
  mls.setPolynomialOrder (2);
  mls.setSearchMethod (tree);
  mls.setSearchRadius (0.03);
  // 曲面重建
  mls.process (mls_points);
  // 保存结果
  pcl::io::savePCDFile ("bun0-mls.pcd", mls_points);
}	

注:教程里应该是<pcl/search/kdtree.h>

  • 实验结果
    处理前:
    在这里插入图片描述
    处理后:
    在这里插入图片描述
    看颜色应该是平滑处理了吧。

在平面模型上构建凹/凸多边形

就是提取多边形边界,本实验实现凹多边形构建。

  • 代码
#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/filters/passthrough.h>
#include <pcl/filters/project_inliers.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl/surface/concave_hull.h>

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

  reader.read ("table_scene_mug_stereo_textured.pcd", *cloud);
  // Build a filter to remove spurious NaNs 消除杂散的NaN
  pcl::PassThrough<pcl::PointXYZ> pass;
  pass.setInputCloud (cloud);
  pass.setFilterFieldName ("z");
  pass.setFilterLimits (0, 1.1);
  pass.filter (*cloud_filtered);
  std::cerr << "PointCloud after filtering has: "
            << cloud_filtered->points.size () << " data points." << std::endl;

  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);  //模型系数对象指针
  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);                 //存储分割后的点云索引对象指针
  // Create the segmentation object
  pcl::SACSegmentation<pcl::PointXYZ> seg;
  // Optional
  seg.setOptimizeCoefficients (true);                                     //优化系数
  // Mandatory
  seg.setModelType (pcl::SACMODEL_PLANE);                                 //模型类型-平面
  seg.setMethodType (pcl::SAC_RANSAC);                                    //方法类型-随机采样一致性
  seg.setDistanceThreshold (0.01);                                        //距离阈值

  seg.setInputCloud (cloud_filtered);
  seg.segment (*inliers, *coefficients);                                  //执行分割 输出内点索引和模型系数
  std::cerr << "PointCloud after segmentation has: "
            << inliers->indices.size () << " inliers." << std::endl;

  // Project the model inliers  投影
  pcl::ProjectInliers<pcl::PointXYZ> proj;                                //投影滤波对象                    
  proj.setModelType (pcl::SACMODEL_PLANE);                                //要投影模型
  proj.setInputCloud (cloud_filtered); 
  proj.setModelCoefficients (coefficients);                               //设置估计的模型系数
  proj.filter (*cloud_projected);                                         //执行投影 将cloud_filtered投影到平面模型
  std::cerr << "PointCloud after projection has: "
            << cloud_projected->points.size () << " data points." << std::endl;

  // Create a Concave Hull representation of the projected inliers
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_hull (new pcl::PointCloud<pcl::PointXYZ>);  
  pcl::ConcaveHull<pcl::PointXYZ> chull;                                                //凹边形对象
  chull.setInputCloud (cloud_projected);
  chull.setAlpha (0.1);                                                                 //设定参数
  chull.reconstruct (*cloud_hull);                                                      //重建提取创建凹多边形

  std::cerr << "Concave hull has: " << cloud_hull->points.size ()
            << " data points." << std::endl;

  pcl::PCDWriter writer;
  writer.write ("table_scene_mug_stereo_textured_hull.pcd", *cloud_hull, false);

  return 0;
}
  • 实验结果
PointCloud after filtering has: 139656 data points.
PointCloud after segmentation has: 123727 inliers.
PointCloud after projection has: 139656 data points.//因为不在平面的点也被投影,包含在内,和cloud_filtered点云大小一样
Concave hull has: 457 data points.

原始点云
在这里插入图片描述
提取后点云边界
在这里插入图片描述

无序点云快速三角化

  • 代码
    大部分都已经很清楚了,就不注释了。
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/features/normal_3d.h>
#include <pcl/surface/gp3.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <boost/thread/thread.hpp>
#include <pcl/io/vtk_io.h>


int main (int argc, char** argv)
{
  // Load input file into a PointCloud<T> with an appropriate type
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
  //sensor_msgs::PointCloud2 cloud_blob;
  pcl::io::loadPCDFile ("table_scene_lms400_downsampled.pcd", *cloud);
  //pcl::fromROSMsg (cloud_blob, *cloud);
  //* the data should be available in cloud

  // Normal estimation*
  pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> n;
  pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
  tree->setInputCloud (cloud);
  n.setInputCloud (cloud);
  n.setSearchMethod (tree);
  n.setKSearch (20);
  n.compute (*normals);
  //* normals should not contain the point normals + surface curvatures

  // Concatenate the XYZ and normal fields* 连接 XYZ 和 Normal 为一个点云
  pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals (new pcl::PointCloud<pcl::PointNormal>);
  pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
  //* cloud_with_normals = cloud + normals

  // Create search tree*
  pcl::search::KdTree<pcl::PointNormal>::Ptr tree2 (new pcl::search::KdTree<pcl::PointNormal>);
  tree2->setInputCloud (cloud_with_normals);

  // Initialize objects
  pcl::GreedyProjectionTriangulation<pcl::PointNormal> gp3;   //定义贪婪投影三角化对象
  pcl::PolygonMesh triangles;                                 //存储最终三角化的网格模型

  // Set the maximum distance between connected points (maximum edge length)
  gp3.setSearchRadius (0.025);                                //设置连接点之间最大距离

  // Set typical values for the parameters
  gp3.setMu (2.5);                                            //设置被样本点搜索其邻近点的最远距离
  gp3.setMaximumNearestNeighbors (100);                       //设置样本点可搜索的邻域个数
  gp3.setMaximumSurfaceAngle(M_PI/4);                         //某点法线方向偏离样本点法线方向最大角度 45 degrees
  gp3.setMinimumAngle(M_PI/18);                               //三角化后三角形内角最小角度 10 degrees
  gp3.setMaximumAngle(2*M_PI/3);                              //三角化后三角形内角最大角度 120 degrees
  gp3.setNormalConsistency(false);                            //输入的法线方向是否一致 false:那就保证它一致 true:那就不管了

  // Get result
  gp3.setInputCloud (cloud_with_normals);
  gp3.setSearchMethod (tree2);
  gp3.reconstruct (triangles);                                //重建提取三角化
 // std::cout << triangles;
  // Additional vertex information
  std::vector<int> parts = gp3.getPartIDs();                  //获取ID字段
  std::vector<int> states = gp3.getPointStates();             //获取点状态

  //可视化
  /*
  boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
  viewer->setBackgroundColor (0, 0, 0);
  viewer->addPolygonMesh(triangles,"my");
 
  viewer->addCoordinateSystem (1.0);
  viewer->initCameraParameters ();
   // 主循环
  while (!viewer->wasStopped ())
  {
    viewer->spinOnce (100);
    boost::this_thread::sleep (boost::posix_time::microseconds (100000));
  }
  */

  //存为VTK文件
  pcl::io::saveVTKFile("mesh.vtk", triangles);

  // Finish
  return (0);
}
  • 实验结果
    原始点云.pcd
    在这里插入图片描述
    贪婪投影三角化后的网格.vtk
    在这里插入图片描述
  • 4
    点赞
  • 30
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
PCL(Point Cloud Library)是一个开源的计算机视觉库,其中内置了许多点云处理的算法,包括点云曲面重建点云曲面重建是将无序的点云数据转换为连续的曲面模型,常用于三维建模、机器人视觉导航、医学图像处理等领域。PCL提供了多种点云曲面重建算法,包括基于网格的方法和基于隐式曲面的方法。本文将介绍其中的一种基于网格的方法——Poisson重建。 Poisson重建算法的基本思想是,利用点云数据构建一个无向加权图,并将重建曲面模型视为该图的等势面。在该图上进行拉普拉斯平滑,得到的曲面为最小化拉普拉斯能量的解。 下面是Poisson重建的具体步骤: 1. 对点云进行预处理,去除离群点、滤波、下采样等操作,以减少噪声和计算量。 2. 构建点云的法向量估计算法。Poisson重建算法需要法向量信息作为重建的基础,PCL提供了多种法向量估计算法,如基于协方差矩阵的法向量估计、基于法向量的一致性检测等。 3. 构建无向加权图。Poisson重建算法将点云数据视为一个无向加权图,其中每个点表示一个顶点,每个点之间根据一定的规则连接一条边,边权重表示两个点之间的相似度。PCL中常用的连接规则为K近邻和半径搜索。 4. 执行Poisson重建算法。在无向加权图上进行拉普拉斯平滑,得到的曲面为最小化拉普拉斯能量的解。Poisson重建算法还可以对结果进行后处理,如光滑、去除孔洞等。 下面是Poisson重建算法的Python实现代码: ``` import pcl # 加载点云数据 cloud = pcl.load('input_cloud.pcd') # 预处理 cloud_filtered = cloud.make_statistical_outlier_filter().filter() cloud_downsampled = cloud_filtered.make_voxel_grid_filter().filter() cloud_normals = cloud_downsampled.make_normal_estimation().compute() # 构建无向加权图 search_tree = cloud_downsampled.make_kdtree() mls = cloud_downsampled.make_moving_least_squares() mls.set_search_radius(0.1) mls.set_polynomial_order(2) mls.set_upsampling_method(pcl.MovingLeastSquares.NONE) cloud_smoothed = mls.process() poisson = cloud_smoothed.make_poisson_reconstruction() poisson.set_depth(9) poisson.set_iso_divide(8) poisson.set_point_weight(4) poisson.set_samples_per_node(1.5) poisson.set_confidence(false) poisson.set_output_polygons(true) reconstructed = poisson.reconstruct() ``` 其中,'input_cloud.pcd'为点云数据文件名,需要先使用PCL进行格式转换。以上代码仅为示例,具体参数需要根据实际应用场景进行调整。

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值