Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_pcl_extensions): porting from universe to core #163

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 25 additions & 0 deletions sensing/autoware_pcl_extensions/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_pcl_extensions)

find_package(autoware_cmake REQUIRED)
autoware_package()

find_package(PCL REQUIRED COMPONENTS common)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)

include_directories(
SYSTEM
${EIGEN3_INCLUDE_DIR}
${PCL_INCLUDE_DIRS}
)
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})

ament_auto_add_library(autoware_pcl_extensions SHARED
src/voxel_grid_nearest_centroid.cpp
)

target_link_libraries(autoware_pcl_extensions ${PCL_LIBRARIES})

ament_auto_package()
56 changes: 56 additions & 0 deletions sensing/autoware_pcl_extensions/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
# autoware_pcl_extensions

## Overview

The `autoware_pcl_extensions` is a pcl extension library. The voxel grid filter in this package works with a different algorithm than the original one.

## Design

Inner-workings / Algorithms

### Original Algorithm [1]

1. create a 3D voxel grid over the input pointcloud data
2. calculate centroid in each voxel
3. all the points are approximated with their centroid

### Extended Algorithm

1. create a 3D voxel grid over the input pointcloud data
2. calculate centroid in each voxel
3. **all the points are approximated with the closest point to their centroid**

## Inputs / Outputs

input and output are pointcloud with the datatype `pcl::PointCloud<pcl::PointXYZ>`

## Parameters

`leaf_size`: it represents the scale of each cell in 3 dimension.

It can be set by calling this function, where the scale of the cell in the axis of x, y and z are set respectively

```cpp
filter.setLeafSize(voxel_size_x_, voxel_size_y_, voxel_size_z_);
```

## Usage

include the header file

```cpp
#include <autoware/pcl_extensions/voxel_grid_nearest_centroid.hpp>
```

init the filter with input pointcloud, set leaf size and get output result

```cpp
pcl::VoxelGridNearestCentroid<pcl::PointXYZ> filter;
filter.setInputCloud(pcl_input);
filter.setLeafSize(voxel_size_x_, voxel_size_y_, voxel_size_z_);
filter.filter(*pcl_output);
```

## (Optional) References/External links

[1] <https://pointclouds.org/documentation/tutorials/voxel_grid.html>
Loading
Loading