Conditional Euclidean Clustering

This tutorial describes how to use the pcl::ConditionalEuclideanClustering class: A segmentation algorithm that clusters points based on Euclidean distance and a user-customizable condition that needs to hold.

This class uses the same greedy-like / region-growing / flood-filling approach that is used in Euclidean Cluster Extraction, Region growing segmentation and Color-based region growing segmentation. The advantage of using this class over the other classes is that the constraints for clustering (pure Euclidean, smoothness, RGB) are now customizable by the user. Some disadvantages include: no initial seeding system, no over- and under-segmentation control, and the fact that calling a conditional function from inside the main computational loop is less time efficient.

Theoretical Primer

The Euclidean Cluster Extraction and Region growing segmentation tutorials already explain the region growing algorithm very accurately. The only addition to those explanations is that the condition that needs to hold for a neighbor to be merged into the current cluster, can now be fully customized.

As a cluster grows, it will evaluate the user-defined condition between points already inside the cluster and nearby candidate points. The candidate points (nearest neighbor points) are found using a Euclidean radius search around each point in the cluster. For each point within a resulting cluster, the condition needed to hold with at least one of its neighbors and NOT with all of its neighbors.

The Conditional Euclidean Clustering class can also automatically filter clusters based on a size constraint. The clusters classified as too small or too large can still be retrieved afterwards.

The Code

First, download the dataset Statues_4.pcd and extract the PCD file from the archive. This is a very large data set of an outdoor environment where we aim to cluster the separate objects and also want to separate the building from the ground plane even though it is attached in a Euclidean sense.

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

  1#include <pcl/point_types.h>
  2#include <pcl/io/pcd_io.h>
  3#include <pcl/console/time.h>
  4
  5#include <pcl/filters/voxel_grid.h>
  6#include <pcl/features/normal_3d.h>
  7#include <pcl/segmentation/conditional_euclidean_clustering.h>
  8
  9typedef pcl::PointXYZI PointTypeIO;
 10typedef pcl::PointXYZINormal PointTypeFull;
 11
 12bool
 13enforceIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/)
 14{
 15  if (std::abs (point_a.intensity - point_b.intensity) < 5.0f)
 16    return (true);
 17  else
 18    return (false);
 19}
 20
 21bool
 22enforceNormalOrIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/)
 23{
 24  Eigen::Map<const Eigen::Vector3f> point_a_normal = point_a.getNormalVector3fMap (), point_b_normal = point_b.getNormalVector3fMap ();
 25  if (std::abs (point_a.intensity - point_b.intensity) < 5.0f)
 26    return (true);
 27  if (std::abs (point_a_normal.dot (point_b_normal)) > std::cos (30.0f / 180.0f * static_cast<float> (M_PI)))
 28    return (true);
 29  return (false);
 30}
 31
 32bool
 33customRegionGrowing (const PointTypeFull& point_a, const PointTypeFull& point_b, float squared_distance)
 34{
 35  Eigen::Map<const Eigen::Vector3f> point_a_normal = point_a.getNormalVector3fMap (), point_b_normal = point_b.getNormalVector3fMap ();
 36  if (squared_distance < 10000)
 37  {
 38    if (std::abs (point_a.intensity - point_b.intensity) < 8.0f)
 39      return (true);
 40    if (std::abs (point_a_normal.dot (point_b_normal)) > std::cos (30.0f / 180.0f * static_cast<float> (M_PI)))
 41      return (true);
 42  }
 43  else
 44  {
 45    if (std::abs (point_a.intensity - point_b.intensity) < 3.0f)
 46      return (true);
 47  }
 48  return (false);
 49}
 50
 51int
 52main ()
 53{
 54  // Data containers used
 55  pcl::PointCloud<PointTypeIO>::Ptr cloud_in (new pcl::PointCloud<PointTypeIO>), cloud_out (new pcl::PointCloud<PointTypeIO>);
 56  pcl::PointCloud<PointTypeFull>::Ptr cloud_with_normals (new pcl::PointCloud<PointTypeFull>);
 57  pcl::IndicesClustersPtr clusters (new pcl::IndicesClusters), small_clusters (new pcl::IndicesClusters), large_clusters (new pcl::IndicesClusters);
 58  pcl::search::KdTree<PointTypeIO>::Ptr search_tree (new pcl::search::KdTree<PointTypeIO>);
 59  pcl::console::TicToc tt;
 60
 61  // Load the input point cloud
 62  std::cerr << "Loading...\n", tt.tic ();
 63  pcl::io::loadPCDFile ("Statues_4.pcd", *cloud_in);
 64  std::cerr << ">> Done: " << tt.toc () << " ms, " << cloud_in->size () << " points\n";
 65
 66  // Downsample the cloud using a Voxel Grid class
 67  std::cerr << "Downsampling...\n", tt.tic ();
 68  pcl::VoxelGrid<PointTypeIO> vg;
 69  vg.setInputCloud (cloud_in);
 70  vg.setLeafSize (80.0, 80.0, 80.0);
 71  vg.setDownsampleAllData (true);
 72  vg.filter (*cloud_out);
 73  std::cerr << ">> Done: " << tt.toc () << " ms, " << cloud_out->size () << " points\n";
 74
 75  // Set up a Normal Estimation class and merge data in cloud_with_normals
 76  std::cerr << "Computing normals...\n", tt.tic ();
 77  pcl::copyPointCloud (*cloud_out, *cloud_with_normals);
 78  pcl::NormalEstimation<PointTypeIO, PointTypeFull> ne;
 79  ne.setInputCloud (cloud_out);
 80  ne.setSearchMethod (search_tree);
 81  ne.setRadiusSearch (300.0);
 82  ne.compute (*cloud_with_normals);
 83  std::cerr << ">> Done: " << tt.toc () << " ms\n";
 84
 85  // Set up a Conditional Euclidean Clustering class
 86  std::cerr << "Segmenting to clusters...\n", tt.tic ();
 87  pcl::ConditionalEuclideanClustering<PointTypeFull> cec (true);
 88  cec.setInputCloud (cloud_with_normals);
 89  cec.setConditionFunction (&customRegionGrowing);
 90  cec.setClusterTolerance (500.0);
 91  cec.setMinClusterSize (cloud_with_normals->size () / 1000);
 92  cec.setMaxClusterSize (cloud_with_normals->size () / 5);
 93  cec.segment (*clusters);
 94  cec.getRemovedClusters (small_clusters, large_clusters);
 95  std::cerr << ">> Done: " << tt.toc () << " ms\n";
 96
 97  // Using the intensity channel for lazy visualization of the output
 98  for (const auto& small_cluster : (*small_clusters))
 99    for (const auto& j : small_cluster.indices)
100      (*cloud_out)[j].intensity = -2.0;
101  for (const auto& large_cluster : (*large_clusters))
102    for (const auto& j : large_cluster.indices)
103      (*cloud_out)[j].intensity = +10.0;
104  for (const auto& cluster : (*clusters))
105  {
106    int label = rand () % 8;
107    for (const auto& j : cluster.indices)
108      (*cloud_out)[j].intensity = label;
109  }
110
111  // Save the output point cloud
112  std::cerr << "Saving...\n", tt.tic ();
113  pcl::io::savePCDFile ("output.pcd", *cloud_out);
114  std::cerr << ">> Done: " << tt.toc () << " ms\n";
115
116  return (0);
117}

The Explanation

Since the Conditional Euclidean Clustering class is for more advanced users, I will skip explanation of the more obvious parts of the code:

  • pcl::io::loadPCDFile and pcl::io::savePCDFile are used for loading and saving the point cloud data.

  • pcl::console::TicToc is used for easy output of timing results.

  • Downsampling a PointCloud using a VoxelGrid filter is being used (lines 66-73) to downsample the cloud and give a more equalized point density.

  • Estimating Surface Normals in a PointCloud is being used (lines 75-83) to estimate normals which will be appended to the point information; The Conditional Euclidean Clustering class will be templated with pcl::PointXYZINormal, containing x, y, z, intensity, normal and curvature information to use in the condition function.

Lines 85-95 set up the Conditional Euclidean Clustering class for use:

  // Set up a Conditional Euclidean Clustering class
  std::cerr << "Segmenting to clusters...\n", tt.tic ();
  pcl::ConditionalEuclideanClustering<PointTypeFull> cec (true);
  cec.setInputCloud (cloud_with_normals);
  cec.setConditionFunction (&customRegionGrowing);
  cec.setClusterTolerance (500.0);
  cec.setMinClusterSize (cloud_with_normals->size () / 1000);
  cec.setMaxClusterSize (cloud_with_normals->size () / 5);
  cec.segment (*clusters);
  cec.getRemovedClusters (small_clusters, large_clusters);
  std::cerr << ">> Done: " << tt.toc () << " ms\n";

A more elaborate description of the different lines of code:

  • The class is initialized with TRUE. This will allow extraction of clusters that are too small or too large. It saves some computation time and memory if the class is initialized without this.

  • The input data for the class can be specified using methods derived from the PCLBase class, i.e.: setInputCloud and setIndices.

  • As a cluster grows, it will evaluate a user-defined condition between points already inside the cluster and nearby candidate points. More on the condition function can be read further below.

  • The cluster tolerance is the radius for the k-NN searching, used to find the candidate points.

  • Clusters that make up less than 0.1% of the cloud’s total points are considered too small.

  • Clusters that make up more than 20% of the cloud’s total points are considered too large.

  • The resulting clusters are stored in the pcl::IndicesClusters format, which is an array of indices-arrays, indexing points of the input point cloud.

  • Too small clusters or too large clusters are not passed to the main output but can instead be retrieved in separate pcl::IndicesClusters data containers, but only if the class was initialized with TRUE.

Lines 12-49 show some examples of condition functions:

bool
enforceIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/)
{
  if (std::abs (point_a.intensity - point_b.intensity) < 5.0f)
    return (true);
  else
    return (false);
}

bool
enforceNormalOrIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/)
{
  Eigen::Map<const Eigen::Vector3f> point_a_normal = point_a.getNormalVector3fMap (), point_b_normal = point_b.getNormalVector3fMap ();
  if (std::abs (point_a.intensity - point_b.intensity) < 5.0f)
    return (true);
  if (std::abs (point_a_normal.dot (point_b_normal)) > std::cos (30.0f / 180.0f * static_cast<float> (M_PI)))
    return (true);
  return (false);
}

bool
customRegionGrowing (const PointTypeFull& point_a, const PointTypeFull& point_b, float squared_distance)
{
  Eigen::Map<const Eigen::Vector3f> point_a_normal = point_a.getNormalVector3fMap (), point_b_normal = point_b.getNormalVector3fMap ();
  if (squared_distance < 10000)
  {
    if (std::abs (point_a.intensity - point_b.intensity) < 8.0f)
      return (true);
    if (std::abs (point_a_normal.dot (point_b_normal)) > std::cos (30.0f / 180.0f * static_cast<float> (M_PI)))
      return (true);
  }
  else
  {
    if (std::abs (point_a.intensity - point_b.intensity) < 3.0f)
      return (true);
  }
  return (false);
}

The format of the condition function is fixed:

  • The first two input arguments need to be of the same type as the templated type used in the Conditional Euclidean Clustering class. These arguments will pass the point information for the current seed point (first argument) and the current candidate point (second argument).

  • The third input argument needs to be a float. This argument will pass the squared distance between the seed and candidate point. Although this information is also computable using the first two arguments, it is already provided by the underlying nearest neighbor search and can be used to easily make a distance dependent condition function.

  • The output argument needs to be a boolean. Returning TRUE will merge the candidate point into the cluster of the seed point. Returning FALSE will not merge the candidate point through this particular point-pair, however, it is still possible that the two points will end up in the same cluster through a different point-pair relationship.

These example condition functions are just to give an indication of how to use them. For instance, the second condition function will grow clusters as long as they are similar in surface normal direction OR similar in intensity value. This should hopefully cluster buildings of similar texture as one cluster, but not merge them into the same cluster as adjacent objects. This is going to work out if the intensity is different enough from nearby objects AND the nearby objects are not sharing a nearby surface with the same normal. The third condition function is similar to the second but has different constraints depending on the distance between the points.

Lines 97-109 contain a piece of code that is a quick and dirty fix to visualize the result:

  // Using the intensity channel for lazy visualization of the output
  for (const auto& small_cluster : (*small_clusters))
    for (const auto& j : small_cluster.indices)
      (*cloud_out)[j].intensity = -2.0;
  for (const auto& large_cluster : (*large_clusters))
    for (const auto& j : large_cluster.indices)
      (*cloud_out)[j].intensity = +10.0;
  for (const auto& cluster : (*clusters))
  {
    int label = rand () % 8;
    for (const auto& j : cluster.indices)
      (*cloud_out)[j].intensity = label;
  }

When the output point cloud is opened with PCL’s standard PCD viewer, pressing ‘5’ will switch to the intensity channel visualization. The too-small clusters will be colored red, the too-large clusters will be colored blue, and the actual clusters/objects of interest will be colored randomly in between yellow and cyan hues.

Compiling and running the program

Add the following lines to your CMakeLists.txt

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

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

$ ./conditional_euclidean_clustering

The resulting output point cloud can be opened like so:

$ ./pcl_viewer output.pcd

You should see something similar to this:

Output Cluster Extraction

This result is sub-optimal but it gives an idea of what can be achieved with this class. The mathematics and heuristics behind the customizable condition are now the responsibility of the user.