Estimating Surface Normals in a PointCloud¶
In this tutorial, we will learn how to obtain the surface normals of each point in the cloud.
Note
This tutorial is applicable for execution for both within inside and outside a Docker* image. It assumes that the pcl-oneapi-tutorials Deb package is installed, and the user has copied the tutorial directory from /opt/intel/pcl/oneapi/tutorials/ to a user-writable directory.
Prepare the environment:
cd <path-to-oneapi-tutorials>/normal_estimation
oneapi_normal_estimation.cpp
should be in the directory with following content:1#include <pcl/io/pcd_io.h> 2#include <pcl/oneapi/features/normal_3d.h> 3#include <pcl/oneapi/kdtree/kdtree_flann.h> 4#include <pcl/oneapi/point_cloud.h> 5 6int main (int argc, char** argv) 7{ 8 int k = 10; 9 float radius = 0.01; 10 11 std::cout << "Running on device: " << dpct::get_default_queue().get_device().get_info<sycl::info::device::name>() << "\n"; 12 13 // load point cloud 14 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr( new pcl::PointCloud<pcl::PointXYZ>() ); 15 16 int result = pcl::io::loadPCDFile("bun0.pcd", *cloud_ptr); 17 if (result != 0) 18 { 19 pcl::console::print_info ("Load pcd file failed.\n"); 20 return result; 21 } 22 23 // estimate normals with knn search 24 pcl::oneapi::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne; 25 ne.setSearchMethod (pcl::oneapi::KdTreeFLANN<pcl::PointXYZ>::Ptr (new pcl::oneapi::KdTreeFLANN<pcl::PointXYZ>)); 26 ne.setInputCloud(cloud_ptr); 27 ne.setKSearch(k); 28 29 // save normal estimation to CPU memory point cloud 30 pcl::PointCloud<pcl::Normal>::Ptr normals_knn(new pcl::PointCloud<pcl::Normal>); 31 ne.compute(*normals_knn); 32 33 std::cout << "normals_knn.size (): " << normals_knn->size () << std::endl; 34 35 // estimate normals with radius search 36 ne.setSearchMethod (pcl::oneapi::KdTreeFLANN<pcl::PointXYZ>::Ptr (new pcl::oneapi::KdTreeFLANN<pcl::PointXYZ>)); 37 ne.setInputCloud(cloud_ptr); 38 ne.setRadiusSearch(radius); 39 ne.setKSearch(0); 40 41 // save normal estimation output to device shared memory point cloud 42 pcl::oneapi::PointCloudDev<pcl::Normal>::Ptr normals_radius(new pcl::oneapi::PointCloudDev<pcl::Normal>) ; 43 ne.compute(*normals_radius); 44 45 std::cout << "normals_radius.size (): " << normals_radius->size () << std::endl; 46 47 return 0; 48}
Source the Intel® oneAPI Base Toolkit environment:
source /opt/intel/oneapi/setvars.sh
(Optional) Setup proxy setting to download test data:
export http_proxy="http://<http_proxy>:port" export https_proxy="http://<https_proxy>:port"
Build the code:
mkdir build && cd build cmake ../ make -j
Run the binary:
./oneapi_normal_estimation
Expected results example:
normals_knn.size (): 397 normals_radius.size (): 397
Code Explanation¶
The example PCD is initially loaded into a PointCloud<PointXYZ>.
// load point cloud
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr( new pcl::PointCloud<pcl::PointXYZ>() );
int result = pcl::io::loadPCDFile("bun0.pcd", *cloud_ptr);
if (result != 0)
{
pcl::console::print_info ("Load pcd file failed.\n");
return result;
}
This tutorial includes two normal estimation processes: KNN search and Radius search. The initial step involves adjusting the parameters for normal estimation in the KNN search.
// estimate normals with knn search
pcl::oneapi::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
ne.setSearchMethod (pcl::oneapi::KdTreeFLANN<pcl::PointXYZ>::Ptr (new pcl::oneapi::KdTreeFLANN<pcl::PointXYZ>));
ne.setInputCloud(cloud_ptr);
ne.setKSearch(k);
Normal estimation is then executed.
pcl::PointCloud<pcl::Normal>::Ptr normals_knn(new pcl::PointCloud<pcl::Normal>);
ne.compute(*normals_knn);
The parameters for normal estimation are modified for the radius search.
// estimate normals with radius search
ne.setSearchMethod (pcl::oneapi::KdTreeFLANN<pcl::PointXYZ>::Ptr (new pcl::oneapi::KdTreeFLANN<pcl::PointXYZ>));
ne.setInputCloud(cloud_ptr);
ne.setRadiusSearch(radius);
ne.setKSearch(0);
Normal estimation is performed once more.
// save normal estimation output to device shared memory point cloud
pcl::oneapi::PointCloudDev<pcl::Normal>::Ptr normals_radius(new pcl::oneapi::PointCloudDev<pcl::Normal>) ;
ne.compute(*normals_radius);