From bac30320fecdd6963806eba6d8571659fee71ece Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 21 Sep 2023 14:36:32 +0900 Subject: [PATCH] chore(motion_velocity_smoother): add enable curve filtering param Signed-off-by: Takamasa Horibe --- .../motion_velocity_smoother.param.yaml | 2 ++ 1 file changed, 2 insertions(+) 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 868b1bd15c..1d0f47b261 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 @@ -8,6 +8,7 @@ margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m] # curve 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] decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit @@ -49,6 +50,7 @@ post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m] # 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] resample_ds: 0.1 # distance between trajectory points [m] curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]