autoware_euclidean_cluster#
Purpose#
autoware_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.
label_based_euclidean_cluster#
LabelBasedEuclideanCluster converts a semantically segmented pointcloud into DetectedObjects.
See docs/label-based-euclidean-cluster.md for the node-specific behavior and configuration details.
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 | Default | Range |
|---|---|---|---|---|
| max_cluster_size | integer | The maximum number of points that a cluster needs to contain in order to be considered valid. | 1000 | N/A |
| min_points_per_cluster | integer | The minimum number of points that a cluster needs to contain in order to be considered valid. | 10 | N/A |
| tolerance_m | float | The spatial cluster tolerance as a measure in the L2 Euclidean space. | 0.7 | N/A |
| use_height | boolean | Whether to use point.z for clustering. | 0 | N/A |
voxel_grid_based_euclidean_cluster#
| Name | Type | Description | Default | Range |
|---|---|---|---|---|
| tolerance_m | float | Euclidean cluster tolerance. Two occupied voxels are merged into the same cluster when their 2D (x-y) centroid distance is within this value (applied transitively). Clustering is performed on voxel centroids with z flattened to 0. | 0.7 | N/A |
| voxel_leaf_size_m | float | Voxel leaf size in x and y. The z leaf is effectively infinite, so the grid is 2D and all heights collapse into a single x-y cell. This value bounds the footprint resolution used for clustering and splitting. | 0.3 | N/A |
| min_points_per_voxel | integer | Minimum number of raw points a voxel must contain to be kept. Voxels with fewer points are discarded before clustering, rejecting sparse noise. | 1 | N/A |
| min_points_per_cluster | integer | Minimum number of raw points a cluster must contain to be included in the output. Smaller clusters are dropped at the final filtering stage. | 10 | N/A |
| max_voxels_per_cluster | integer | Voxel-count split bound. Any cluster whose voxel count exceeds this is recursively bisected along its principal (longest) axis into smaller sub-clusters until every piece is at or below this size. No cluster is dropped for being large; large groups are exported as multiple bounded sections. | 800 | ≥1 |
| large_cluster_voxel_count_threshold | integer | Voxel-count threshold above which a cluster is considered 'large' and subject to per-voxel point capping (see large_cluster_max_points_per_voxel). Clusters at or below this size keep all their points. | 65 | N/A |
| large_cluster_max_points_per_voxel | integer | Maximum number of points kept per voxel within a large cluster (one whose voxel count exceeds large_cluster_voxel_count_threshold). Excess points are dropped to bound downstream cost; points are processed in a deterministically shuffled order so the kept points sample uniformly across each voxel. | 10 | N/A |
| use_height | boolean | Use point.z for clustering. Currently only the 2D (false) path is implemented. | 0 | N/A |
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.