From c4c9ff0f2eeeffd8de44d322ffa8d35c0d2233b7 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 12 Mar 2024 00:13:24 +0900 Subject: [PATCH] feat: sp tuning for low obstacle (#578) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat: tune condition of between cruise and stop (#565) Tune condition of between cruise and stop * fix(traffic_light): stop if the traffic light signal timed out (#727) (#571) Signed-off-by: Fumiya Watanabe Co-authored-by: Fumiya Watanabe * feat(component_state_monitor): monitor traffic light recognition outp… (#572) feat(component_state_monitor): monitor traffic light recognition output (#720) Signed-off-by: Tomohito Ando * update ground segmentation Signed-off-by: yoshiri * update comparemap parameter Signed-off-by: yoshiri * update clustering parameters Signed-off-by: yoshiri * fix tracking iou threshold parameters Signed-off-by: yoshiri * feat: set smaller threshold for euclidean clustering Signed-off-by: yoshiri * chore: fit parameter for v3.0.0 Signed-off-by: yoshiri --------- Signed-off-by: Fumiya Watanabe Signed-off-by: Tomohito Ando Signed-off-by: yoshiri Co-authored-by: Shohei Sakai Co-authored-by: Tomohito ANDO Co-authored-by: Fumiya Watanabe Co-authored-by: Shinnosuke Hirakawa <8327162+0x126@users.noreply.github.com> --- ...voxel_grid_based_euclidean_cluster.param.yaml | 2 +- .../pointcloud_map_filter.param.yaml | 4 ++-- .../data_association_matrix.param.yaml | 2 +- .../ground_segmentation.param.yaml | 16 ++++++++-------- 4 files changed, 12 insertions(+), 12 deletions(-) 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 26b027f007..b99612ab8f 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 @@ -3,7 +3,7 @@ tolerance: 0.7 voxel_leaf_size: 0.3 min_points_number_per_voxel: 1 - min_cluster_size: 10 + min_cluster_size: 3 max_cluster_size: 3000 use_height: false input_frame: "base_link" 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 62b3074c15..5b9ad199fa 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 @@ -2,13 +2,13 @@ ros__parameters: # voxel size for downsample filter - down_sample_voxel_size: 0.1 + down_sample_voxel_size: 0.05 # distance threshold for compare compare distance_threshold: 0.5 # ratio to reduce voxel_leaf_size and neighbor points distance threshold in z axis - downsize_ratio_z_axis: 0.6 + downsize_ratio_z_axis: 0.3 # publish voxelized map pointcloud for debug publish_debug_pcd: False diff --git a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml index 13f2220655..9743a9ce59 100644 --- a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml +++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -56,7 +56,7 @@ min_iou_matrix: # If value is negative, it will be ignored. #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN - [0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN + [0.0, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN 0.1, 0.1, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS diff --git a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml index 53c20b5813..37edca19e0 100644 --- a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml +++ b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - additional_lidars: [] + additional_lidars: ["front_lower"] ransac_input_topics: [] use_single_frame_filter: False use_time_series_filter: True @@ -20,10 +20,10 @@ parameters: global_slope_max_angle_deg: 10.0 local_slope_max_angle_deg: 25.0 # recommended 30.0 for non elevation_grid_mode - split_points_distance_tolerance: 0.2 + split_points_distance_tolerance: 0.15 use_virtual_ground_point: True split_height_distance: 0.2 - non_ground_height_threshold: 0.20 + non_ground_height_threshold: 0.12 grid_size_m: 0.2 grid_mode_switch_radius: 20.0 gnd_grid_buffer_size: 5 @@ -54,7 +54,7 @@ global_slope_max_angle_deg: 10.0 local_slope_max_angle_deg: 18.0 # recommended 30.0 for non elevation_grid_mode split_points_distance_tolerance: 0.20 # recommended 0.045 for non elevation_grid_mode - split_height_distance: 0.2 # recommended 0.15 for non elevation_grid_mode + split_height_distance: 0.15 # recommended 0.15 for non elevation_grid_mode use_virtual_ground_point: False non_ground_height_threshold: 0.1 grid_size_m: 0.1 @@ -79,14 +79,14 @@ parameters: global_slope_max_angle_deg: 10.0 local_slope_max_angle_deg: 18.0 # recommended 30.0 for non elevation_grid_mode - split_points_distance_tolerance: 0.20 # recommended 0.1 for non elevation_grid_mode - split_height_distance: 0.2 # recommended 0.05 for non elevation_grid_mode - use_virtual_ground_point: False + split_points_distance_tolerance: 0.10 # recommended 0.1 for non elevation_grid_mode + split_height_distance: 0.05 # recommended 0.05 for non elevation_grid_mode + use_virtual_ground_point: true non_ground_height_threshold: 0.1 grid_size_m: 0.1 grid_mode_switch_radius: 20.0 gnd_grid_buffer_size: 4 detection_range_z_max: 3.2 center_pcl_shift: 0.0 - elevation_grid_mode: true + elevation_grid_mode: false use_recheck_ground_cluster: false