euclidean_cluster#
Purpose#
euclidean_cluster is a package for clustering points into smaller parts to classify objects.
This package has two clustering methods: euclidean_cluster
and voxel_grid_based_euclidean_cluster
.
Inner-workings / Algorithms#
euclidean_cluster#
pcl::EuclideanClusterExtraction
is applied to points. See official document for details.
voxel_grid_based_euclidean_cluster#
- A centroid in each voxel is calculated by
pcl::VoxelGrid
. - The centroids are clustered by
pcl::EuclideanClusterExtraction
. - The input points are clustered based on the clustered centroids.
Inputs / Outputs#
Input#
Name | Type | Description |
---|---|---|
input |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output#
Name | Type | Description |
---|---|---|
output |
tier4_perception_msgs::msg::DetectedObjectsWithFeature |
cluster pointcloud |
debug/clusters |
sensor_msgs::msg::PointCloud2 |
colored cluster pointcloud for visualization |
Parameters#
Core Parameters#
euclidean_cluster#
Name | Type | Description |
---|---|---|
use_height |
bool | use point.z for clustering |
min_cluster_size |
int | the minimum number of points that a cluster needs to contain in order to be considered valid |
max_cluster_size |
int | the maximum number of points that a cluster needs to contain in order to be considered valid |
tolerance |
float | the spatial cluster tolerance as a measure in the L2 Euclidean space |
voxel_grid_based_euclidean_cluster#
Name | Type | Description |
---|---|---|
use_height |
bool | use point.z for clustering |
min_cluster_size |
int | the minimum number of points that a cluster needs to contain in order to be considered valid |
max_cluster_size |
int | the maximum number of points that a cluster needs to contain in order to be considered valid |
tolerance |
float | the spatial cluster tolerance as a measure in the L2 Euclidean space |
voxel_leaf_size |
float | the voxel leaf size of x and y |
min_points_number_per_voxel |
int | the minimum number of points for a voxel |
Assumptions / Known limits#
(Optional) Error detection and handling#
(Optional) Performance characterization#
(Optional) References/External links#
(Optional) Future extensions / Unimplemented parts#
The use_height
option of voxel_grid_based_euclidean_cluster
isn't implemented yet.