Normal Estimation Using Integral Images
In this tutorial we will learn how to compute normals for an organized point cloud using integral images.
The code
First, download the dataset table_scene_mug_stereo_textured.pcd and save it somewhere to disk.
Then, create a file, let’s say, normal_estimation_using_integral_images.cpp
in your favorite
editor, and place the following inside it:
1#include <pcl/visualization/pcl_visualizer.h>
2#include <iostream>
3#include <pcl/common/io.h>
4#include <pcl/io/pcd_io.h>
5#include <pcl/features/integral_image_normal.h>
6
7int
8main ()
9{
10 // load point cloud
11 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
12 pcl::io::loadPCDFile ("table_scene_mug_stereo_textured.pcd", *cloud);
13
14 // estimate normals
15 pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
16
17 pcl::IntegralImageNormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
18 ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
19 ne.setMaxDepthChangeFactor(0.02f);
20 ne.setNormalSmoothingSize(10.0f);
21 ne.setInputCloud(cloud);
22 ne.compute(*normals);
23
24 // visualize normals
25 pcl::visualization::PCLVisualizer viewer("PCL Viewer");
26 viewer.setBackgroundColor (0.0, 0.0, 0.5);
27 viewer.addPointCloudNormals<pcl::PointXYZ,pcl::Normal>(cloud, normals);
28
29 while (!viewer.wasStopped ())
30 {
31 viewer.spinOnce ();
32 }
33 return 0;
34}
The explanation
Now, let’s break down the code piece by piece. In the first part we load a point cloud from a file:
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::io::loadPCDFile ("table_scene_mug_stereo_textured.pcd", *cloud);
In the second part we create an object for the normal estimation and compute the normals:
// estimate normals
pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
pcl::IntegralImageNormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
ne.setMaxDepthChangeFactor(0.02f);
ne.setNormalSmoothingSize(10.0f);
ne.setInputCloud(cloud);
ne.compute(*normals);
The following normal estimation methods are available:
enum NormalEstimationMethod
{
COVARIANCE_MATRIX,
AVERAGE_3D_GRADIENT,
AVERAGE_DEPTH_CHANGE,
SIMPLE_3D_GRADIENT
};
The COVARIANCE_MATRIX mode creates 9 integral images to compute the normal for a specific point from the covariance matrix of its local neighborhood. The AVERAGE_3D_GRADIENT mode creates 6 integral images to compute smoothed versions of horizontal and vertical 3D gradients and computes the normals using the cross-product between these two gradients. The AVERAGE_DEPTH_CHANGE mode creates only a single integral image and computes the normals from the average depth changes.
In the last part we visualize the point cloud and the corresponding normals:
// visualize normals
pcl::visualization::PCLVisualizer viewer("PCL Viewer");
viewer.setBackgroundColor (0.0, 0.0, 0.5);
viewer.addPointCloudNormals<pcl::PointXYZ,pcl::Normal>(cloud, normals);
while (!viewer.wasStopped ())
{
viewer.spinOnce ();
}