Robust pose estimation of rigid objects
In this tutorial, we show how to find the alignment pose of a rigid object in a scene with clutter and occlusions.
The code
First, download the test models: object
and scene
.
Next, copy and paste the following code into your editor and save it as alignment_prerejective.cpp
(or download the source file here
).
1#include <Eigen/Core>
2
3#include <pcl/point_types.h>
4#include <pcl/point_cloud.h>
5#include <pcl/common/time.h>
6#include <pcl/console/print.h>
7#include <pcl/features/normal_3d_omp.h>
8#include <pcl/features/fpfh_omp.h>
9#include <pcl/filters/filter.h>
10#include <pcl/filters/voxel_grid.h>
11#include <pcl/io/pcd_io.h>
12#include <pcl/registration/sample_consensus_prerejective.h>
13#include <pcl/visualization/pcl_visualizer.h>
14
15// Types
16typedef pcl::PointNormal PointNT;
17typedef pcl::PointCloud<PointNT> PointCloudT;
18typedef pcl::FPFHSignature33 FeatureT;
19typedef pcl::FPFHEstimationOMP<PointNT,PointNT,FeatureT> FeatureEstimationT;
20typedef pcl::PointCloud<FeatureT> FeatureCloudT;
21typedef pcl::visualization::PointCloudColorHandlerCustom<PointNT> ColorHandlerT;
22
23// Align a rigid object to a scene with clutter and occlusions
24int
25main (int argc, char **argv)
26{
27 // Point clouds
28 PointCloudT::Ptr object (new PointCloudT);
29 PointCloudT::Ptr object_aligned (new PointCloudT);
30 PointCloudT::Ptr scene_before_downsampling (new PointCloudT);
31 PointCloudT::Ptr scene (new PointCloudT);
32 FeatureCloudT::Ptr object_features (new FeatureCloudT);
33 FeatureCloudT::Ptr scene_features (new FeatureCloudT);
34
35 // Get input object and scene
36 if (argc != 3)
37 {
38 pcl::console::print_error ("Syntax is: %s object.pcd scene.pcd\n", argv[0]);
39 return (1);
40 }
41
42 // Load object and scene
43 pcl::console::print_highlight ("Loading point clouds...\n");
44 if (pcl::io::loadPCDFile<PointNT> (argv[1], *object) < 0 ||
45 pcl::io::loadPCDFile<PointNT> (argv[2], *scene_before_downsampling) < 0)
46 {
47 pcl::console::print_error ("Error loading object/scene file!\n");
48 return (1);
49 }
50
51 // Downsample
52 pcl::console::print_highlight ("Downsampling...\n");
53 pcl::VoxelGrid<PointNT> grid;
54 const float leaf = 0.005f;
55 grid.setLeafSize (leaf, leaf, leaf);
56 grid.setInputCloud (object);
57 grid.filter (*object);
58 grid.setInputCloud (scene_before_downsampling);
59 grid.filter (*scene);
60
61 // Estimate normals for scene
62 pcl::console::print_highlight ("Estimating scene normals...\n");
63 pcl::NormalEstimationOMP<PointNT,PointNT> nest;
64 nest.setRadiusSearch (0.005);
65 nest.setInputCloud (scene);
66 nest.setSearchSurface (scene_before_downsampling);
67 nest.compute (*scene);
68
69 // Estimate features
70 pcl::console::print_highlight ("Estimating features...\n");
71 FeatureEstimationT fest;
72 fest.setRadiusSearch (0.025);
73 fest.setInputCloud (object);
74 fest.setInputNormals (object);
75 fest.compute (*object_features);
76 fest.setInputCloud (scene);
77 fest.setInputNormals (scene);
78 fest.compute (*scene_features);
79
80 // Perform alignment
81 pcl::console::print_highlight ("Starting alignment...\n");
82 pcl::SampleConsensusPrerejective<PointNT,PointNT,FeatureT> align;
83 align.setInputSource (object);
84 align.setSourceFeatures (object_features);
85 align.setInputTarget (scene);
86 align.setTargetFeatures (scene_features);
87 align.setMaximumIterations (50000); // Number of RANSAC iterations
88 align.setNumberOfSamples (3); // Number of points to sample for generating/prerejecting a pose
89 align.setCorrespondenceRandomness (5); // Number of nearest features to use
90 align.setSimilarityThreshold (0.95f); // Polygonal edge length similarity threshold
91 align.setMaxCorrespondenceDistance (2.5f * leaf); // Inlier threshold
92 align.setInlierFraction (0.25f); // Required inlier fraction for accepting a pose hypothesis
93 {
94 pcl::ScopeTime t("Alignment");
95 align.align (*object_aligned);
96 }
97
98 if (align.hasConverged ())
99 {
100 // Print results
101 printf ("\n");
102 Eigen::Matrix4f transformation = align.getFinalTransformation ();
103 pcl::console::print_info (" | %6.3f %6.3f %6.3f | \n", transformation (0,0), transformation (0,1), transformation (0,2));
104 pcl::console::print_info ("R = | %6.3f %6.3f %6.3f | \n", transformation (1,0), transformation (1,1), transformation (1,2));
105 pcl::console::print_info (" | %6.3f %6.3f %6.3f | \n", transformation (2,0), transformation (2,1), transformation (2,2));
106 pcl::console::print_info ("\n");
107 pcl::console::print_info ("t = < %0.3f, %0.3f, %0.3f >\n", transformation (0,3), transformation (1,3), transformation (2,3));
108 pcl::console::print_info ("\n");
109 pcl::console::print_info ("Inliers: %i/%i\n", align.getInliers ().size (), object->size ());
110
111 // Show alignment
112 pcl::visualization::PCLVisualizer visu("Alignment");
113 visu.addPointCloud (scene, ColorHandlerT (scene, 0.0, 255.0, 0.0), "scene");
114 visu.addPointCloud (object_aligned, ColorHandlerT (object_aligned, 0.0, 0.0, 255.0), "object_aligned");
115 visu.spin ();
116 }
117 else
118 {
119 pcl::console::print_error ("Alignment failed!\n");
120 return (1);
121 }
122
123 return (0);
124}
The explanation
We start by defining convenience types in order not to clutter the code.
// Types
typedef pcl::PointNormal PointNT;
typedef pcl::PointCloud<PointNT> PointCloudT;
typedef pcl::FPFHSignature33 FeatureT;
typedef pcl::FPFHEstimationOMP<PointNT,PointNT,FeatureT> FeatureEstimationT;
typedef pcl::PointCloud<FeatureT> FeatureCloudT;
typedef pcl::visualization::PointCloudColorHandlerCustom<PointNT> ColorHandlerT;
Then we instantiate the necessary data containers, check the input arguments and load the object and scene point clouds. Although we have defined the basic point type to contain normals, we only have those in advance for the object (which is often the case). We will estimate the normal information for the scene below.
// Point clouds
PointCloudT::Ptr object (new PointCloudT);
PointCloudT::Ptr object_aligned (new PointCloudT);
PointCloudT::Ptr scene_before_downsampling (new PointCloudT);
PointCloudT::Ptr scene (new PointCloudT);
FeatureCloudT::Ptr object_features (new FeatureCloudT);
FeatureCloudT::Ptr scene_features (new FeatureCloudT);
// Get input object and scene
if (argc != 3)
{
pcl::console::print_error ("Syntax is: %s object.pcd scene.pcd\n", argv[0]);
return (1);
}
// Load object and scene
pcl::console::print_highlight ("Loading point clouds...\n");
if (pcl::io::loadPCDFile<PointNT> (argv[1], *object) < 0 ||
pcl::io::loadPCDFile<PointNT> (argv[2], *scene_before_downsampling) < 0)
{
pcl::console::print_error ("Error loading object/scene file!\n");
return (1);
}
To speed up processing, we use PCL’s VoxelGrid class to downsample both the object and the scene point clouds to a resolution of 5 mm.
// Downsample
pcl::console::print_highlight ("Downsampling...\n");
pcl::VoxelGrid<PointNT> grid;
const float leaf = 0.005f;
grid.setLeafSize (leaf, leaf, leaf);
grid.setInputCloud (object);
grid.filter (*object);
grid.setInputCloud (scene_before_downsampling);
grid.filter (*scene);
The missing surface normals for the scene are now estimated using PCL’s NormalEstimationOMP. The surface normals are required for computing the features below used for matching.
// Estimate normals for scene
pcl::console::print_highlight ("Estimating scene normals...\n");
pcl::NormalEstimationOMP<PointNT,PointNT> nest;
nest.setRadiusSearch (0.005);
nest.setInputCloud (scene);
nest.setSearchSurface (scene_before_downsampling);
nest.compute (*scene);
For each point in the downsampled point clouds, we now use PCL’s FPFHEstimationOMP class to compute Fast Point Feature Histogram (FPFH) descriptors used for matching during the alignment process.
// Estimate features
pcl::console::print_highlight ("Estimating features...\n");
FeatureEstimationT fest;
fest.setRadiusSearch (0.025);
fest.setInputCloud (object);
fest.setInputNormals (object);
fest.compute (*object_features);
fest.setInputCloud (scene);
fest.setInputNormals (scene);
fest.compute (*scene_features);
We are now ready to setup the alignment process. We use the class SampleConsensusPrerejective, which implements an efficient RANSAC pose estimation loop. This is achieved by early elimination of bad pose hypothesis using the class CorrespondenceRejectorPoly.
// Perform alignment
pcl::console::print_highlight ("Starting alignment...\n");
pcl::SampleConsensusPrerejective<PointNT,PointNT,FeatureT> align;
align.setInputSource (object);
align.setSourceFeatures (object_features);
align.setInputTarget (scene);
align.setTargetFeatures (scene_features);
align.setMaximumIterations (50000); // Number of RANSAC iterations
align.setNumberOfSamples (3); // Number of points to sample for generating/prerejecting a pose
align.setCorrespondenceRandomness (5); // Number of nearest features to use
align.setSimilarityThreshold (0.95f); // Polygonal edge length similarity threshold
align.setMaxCorrespondenceDistance (2.5f * leaf); // Inlier threshold
align.setInlierFraction (0.25f); // Required inlier fraction for accepting a pose hypothesis
Note
Apart from the usual input point clouds and features, this class takes some additional runtime parameters which have great influence on the performance of the alignment algorithm. The first two have the same meaning as in the alignment class SampleConsensusInitialAlignment:
Number of samples - setNumberOfSamples (): The number of point correspondences to sample between the object and the scene. At minimum, 3 points are required to calculate a pose.
Correspondence randomness - setCorrespondenceRandomness (): Instead of matching each object FPFH descriptor to its nearest matching feature in the scene, we can choose between the N best matches at random. This increases the iterations necessary, but also makes the algorithm robust towards outlier matches.
Polygonal similarity threshold - setSimilarityThreshold (): The alignment class uses the CorrespondenceRejectorPoly class for early elimination of bad poses based on pose-invariant geometric consistencies of the inter-distances between sampled points on the object and the scene. The closer this value is set to 1, the more greedy and thereby fast the algorithm becomes. However, this also increases the risk of eliminating good poses when noise is present.
Inlier threshold - setMaxCorrespondenceDistance (): This is the Euclidean distance threshold used for determining whether a transformed object point is correctly aligned to the nearest scene point or not. In this example, we have used a heuristic value of 2.5 times the point cloud resolution.
Inlier fraction - setInlierFraction (): In many practical scenarios, large parts of the observed object in the scene are not visible, either due to clutter, occlusions or both. In such cases, we need to allow for pose hypotheses that do not align all object points to the scene. The absolute number of correctly aligned points is determined using the inlier threshold, and if the ratio of this number to the total number of points in the object is higher than the specified inlier fraction, we accept a pose hypothesis as valid.
Finally, we are ready to execute the alignment process.
{
pcl::ScopeTime t("Alignment");
align.align (*object_aligned);
}
The aligned object is stored in the point cloud object_aligned. If a pose with enough inliers was found (more than 25 % of the total number of object points), the algorithm is said to converge, and we can print and visualize the results.
// Print results
printf ("\n");
Eigen::Matrix4f transformation = align.getFinalTransformation ();
pcl::console::print_info (" | %6.3f %6.3f %6.3f | \n", transformation (0,0), transformation (0,1), transformation (0,2));
pcl::console::print_info ("R = | %6.3f %6.3f %6.3f | \n", transformation (1,0), transformation (1,1), transformation (1,2));
pcl::console::print_info (" | %6.3f %6.3f %6.3f | \n", transformation (2,0), transformation (2,1), transformation (2,2));
pcl::console::print_info ("\n");
pcl::console::print_info ("t = < %0.3f, %0.3f, %0.3f >\n", transformation (0,3), transformation (1,3), transformation (2,3));
pcl::console::print_info ("\n");
pcl::console::print_info ("Inliers: %i/%i\n", align.getInliers ().size (), object->size ());
// Show alignment
pcl::visualization::PCLVisualizer visu("Alignment");
visu.addPointCloud (scene, ColorHandlerT (scene, 0.0, 255.0, 0.0), "scene");
visu.addPointCloud (object_aligned, ColorHandlerT (object_aligned, 0.0, 0.0, 255.0), "object_aligned");
visu.spin ();
Compiling and running the program
Create a CMakeLists.txt
file with the following content (or download it here
):
1cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
2
3project(alignment_prerejective)
4
5find_package(PCL 1.7 REQUIRED COMPONENTS io registration segmentation visualization)
6
7include_directories(${PCL_INCLUDE_DIRS})
8link_directories(${PCL_LIBRARY_DIRS})
9add_definitions(${PCL_DEFINITIONS})
10
11add_executable (alignment_prerejective alignment_prerejective.cpp)
12target_link_libraries (alignment_prerejective ${PCL_LIBRARIES})
After you have made the executable, you can run it like so:
$ ./alignment_prerejective chef.pcd rs1.pcd
After a few seconds, you will see a visualization and a terminal output similar to:
Alignment took 352ms.
| 0.040 -0.929 -0.369 |
R = | -0.999 -0.035 -0.020 |
| 0.006 0.369 -0.929 |
t = < -0.120, 0.055, 0.076 >
Inliers: 1422/3432
The visualization window should look something like the below figures. The scene is shown with green color, and the aligned object model is shown with blue color. Note the high number of non-visible object points.