-
Notifications
You must be signed in to change notification settings - Fork 718
/
Copy pathdefault_velocity_smoother.param.yaml
63 lines (54 loc) · 4.59 KB
/
default_velocity_smoother.param.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
/**:
ros__parameters:
# motion state constraints
max_velocity: 20.0 # max velocity limit [m/s]
stop_decel: 0.0 # deceleration at a stop point[m/ss]
# external velocity limit parameter
margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m]
# ---- 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]
# - 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: 0.8 # 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
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]
resample_ds: 0.1 # distance between trajectory points [m]
curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]
# engage & replan parameters
replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s]
engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed)
engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement)
engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity.
stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m]
# stop velocity
stopping_velocity: 2.778 # change target velocity to this value before v=0 point [m/s]
stopping_distance: 0.0 # distance for the stopping_velocity [m]. 0 means the stopping velocity is not applied.
# path extraction parameters
extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m]
extract_behind_dist: 5.0 # backward trajectory distance used for planning [m]
delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajectory pose [radian]
# resampling parameters for optimization
max_trajectory_length: 200.0 # max trajectory length for resampling [m]
min_trajectory_length: 150.0 # min trajectory length for resampling [m]
resample_time: 2.0 # resample total time for dense sampling [s]
dense_resample_dt: 0.2 # resample time interval for dense sampling [s]
dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m]
sparse_resample_dt: 0.5 # resample time interval for sparse sampling [s]
sparse_min_interval_distance: 4.0 # minimum points-interval length for sparse sampling [m]
# resampling parameters for post process
post_max_trajectory_length: 300.0 # max trajectory length for resampling [m]
post_min_trajectory_length: 30.0 # min trajectory length for resampling [m]
post_resample_time: 10.0 # resample total time for dense sampling [s]
post_dense_resample_dt: 0.1 # resample time interval for dense sampling [s]
post_dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m]
post_sparse_resample_dt: 0.1 # resample time interval for sparse sampling [s]
post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m]
# system
over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point
plan_from_ego_speed_on_manual_mode: true # planning is done from ego velocity/acceleration on MANUAL mode. This should be true for smooth transition from MANUAL to AUTONOMOUS, but could be false for debugging.