From bdb5489a5fd2d494ae3a8477af46b46ca2aa8194 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Thu, 24 Oct 2024 10:06:18 +0900 Subject: [PATCH] feat(autonomous_emergency_braking): change params to cater to urban scenario (#1197) update scenarios Signed-off-by: Daniel Sanchez --- .../autonomous_emergency_braking.param.yaml | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml index f7548536be..710001ec58 100644 --- a/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml +++ b/autoware_launch/config/control/autoware_autonomous_emergency_braking/autonomous_emergency_braking.param.yaml @@ -21,14 +21,14 @@ # Point cloud partitioning detection_range_min_height: 0.0 detection_range_max_height_margin: 0.0 - voxel_grid_x: 0.05 - voxel_grid_y: 0.05 - voxel_grid_z: 100000.0 + voxel_grid_x: 0.1 + voxel_grid_y: 0.1 + voxel_grid_z: 0.5 # Point cloud cropping - expand_width: 0.1 - path_footprint_extra_margin: 4.0 - speed_calculation_expansion_margin: 0.5 + expand_width: -0.2 + path_footprint_extra_margin: 1.0 + speed_calculation_expansion_margin: 0.7 # Point cloud clustering cluster_tolerance: 0.15 #[m] @@ -37,10 +37,10 @@ maximum_cluster_size: 10000 # RSS distance collision check - longitudinal_offset: 2.0 + longitudinal_offset: 1.0 t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0 - collision_keeping_sec: 2.0 + collision_keeping_sec: 3.0 previous_obstacle_keep_time: 1.0 aeb_hz: 10.0