From 2796d0a2115398f5479d95990dc72deabd09942d Mon Sep 17 00:00:00 2001 From: Ismet Atabay <56237550+ismetatabay@users.noreply.github.com> Date: Fri, 14 Jul 2023 15:10:48 +0300 Subject: [PATCH] refactor(autoware_launch): add euclidean_clustering params (#445) * add euclidean_clustering param Signed-off-by: ismetatabay * style(pre-commit): autofix Signed-off-by: ismetatabay * update and rearrange comments Signed-off-by: ismetatabay * style(pre-commit): autofix Signed-off-by: ismetatabay --------- Signed-off-by: ismetatabay Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../clustering/compare_map.param.yaml | 20 +++++++++++ .../clustering/euclidean_cluster.param.yaml | 6 ++++ .../detection/clustering/outlier.param.yaml | 8 +++++ .../clustering/voxel_grid.param.yaml | 7 ++++ ...el_grid_based_euclidean_cluster.param.yaml | 15 ++++++++ .../roi_sync.param.yaml | 0 .../object_lanelet_filter.param.yaml | 0 .../object_position_filter.param.yaml | 0 .../pointcloud_map_filter.param.yaml | 0 .../tier4_perception_component.launch.xml | 34 +++++++++++++++---- 10 files changed, 84 insertions(+), 6 deletions(-) create mode 100644 autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml create mode 100644 autoware_launch/config/perception/object_recognition/detection/clustering/euclidean_cluster.param.yaml create mode 100644 autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml create mode 100644 autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml create mode 100644 autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml rename autoware_launch/config/perception/object_recognition/detection/{ => image_projection_based_fusion}/roi_sync.param.yaml (100%) rename autoware_launch/config/perception/object_recognition/detection/{ => object_filter}/object_lanelet_filter.param.yaml (100%) rename autoware_launch/config/perception/object_recognition/detection/{ => object_filter}/object_position_filter.param.yaml (100%) rename autoware_launch/config/perception/object_recognition/detection/{ => pointcloud_filter}/pointcloud_map_filter.param.yaml (100%) diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml new file mode 100644 index 0000000000..3dd303464a --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml @@ -0,0 +1,20 @@ +/**: + ros__parameters: + + # distance threshold for compare compare + distance_threshold: 0.5 + + # publish voxelized map pointcloud for debug + publish_debug_pcd: False + + # use dynamic map loading + use_dynamic_map_loading: True + + # time interval to check dynamic map loading + timer_interval_ms: 100 + + # distance threshold for dynamic map update + map_update_distance_threshold: 10.0 + + # radius map for dynamic map loading + map_loader_radius: 150.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/euclidean_cluster.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/euclidean_cluster.param.yaml new file mode 100644 index 0000000000..1411f766b4 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/clustering/euclidean_cluster.param.yaml @@ -0,0 +1,6 @@ +/**: + ros__parameters: + max_cluster_size: 1000 + min_cluster_size: 10 + tolerance: 0.7 + use_height: false diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml new file mode 100644 index 0000000000..1962fba1f3 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + input_frame: base_link + output_frame: base_link + voxel_size_x: 0.3 + voxel_size_y: 0.3 + voxel_size_z: 100.0 + voxel_points_threshold: 3 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml new file mode 100644 index 0000000000..3ff32bfbb7 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + input_frame: base_link + output_frame: base_link + voxel_size_x: 0.15 + voxel_size_y: 0.15 + voxel_size_z: 0.15 diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml new file mode 100644 index 0000000000..2f3de2b789 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + tolerance: 0.7 + voxel_leaf_size: 0.3 + min_points_number_per_voxel: 1 + min_cluster_size: 10 + max_cluster_size: 3000 + use_height: false + input_frame: "base_link" + max_x: 70.0 + min_x: -70.0 + max_y: 70.0 + min_y: -70.0 + max_z: 4.5 + min_z: -4.5 diff --git a/autoware_launch/config/perception/object_recognition/detection/roi_sync.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml similarity index 100% rename from autoware_launch/config/perception/object_recognition/detection/roi_sync.param.yaml rename to autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml diff --git a/autoware_launch/config/perception/object_recognition/detection/object_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml similarity index 100% rename from autoware_launch/config/perception/object_recognition/detection/object_lanelet_filter.param.yaml rename to autoware_launch/config/perception/object_recognition/detection/object_filter/object_lanelet_filter.param.yaml diff --git a/autoware_launch/config/perception/object_recognition/detection/object_position_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_filter/object_position_filter.param.yaml similarity index 100% rename from autoware_launch/config/perception/object_recognition/detection/object_position_filter.param.yaml rename to autoware_launch/config/perception/object_recognition/detection/object_filter/object_position_filter.param.yaml diff --git a/autoware_launch/config/perception/object_recognition/detection/pointcloud_map_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml similarity index 100% rename from autoware_launch/config/perception/object_recognition/detection/pointcloud_map_filter.param.yaml rename to autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml index 5de556ac6f..84c3c1519d 100644 --- a/autoware_launch/launch/components/tier4_perception_component.launch.xml +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -9,24 +9,46 @@ + + + + + + + + + - + + - + + -