Fast triangulation of unordered point clouds

This tutorial explains how to run a greedy surface triangulation algorithm on a PointCloud with normals, to obtain a triangle mesh based on projections of the local neighborhoods. An example of the method’s output can be seen here:

Background: algorithm and parameters

The method works by maintaining a list of points from which the mesh can be grown (“fringe” points) and extending it until all possible points are connected. It can deal with unorganized points, coming from one or multiple scans, and having multiple connected parts. It works best if the surface is locally smooth and there are smooth transitions between areas with different point densities.

Triangulation is performed locally, by projecting the local neighborhood of a point along the point’s normal, and connecting unconnected points. Thus, the following parameters can be set:

  • setMaximumNearestNeighbors(unsigned) and setMu(double) control the size of the neighborhood. The former defines how many neighbors are searched for, while the latter specifies the maximum acceptable distance for a point to be considered, relative to the distance of the nearest point (in order to adjust to changing densities). Typical values are 50-100 and 2.5-3 (or 1.5 for grids).

  • setSearchRadius(double) is practically the maximum edge length for every triangle. This has to be set by the user such that to allow for the biggest triangles that should be possible.

  • setMinimumAngle(double) and setMaximumAngle(double) are the minimum and maximum angles in each triangle. While the first is not guaranteed, the second is. Typical values are 10 and 120 degrees (in radians).

  • setMaximumSurfaceAgle(double) and setNormalConsistency(bool) are meant to deal with the cases where there are sharp edges or corners and where two sides of a surface run very close to each other. To achieve this, points are not connected to the current point if their normals deviate more than the specified angle (note that most surface normal estimation methods produce smooth transitions between normal angles even at sharp edges). This angle is computed as the angle between the lines defined by the normals (disregarding the normal’s direction) if the normal-consistency-flag is not set, as not all normal estimation methods can guarantee consistently oriented normals. Typically, 45 degrees (in radians) and false works on most datasets.

Please see the example below, and you can consult the following paper and its references for more details:

@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},
}

The code

First, create a file, let’s say, greedy_projection.cpp in your favorite editor, and place the following code inside it:

 1#include <pcl/point_types.h>
 2#include <pcl/io/pcd_io.h>
 3#include <pcl/search/kdtree.h> // for KdTree
 4#include <pcl/features/normal_3d.h>
 5#include <pcl/surface/gp3.h>
 6
 7int
 8main ()
 9{
10  // Load input file into a PointCloud<T> with an appropriate type
11  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
12  pcl::PCLPointCloud2 cloud_blob;
13  pcl::io::loadPCDFile ("bun0.pcd", cloud_blob);
14  pcl::fromPCLPointCloud2 (cloud_blob, *cloud);
15  //* the data should be available in cloud
16
17  // Normal estimation*
18  pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> n;
19  pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
20  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
21  tree->setInputCloud (cloud);
22  n.setInputCloud (cloud);
23  n.setSearchMethod (tree);
24  n.setKSearch (20);
25  n.compute (*normals);
26  //* normals should not contain the point normals + surface curvatures
27
28  // Concatenate the XYZ and normal fields*
29  pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals (new pcl::PointCloud<pcl::PointNormal>);
30  pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
31  //* cloud_with_normals = cloud + normals
32
33  // Create search tree*
34  pcl::search::KdTree<pcl::PointNormal>::Ptr tree2 (new pcl::search::KdTree<pcl::PointNormal>);
35  tree2->setInputCloud (cloud_with_normals);
36
37  // Initialize objects
38  pcl::GreedyProjectionTriangulation<pcl::PointNormal> gp3;
39  pcl::PolygonMesh triangles;
40
41  // Set the maximum distance between connected points (maximum edge length)
42  gp3.setSearchRadius (0.025);
43
44  // Set typical values for the parameters
45  gp3.setMu (2.5);
46  gp3.setMaximumNearestNeighbors (100);
47  gp3.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
48  gp3.setMinimumAngle(M_PI/18); // 10 degrees
49  gp3.setMaximumAngle(2*M_PI/3); // 120 degrees
50  gp3.setNormalConsistency(false);
51
52  // Get result
53  gp3.setInputCloud (cloud_with_normals);
54  gp3.setSearchMethod (tree2);
55  gp3.reconstruct (triangles);
56
57  // Additional vertex information
58  std::vector<int> parts = gp3.getPartIDs();
59  std::vector<int> states = gp3.getPointStates();
60
61  // Finish
62  return (0);
63}

The input file you can find at pcl/test/bun0.pcd

The explanation

Now, let’s break down the code piece by piece.

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

as the example PCD has only XYZ coordinates, we load it into a 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

the method requires normals, so they are estimated using the standard method from 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

Since coordinates and normals need to be in the same PointCloud, we create a PointNormal type point cloud.

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

The above lines deal with the initialization of the required objects.

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

The above lines set the parameters, as explained above.

  // Get result
  gp3.setInputCloud (cloud_with_normals);
  gp3.setSearchMethod (tree2);
  gp3.reconstruct (triangles);

The lines above set the input objects and perform the actual triangulation.

  // Additional vertex information
  std::vector<int> parts = gp3.getPartIDs();
  std::vector<int> states = gp3.getPointStates();

for each point, the ID of the containing connected component and its “state” (i.e. gp3.FREE, gp3.BOUNDARY or gp3.COMPLETED) can be retrieved.

Compiling and running the program

Add the following lines to your CMakeLists.txt file:

 1cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
 2
 3project(greedy_projection)
 4
 5find_package(PCL 1.2 REQUIRED)
 6
 7include_directories(${PCL_INCLUDE_DIRS})
 8link_directories(${PCL_LIBRARY_DIRS})
 9add_definitions(${PCL_DEFINITIONS})
10
11add_executable (greedy_projection greedy_projection.cpp)
12target_link_libraries (greedy_projection ${PCL_LIBRARIES})

After you have made the executable, you can run it. Simply do:

$ ./greedy_projection

Saving and viewing the result

You can view the smoothed cloud for example by saving into a VTK file by:

#include <pcl/io/vtk_io.h>
...
saveVTKFile ("mesh.vtk", triangles);