From 1a1aed422a2c4940ac331dcd3996335593832ed0 Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Tue, 19 Sep 2023 11:28:32 +0900 Subject: [PATCH] refactor(perception): rearrange clustering pipeline parameters (#567) (#638) * fix: use downsample before compare map Signed-off-by: badai-nguyen * fix: remove downsample after compare map Signed-off-by: badai-nguyen * fix: add low range crop filter param Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen # Conflicts: # autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml # autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml --- .../clustering/compare_map.param.yaml | 20 ------------------- .../detection/clustering/outlier.param.yaml | 8 -------- .../clustering/voxel_grid.param.yaml | 7 ------- ...el_grid_based_euclidean_cluster.param.yaml | 14 +++++++------ .../pointcloud_map_filter.param.yaml | 2 -- .../tier4_perception_component.launch.xml | 5 ----- 6 files changed, 8 insertions(+), 48 deletions(-) delete mode 100644 autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml delete mode 100644 autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml delete mode 100644 autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml 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 deleted file mode 100644 index 3dd303464a..0000000000 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml +++ /dev/null @@ -1,20 +0,0 @@ -/**: - 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/outlier.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml deleted file mode 100644 index 1962fba1f3..0000000000 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml +++ /dev/null @@ -1,8 +0,0 @@ -/**: - 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 deleted file mode 100644 index 3ff32bfbb7..0000000000 --- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml +++ /dev/null @@ -1,7 +0,0 @@ -/**: - 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 index 6edaa123a8..26b027f007 100644 --- 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 @@ -7,9 +7,11 @@ max_cluster_size: 3000 use_height: false input_frame: "base_link" - max_x: 15.0 - min_x: -10.0 - max_y: 10.0 - min_y: -10.0 - max_z: 10.0 - min_z: -4.5 + + # low height crop box filter param + max_x: 200.0 + min_x: -200.0 + max_y: 200.0 + min_y: -200.0 + max_z: 2.0 + min_z: -10.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml index 3b10100a04..62b3074c15 100644 --- a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml @@ -1,7 +1,5 @@ /**: ros__parameters: - # use downsample filter before compare map - use_down_sample_filter: True # voxel size for downsample filter down_sample_voxel_size: 0.1 diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml index a9d62c9270..1ea11e73d6 100644 --- a/autoware_launch/launch/components/tier4_perception_component.launch.xml +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -25,16 +25,11 @@ - -