From 5d5b3a6e1c90c443eebe14bfb0fb03f4780b09cf Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 2 Feb 2024 20:09:02 +0900 Subject: [PATCH] fix(planning_launch): align parameters to real vehicle (#848) update param Signed-off-by: Yuki Takagi --- .../motion_velocity_smoother.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml index 235c76a5c1..4b6693f150 100644 --- a/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml @@ -9,17 +9,17 @@ # -- curve parameters -- # common parameters - curvature_calculation_distance: 5.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m] + curvature_calculation_distance: 2.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m] # lateral acceleration limit parameters enable_lateral_acc_limit: true # To toggle the lateral acc filter on and off. You can switch it dynamically at runtime. max_lateral_accel: 1.0 # max lateral acceleration limit [m/ss] - min_curve_velocity: 2.74 # min velocity at lateral acceleration limit and steering angle rate limit [m/s] + min_curve_velocity: 2.0 # min velocity at lateral acceleration limit and steering angle rate limit [m/s] decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss] # steering angle rate limit parameters enable_steering_rate_limit: true # To toggle the steer rate filter on and off. You can switch it dynamically at runtime. - max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s] + max_steering_angle_rate: 11.5 # maximum steering angle rate [degree/s] resample_ds: 0.1 # distance between trajectory points [m] curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]