无序点云的快速三角化:
本教程解释了如何在点云上运行一个带有法线的greedy surface triangulation algorithm贪婪曲面三角剖分算法,以获得一个基于局部邻域投影的 triangle mesh 三角形网格。
背景: 算法 和 参数
该方法的工作方式是维护一个可以生长mesh网格的 list of points 点的列表(“fringe 边缘” 点),并拓展它, 直到所有可能的点都连接起来。 它可以处理来自一个或多个扫描线的 unorganized points,并有多个连接部分。 如果表面局部光滑, 且不同点密度的区域之间存在平滑过渡,则效果最好。
triangulation三角化是在局部进行的,通过沿着点的法线投影点的局部邻域,并将未连接的点连接起来。因此,可以设置以下参数:
setMaximumNearestNeighbors( unsigned ) 和 setMu( double )控制邻域的大小。前者定义了搜索的最近邻点数量,而后者指定了,相对最近邻点距离(为了适应密度的变化)的,考虑一个点的最大可接受距离。典型值为50-100 和 2.5-3(对于grids网格来说是1.5)。
setSearchRadius( double )设置实际上每个三角形的最大边长。这必须由用户设置,以便确定可能的最大三角形。
setMinimumAngle( double ) 和 setMaximumAngle( double ) 设置每个三角形的最小和最大角度。虽然前者无法保证,但后者可以。典型的值时10弧度~120弧度
setMaximumSurfaceAgle( double ) 和 setNormalConsistency( bool )用于处理有尖锐边缘或角的情况,以及一个表面的两边非常接近的情况。为了实现这一点,如果点的法线偏离的角度大于指定的角度,则不连接到当前点(请注意,大多数表面法线估计方法往往在尖锐的边缘处,法线角度之间会产生平滑的过渡)。如果不设置法线方向标志,则此角度计算为(不考虑法线方向)法线定义的线之间的角度,因为不是所有的法线估计方向都能保证法线方向一致。通常情况下,45度(radians)和false对大多数数据集有效。
请看下面的example例子,你可以参考下面的论文和参考文献来了解更多的细节:
@InProceedings{Marton09ICRA, author = {Zoltan Csaba Marton and Radu Bogdan Rusu and Michael Beetz}, title = {{On Fast Surface Reconstruction Methods for Large and Noisy Datasets}}, booktitle = {Proceedings of the IEEE International Conference on Robotics and Automation (ICRA)}, month = {May 12-17}, year = {2009}, address = {Kobe, Japan}, }
代码:
首先,创建一个文件,比如说,greedy_projection.cpp 在你最爱的编辑器,然后在其中写入下面的代码:
#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> 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>); pcl::PCLPointCloud2 cloud_blob; pcl::io::loadPCDFile ("bun0.pcd", cloud_blob); pcl::fromPCLPointCloud2 (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* 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); // Get result gp3.setInputCloud (cloud_with_normals); gp3.setSearchMethod (tree2); gp3.reconstruct (triangles); // Additional vertex information std::vector<int> parts = gp3.getPartIDs(); std::vector<int> states = gp3.getPointStates(); // Finish return (0); }
输入文件在pcl源码目录 pcl/test/bun0.pcd。
解释:
现在,我们开始逐块解析代码。
// Load input file into a PointCloud<T> with an appropriate type pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>); pcl::PCLPointCloud2 cloud_blob; pcl::io::loadPCDFile ("bun0.pcd", cloud_blob); pcl::fromPCLPointCloud2 (cloud_blob, *cloud); //* the data should be available in cloud
因为样本PCD文件中仅有XYZ坐标,我们使用 PointCloud<PointXYZ>来存储它。
// 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
这个方法要求法线,因此使用PCL中的标准方估计法线。
// Concatenate the XYZ and normal fields* 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
因为坐标和法线需要在同一个PointCloud中,我们使用 PointNormal类型来存储点云
// 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);
如上所述,上述行设置参数。
// Get result gp3.setInputCloud (cloud_with_normals); gp3.setSearchMethod (tree2); gp3.reconstruct (triangles);
上面的行设置输入对象并执行实际的triangulation三角化。
// Additional vertex information
std::vector<int> parts = gp3.getPartIDs();
std::vector<int> states = gp3.getPointStates();
对于每个点,包含连接组件的ID及其“状态”( i.e. gp3.FREE, gp3.BOUNDARY or gp3.COMPLETED) 能够被检索
保存和可视化结果:
你可以查看平滑的点云,例如通过保存到一个VTK文件。
#include <pcl/io/vtk_io.h>
....
pcl::io::saveVTKFile ("mesh.vtk", triangles);