PCL_13---点云曲面重建

标题

  • 相关算法
  • 入门实验
    • 多项式平滑点云及法线估计的曲面重建
    • 在平面模型上构建凹/凸多边形
    • 无序点云快速三角化

相关算法

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

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

入门实验

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

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

  • 代码
#include 
#include 
#include 
//#include 
#include                       //移动最小二乘法平滑处理头文件

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_13---点云曲面重建_第1张图片
    处理后:
    PCL_13---点云曲面重建_第2张图片
    看颜色应该是平滑处理了吧。

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

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

  • 代码
#include 
#include 
#include 
#include 
#include 
#include 
#include 
#include 
#include 

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.

原始点云
PCL_13---点云曲面重建_第3张图片
提取后点云边界
PCL_13---点云曲面重建_第4张图片

无序点云快速三角化

  • 代码
    大部分都已经很清楚了,就不注释了。
#include 
#include 
#include 
#include 
#include 
#include 
#include 
#include 


int main (int argc, char** argv)
{
  // Load input file into a PointCloud 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 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
    PCL_13---点云曲面重建_第5张图片
    贪婪投影三角化后的网格.vtk
    PCL_13---点云曲面重建_第6张图片

你可能感兴趣的:(雨露均沾的知识)