Skip to content

Commit 5d5b3a6

Browse files
fix(planning_launch): align parameters to real vehicle (#848)
update param Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
1 parent 4abad00 commit 5d5b3a6

File tree

1 file changed

+3
-3
lines changed

1 file changed

+3
-3
lines changed

autoware_launch/config/planning/scenario_planning/common/motion_velocity_smoother/motion_velocity_smoother.param.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -9,17 +9,17 @@
99

1010
# -- curve parameters --
1111
# common parameters
12-
curvature_calculation_distance: 5.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m]
12+
curvature_calculation_distance: 2.0 # distance of points while curvature is calculating for the steer rate and lateral acceleration limit [m]
1313
# lateral acceleration limit parameters
1414
enable_lateral_acc_limit: true # To toggle the lateral acc filter on and off. You can switch it dynamically at runtime.
1515
max_lateral_accel: 1.0 # max lateral acceleration limit [m/ss]
16-
min_curve_velocity: 2.74 # min velocity at lateral acceleration limit and steering angle rate limit [m/s]
16+
min_curve_velocity: 2.0 # min velocity at lateral acceleration limit and steering angle rate limit [m/s]
1717
decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit
1818
decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit
1919
min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss]
2020
# steering angle rate limit parameters
2121
enable_steering_rate_limit: true # To toggle the steer rate filter on and off. You can switch it dynamically at runtime.
22-
max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s]
22+
max_steering_angle_rate: 11.5 # maximum steering angle rate [degree/s]
2323
resample_ds: 0.1 # distance between trajectory points [m]
2424
curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]
2525

0 commit comments

Comments
 (0)