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.
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_cluster_size | integer | The minimum number of points that a cluster needs to contain in order to be considered valid. | 10 | N/A |
tolerance | 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 | float | The spatial cluster tolerance as a measure in the L2 Euclidean space. | 0.7 | N/A |
voxel_leaf_size | float | The voxel leaf size of x and y. | 0.3 | N/A |
min_points_number_per_voxel | integer | The minimum number of points required per voxel. | 1 | N/A |
min_cluster_size | integer | The minimum number of points that a cluster needs to contain in order to be considered valid. | 10 | N/A |
max_cluster_size | integer | The maximum number of points that a cluster needs to contain in order to be considered valid. | 3000 | N/A |
use_height | boolean | Use point.z for clustering. | False | N/A |
input_frame | string | The reference frame for input data processing. | base_link | N/A |
max_x | float | Maximum X coordinate for the low height crop box filter. | 200.0 | N/A |
min_x | float | Minimum X coordinate for the low height crop box filter. | -200.0 | N/A |
max_y | float | Maximum Y coordinate for the low height crop box filter. | 200.0 | N/A |
min_y | float | Minimum Y coordinate for the low height crop box filter. | -200.0 | N/A |
max_z | float | Maximum Z coordinate for the low height crop box filter. | 2.0 | N/A |
min_z | float | Minimum Z coordinate for the low height crop box filter. | -10.0 | N/A |
negative | boolean | Whether to invert the crop box filtering effect. | False | 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.