Downsampling 3D Point Clouds with a Voxelized Grid#
This tutorial shows how to use these optimizations inside a Docker* image. For the same functionality outside of Docker* images, see PCL Optimizations Outside of Docker* Images.
Prepare the environment:
cd <edge_insights_for_amr_path>/Edge_Insights_for_Autonomous_Mobile_Robots_<version>/AMR_containers ./run_interactive_docker.sh eiforamr-full-flavour-sdk:2023.1 root -c full_flavor mkdir voxel_grid && cd voxel_grid
Create the file
oneapi_voxel_grid.cpp
:vim oneapi_voxel_grid.cpp
Place the following inside the file:
#include <pcl/oneapi/filters/voxel_grid.h> #include <pcl/io/pcd_io.h> #include <pcl/point_types.h> #include <pcl/point_cloud.h> int main (int argc, char** argv) { // Read Point Cloud pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_( new pcl::PointCloud<pcl::PointXYZ>() ); int result = pcl::io::loadPCDFile("table_scene_lms400.pcd", *cloud_); if (result != 0) { pcl::console::print_info ("Load pcd file failed.\n"); return result; } // Prepare Device Point Cloud Memory (input) pcl::oneapi::VoxelGrid::PointCloud_xyz cloud_device_xyz; cloud_device_xyz.upload(cloud_->points); pcl::oneapi::VoxelGrid::PointCloud & cloud_device = (pcl::oneapi::VoxelGrid::PointCloud &)cloud_device_xyz; // Prepare Device Point Cloud Memory (output) pcl::oneapi::VoxelGrid::PointCloud_xyz cloud_device_xyz_o; cloud_device_xyz_o.create(cloud_->size()); pcl::oneapi::VoxelGrid::PointCloud & cloud_device_o = (pcl::oneapi::VoxelGrid::PointCloud &)cloud_device_xyz_o; // GPU calculate pcl::oneapi::VoxelGrid vg_oneapi; vg_oneapi.setInputCloud(cloud_device); float leafsize= 0.005f; vg_oneapi.setLeafSize (leafsize, leafsize, leafsize); vg_oneapi.filter(cloud_device_o); // print log std::cout << "[oneapi voxel grid] PointCloud before filtering: " << cloud_device.size() << std::endl; std::cout << "[oneapi voxel grid] PointCloud after filtering: " << cloud_device_o.size() << std::endl; }
Create a CMakeLists.txt file:
vim CMakeLists.txt
Place the following inside the file:
cmake_minimum_required(VERSION 3.5 FATAL_ERROR) set(target oneapi_voxel_grid) set(CMAKE_CXX_COMPILER dpcpp) set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_FLAGS "-Wall -Wpedantic -Wno-unknown-pragmas -Wno-pass-failed -Wno-unneeded-internal-declaration -Wno-unused-function -Wno-gnu-anonymous-struct -Wno-nested-anon-types -Wno-extra-semi -Wno-unused-local-typedef -fsycl -fsycl-unnamed-lambda -ferror-limit=1") project(${target}) find_package(PCL 1.12 REQUIRED) find_package(PCL-ONEAPI 1.12 REQUIRED) include_directories(${PCL_INCLUDE_DIRS} ${PCL-ONEAPI_INCLUDE_DIRS}) link_directories(${PCL_LIBRARY_DIRS} ${PCL-ONEAPI_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS} ${PCL-ONEAPI_DEFINITIONS}) add_executable (${target} oneapi_voxel_grid.cpp) target_link_libraries (${target} sycl pcl_oneapi_filters ${PCL_LIBRARIES})
Source the Intel® oneAPI Base Toolkit environment:
export PATH=/home/eiforamr/workspace/lib/pcl/share/pcl-1.12:/home/eiforamr/workspace/lib/pcl/share/pcl-oneapi-1.12:$PATH source /opt/intel/oneapi/setvars.sh
Build the code:
cd /home/eiforamr/workspace/voxel_grid/ mkdir build && cd build cmake ../ make -j
Download the test data from GitHub*:
wget https://raw.githubusercontent.com/PointCloudLibrary/data/5c26bdd0591ba150b91858b5c9fe5e91cb39ae86/tutorials/table_scene_lms400.pcd # if the binary is not downloaded try setting the proxies first and try again: export http_proxy="http://<http_proxy>:port" export https_proxy="http://<https_proxy>:port"
Run the binary:
./oneapi_voxel_grid
Expected results example:
[oneapi voxel grid] PointCloud before filtering: 460400
[oneapi voxel grid] PointCloud after filtering: 41049
Code Explanation#
Load the test data from GitHub* into a PointCloud<PointXYZ>.
// Read Point Cloud
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_( new pcl::PointCloud<pcl::PointXYZ>() );
int result = pcl::io::loadPCDFile("table_scene_lms400.pcd", *cloud_);
if (result != 0)
{
pcl::console::print_info ("Load pcd file failed.\n");
return result;
}
Create the GPU input and output device arrays, and upload the point cloud data to the input device array.
// Prepare Device Point Cloud Memory (input)
pcl::oneapi::VoxelGrid::PointCloud_xyz cloud_device_xyz;
cloud_device_xyz.upload(cloud_->points);
pcl::oneapi::VoxelGrid::PointCloud & cloud_device = (pcl::oneapi::VoxelGrid::PointCloud &)cloud_device_xyz;
// Prepare Device Point Cloud Memory (output)
pcl::oneapi::VoxelGrid::PointCloud_xyz cloud_device_xyz_o;
cloud_device_xyz_o.create(cloud_->size());
pcl::oneapi::VoxelGrid::PointCloud & cloud_device_o = (pcl::oneapi::VoxelGrid::PointCloud &)cloud_device_xyz_o;
The GPU starts to compute the model.
// GPU calculate
pcl::oneapi::VoxelGrid vg_oneapi;
vg_oneapi.setInputCloud(cloud_device);
float leafsize= 0.005f;
vg_oneapi.setLeafSize (leafsize, leafsize, leafsize);
vg_oneapi.filter(cloud_device_o);
Result (output log):
// print log
std::cout << "[oneapi voxel grid] PointCloud before filtering: " << cloud_device.size() << std::endl;
std::cout << "[oneapi voxel grid] PointCloud after filtering: " << cloud_device_o.size() << std::endl;