From cb7e34612252b940e249ae90aff17d21fb837601 Mon Sep 17 00:00:00 2001 From: t4-adc Date: Tue, 28 Jan 2025 16:07:02 +0000 Subject: [PATCH] change parameters for eve Signed-off-by: t4-adc --- .../planning/preset/default_preset.yaml | 34 +++++++++---------- .../common/common.param.yaml | 6 ++-- 2 files changed, 20 insertions(+), 20 deletions(-) diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml index 0ffeeeccf0..8914af1193 100644 --- a/autoware_launch/config/planning/preset/default_preset.yaml +++ b/autoware_launch/config/planning/preset/default_preset.yaml @@ -2,22 +2,22 @@ launch: # behavior path modules - arg: name: launch_static_obstacle_avoidance - default: "true" + default: "false" - arg: name: launch_avoidance_by_lane_change_module - default: "true" + default: "false" - arg: name: launch_dynamic_obstacle_avoidance - default: "true" + default: "false" - arg: name: launch_sampling_planner_module default: "false" # Warning, experimental module, use only in simulations - arg: name: launch_lane_change_right_module - default: "true" + default: "false" - arg: name: launch_lane_change_left_module - default: "true" + default: "false" - arg: name: launch_external_request_lane_change_right_module default: "false" @@ -26,42 +26,42 @@ launch: default: "false" - arg: name: launch_goal_planner_module - default: "true" + default: "false" - arg: name: launch_start_planner_module - default: "true" + default: "false" - arg: name: launch_side_shift_module - default: "true" + default: "false" # behavior velocity modules - arg: name: launch_crosswalk_module - default: "true" + default: "false" - arg: name: launch_walkway_module - default: "true" + default: "false" - arg: name: launch_traffic_light_module - default: "true" + default: "false" - arg: name: launch_intersection_module - default: "true" + default: "false" - arg: name: launch_merge_from_private_module - default: "true" + default: "false" - arg: name: launch_blind_spot_module - default: "true" + default: "false" - arg: name: launch_detection_area_module default: "true" - arg: name: launch_virtual_traffic_light_module - default: "false" + default: "true" - arg: name: launch_no_stopping_area_module - default: "true" + default: "false" - arg: name: launch_stop_line_module default: "true" @@ -70,7 +70,7 @@ launch: default: "false" - arg: name: launch_run_out_module - default: "true" + default: "false" - arg: name: launch_speed_bump_module default: "false" diff --git a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml index 5680a99713..814d0ba17e 100644 --- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml @@ -4,9 +4,9 @@ # constraints param for normal driving normal: - min_acc: -1.0 # min deceleration [m/ss] - max_acc: 1.0 # max acceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] + min_acc: -0.2 # min deceleration [m/ss] + max_acc: 0.5 # max acceleration [m/ss] + min_jerk: -0.5 # min jerk [m/sss] max_jerk: 1.0 # max jerk [m/sss] # constraints to be observed