Skip to content

Commit f59ad91

Browse files
Merge branch 'tier4/main' into sync-tier4-upstream
2 parents 3e6f51d + 6ba8e15 commit f59ad91

File tree

100 files changed

+4466
-186
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

100 files changed

+4466
-186
lines changed

.github/workflows/comment-on-pr.yaml

+7-2
Original file line numberDiff line numberDiff line change
@@ -5,19 +5,24 @@ on:
55
types:
66
- opened
77
branches:
8-
- beta/v0.[0-9]+.[1-9]+
8+
- beta/v0.[0-9]+.[0-9]+.[0-9]+
99

1010
jobs:
1111
comment:
1212
runs-on: ubuntu-latest
1313
steps:
1414
- name: Create comments
1515
run: |
16-
cat << EOF > comments
16+
cat << 'EOF' > comments
17+
### betaブランチへマージする際のガイドライン
18+
通常は`Squash and merge`を使用してください。
19+
ただし、cherry-pickで複数の変更を取り込むときには、変更履歴を残すために`Create a merge commit`を使用してください。
20+
1721
### Merging guidelines for the beta branch
1822
Please use `Squash and merge` as the default.
1923
However, when incorporating multiple changes with cherry-pick, use a `Create a merge commit` to preserve the changes in the history.
2024
EOF
25+
2126
- name: Post comments
2227
env:
2328
GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }}
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,14 @@
1+
# These parameters are tuned for xx1
2+
13
/**:
24
ros__parameters:
3-
transition_timeout: 10.0
5+
transition_timeout: 5.0
46
frequency_hz: 10.0
57

68
# set true if you want to engage the autonomous driving mode while the vehicle is driving. If set to false, it will deny Engage in any situation where the vehicle speed is not zero. Note that if you use this feature without adjusting the parameters, it may cause issues like sudden deceleration. Before using, please ensure the engage condition and the vehicle_cmd_gate transition filter are appropriately adjusted.
7-
enable_engage_on_driving: false
9+
enable_engage_on_driving: true
810

9-
check_engage_condition: false # set false if you do not want to care about the engage condition.
11+
check_engage_condition: true # set false if you do not want to care about the engage condition.
1012
nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index
1113
nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index
1214
engage_acceptable_limits:
@@ -19,8 +21,8 @@
1921
lateral_acc_threshold: 1.0
2022
lateral_acc_diff_threshold: 0.5
2123
stable_check:
22-
duration: 0.1
23-
dist_threshold: 1.5
24+
duration: 3.0
25+
dist_threshold: 0.5
2426
speed_upper_threshold: 2.0
2527
speed_lower_threshold: -2.0
2628
yaw_threshold: 0.262
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
/**:
2+
ros__parameters:
3+
# -- system --
4+
traj_resample_dist: 0.1 # path resampling interval [m]
5+
use_steer_prediction: false # flag for using steer prediction (do not use steer measurement)
6+
admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value
7+
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value
8+
use_delayed_initial_state: true
9+
10+
# -- path smoothing --
11+
enable_path_smoothing: false # flag for path smoothing
12+
path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing
13+
curvature_smoothing_num_traj: 15 # point-to-point index distance used in curvature calculation (for trajectory): curvature is calculated from three points p(i-num), p(i), p(i+num)
14+
curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num)
15+
16+
# -- trajectory extending --
17+
extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control
18+
19+
# -- mpc optimization --
20+
qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp)
21+
mpc_prediction_horizon: 50 # prediction horizon step
22+
mpc_prediction_dt: 0.1 # prediction horizon period [s]
23+
mpc_weight_lat_error: 0.2 # lateral error weight in matrix Q
24+
mpc_weight_heading_error: 0.0 # heading error weight in matrix Q
25+
mpc_weight_heading_error_squared_vel: 0.03 # heading error * velocity weight in matrix Q
26+
mpc_weight_steering_input: 1.0 # steering error weight in matrix R
27+
mpc_weight_steering_input_squared_vel: 1.00 # steering error * velocity weight in matrix R
28+
mpc_weight_lat_jerk: 0.1 # lateral jerk weight in matrix R
29+
mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R
30+
mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R
31+
mpc_low_curvature_weight_lat_error: 0.05 # lateral error weight in matrix Q in low curvature point
32+
mpc_low_curvature_weight_heading_error: 0.0 # heading error weight in matrix Q in low curvature point
33+
mpc_low_curvature_weight_heading_error_squared_vel: 0.03 # heading error * velocity weight in matrix Q in low curvature point
34+
mpc_low_curvature_weight_steering_input: 1.0 # steering error weight in matrix R in low curvature point
35+
mpc_low_curvature_weight_steering_input_squared_vel: 2.00 # steering error * velocity weight in matrix R in low curvature point
36+
mpc_low_curvature_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R in low curvature point
37+
mpc_low_curvature_weight_steer_rate: 0.0 # steering rate weight in matrix R in low curvature point
38+
mpc_low_curvature_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R in low curvature point
39+
mpc_low_curvature_thresh_curvature: 0.03 # threshold of curvature to use "low_curvature" parameter (recommend: 0.01~0.03)
40+
mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability
41+
mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability
42+
mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero
43+
mpc_acceleration_limit: 2.0 # limit on the vehicle's acceleration
44+
mpc_velocity_time_constant: 0.3 # time constant used for velocity smoothing
45+
mpc_min_prediction_length: 5.0 # minimum prediction length
46+
47+
# -- vehicle model --
48+
vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics
49+
input_delay: 0.1 # steering input delay time for delay compensation
50+
vehicle_model_steer_tau: 0.1 # steering dynamics time constant (1d approximation) [s]
51+
steer_rate_lim_dps_list_by_curvature: [20.0, 20.0, 20.0] # steering angle rate limit list depending on curvature [deg/s]
52+
curvature_list_for_steer_rate_lim: [0.001, 0.002, 0.01] # curvature list for steering angle rate limit interpolation in ascending order [/m]
53+
steer_rate_lim_dps_list_by_velocity: [18.0, 18.0, 15.0, 12.0, 5.0, 2.25, 1.5 , 1.5 , 1.5] # steering angle rate limit list depending on velocity [deg/s] [72, 72, 36, 18, 9, 3.6, 3.6]
54+
velocity_list_for_steer_rate_lim: [0.0, 1.388, 2.778, 4.167, 5.556, 6.944, 8.333, 9.722, 11.11] # velocity list for steering angle rate limit interpolation in ascending order [m/s]
55+
acceleration_limit: 1.0 # acceleration limit for trajectory velocity modification [m/ss]
56+
velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s]
57+
58+
# -- lowpass filter for noise reduction --
59+
steering_lpf_cutoff_hz: 10.0 # cutoff frequency of lowpass filter for steering command [Hz]
60+
error_deriv_lpf_cutoff_hz: 5.0
61+
62+
# stop state: steering command is kept in the previous value in the stop state.
63+
stop_state_entry_ego_speed: 0.2
64+
stop_state_entry_target_speed: 0.2
65+
converged_steer_rad: 0.1
66+
keep_steer_control_until_converged: true
67+
new_traj_duration_time: 1.0
68+
new_traj_end_dist: 0.3
69+
mpc_converged_threshold_rps: 0.01 # threshold of mpc convergence check [rad/s]
70+
71+
# steer offset
72+
steering_offset:
73+
enable_auto_steering_offset_removal: true
74+
update_vel_threshold: 5.56
75+
update_steer_threshold: 0.035
76+
average_num: 1000
77+
steering_offset_limit: 0.02
78+
79+
publish_debug_trajectories: true # flag to publish predicted trajectory and resampled reference trajectory for debug purpose
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
/**:
2+
ros__parameters:
3+
delay_compensation_time: 0.40
4+
5+
enable_smooth_stop: true
6+
enable_overshoot_emergency: false
7+
enable_large_tracking_error_emergency: false
8+
enable_slope_compensation: true
9+
enable_keep_stopped_until_steer_convergence: true
10+
11+
# state transition
12+
drive_state_stop_dist: 0.5
13+
drive_state_offset_stop_dist: 1.0
14+
stopping_state_stop_dist: 0.49
15+
stopped_state_entry_duration_time: 0.1
16+
stopped_state_entry_vel: 0.01
17+
stopped_state_entry_acc: 0.1
18+
emergency_state_overshoot_stop_dist: 1.5
19+
emergency_state_traj_trans_dev: 3.0
20+
emergency_state_traj_rot_dev: 0.7854
21+
22+
# drive state
23+
kp: 2.0
24+
ki: 0.01
25+
kd: 0.1
26+
max_out: 1.0
27+
min_out: -5.0
28+
max_p_effort: 0.5
29+
min_p_effort: -5.0
30+
max_i_effort: 0.3
31+
min_i_effort: -0.3
32+
max_d_effort: 0.3
33+
min_d_effort: -0.3
34+
lpf_vel_error_gain: 0.9
35+
enable_integration_at_low_speed: false
36+
current_vel_threshold_pid_integration: 0.5
37+
time_threshold_before_pid_integration: 2.0
38+
enable_brake_keeping_before_stop: false
39+
brake_keeping_acc: -0.2
40+
41+
# smooth stop state
42+
smooth_stop_max_strong_acc: -0.8
43+
smooth_stop_min_strong_acc: -1.3
44+
smooth_stop_weak_acc: -0.6
45+
smooth_stop_weak_stop_acc: -0.8
46+
smooth_stop_strong_stop_acc: -3.4
47+
smooth_stop_max_fast_vel: 0.5
48+
smooth_stop_min_running_vel: 0.01
49+
smooth_stop_min_running_acc: 0.01
50+
smooth_stop_weak_stop_time: 0.8
51+
smooth_stop_weak_stop_dist: -0.3
52+
smooth_stop_strong_stop_dist: -0.5
53+
54+
# stopped state
55+
stopped_vel: 0.0
56+
stopped_acc: -3.4 # denotes pedal position
57+
58+
# emergency state
59+
emergency_vel: 0.0
60+
emergency_acc: -5.0 # denotes acceleration
61+
emergency_jerk: -3.0
62+
63+
# acceleration feedback
64+
lpf_acc_error_gain: 0.98
65+
acc_feedback_gain: 0.0
66+
67+
# acceleration limit
68+
max_acc: 3.0
69+
min_acc: -5.0
70+
71+
# jerk limit
72+
max_jerk: 3.5
73+
min_jerk: -5.0
74+
max_acc_cmd_diff: 50.0 # [m/s^2 * s^-1]
75+
76+
77+
# slope compensation
78+
lpf_pitch_gain: 0.95
79+
slope_source: "raw_pitch" # raw_pitch, trajectory_pitch or trajectory_adaptive
80+
adaptive_trajectory_velocity_th: 1.0
81+
max_pitch_rad: 0.1
82+
min_pitch_rad: -0.1
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
/**:
2+
ros__parameters:
3+
# -- system --
4+
traj_resample_dist: 0.1 # path resampling interval [m]
5+
use_steer_prediction: false # flag for using steer prediction (do not use steer measurement)
6+
admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value
7+
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value
8+
use_delayed_initial_state: true
9+
10+
# -- path smoothing --
11+
enable_path_smoothing: false # flag for path smoothing
12+
path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing
13+
curvature_smoothing_num_traj: 15 # point-to-point index distance used in curvature calculation (for trajectory): curvature is calculated from three points p(i-num), p(i), p(i+num)
14+
curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num)
15+
16+
# -- trajectory extending --
17+
extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control
18+
19+
# -- mpc optimization --
20+
qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp)
21+
mpc_prediction_horizon: 50 # prediction horizon step
22+
mpc_prediction_dt: 0.1 # prediction horizon period [s]
23+
mpc_weight_lat_error: 0.2 # lateral error weight in matrix Q
24+
mpc_weight_heading_error: 0.0 # heading error weight in matrix Q
25+
mpc_weight_heading_error_squared_vel: 0.03 # heading error * velocity weight in matrix Q
26+
mpc_weight_steering_input: 1.0 # steering error weight in matrix R
27+
mpc_weight_steering_input_squared_vel: 1.00 # steering error * velocity weight in matrix R
28+
mpc_weight_lat_jerk: 0.1 # lateral jerk weight in matrix R
29+
mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R
30+
mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R
31+
mpc_low_curvature_weight_lat_error: 0.05 # lateral error weight in matrix Q in low curvature point
32+
mpc_low_curvature_weight_heading_error: 0.0 # heading error weight in matrix Q in low curvature point
33+
mpc_low_curvature_weight_heading_error_squared_vel: 0.03 # heading error * velocity weight in matrix Q in low curvature point
34+
mpc_low_curvature_weight_steering_input: 1.0 # steering error weight in matrix R in low curvature point
35+
mpc_low_curvature_weight_steering_input_squared_vel: 2.00 # steering error * velocity weight in matrix R in low curvature point
36+
mpc_low_curvature_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R in low curvature point
37+
mpc_low_curvature_weight_steer_rate: 0.0 # steering rate weight in matrix R in low curvature point
38+
mpc_low_curvature_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R in low curvature point
39+
mpc_low_curvature_thresh_curvature: 0.03 # threshold of curvature to use "low_curvature" parameter (recommend: 0.01~0.03)
40+
mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability
41+
mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability
42+
mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero
43+
mpc_acceleration_limit: 2.0 # limit on the vehicle's acceleration
44+
mpc_velocity_time_constant: 0.3 # time constant used for velocity smoothing
45+
mpc_min_prediction_length: 5.0 # minimum prediction length
46+
47+
# -- vehicle model --
48+
vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics
49+
input_delay: 0.1 # steering input delay time for delay compensation
50+
vehicle_model_steer_tau: 0.1 # steering dynamics time constant (1d approximation) [s]
51+
steer_rate_lim_dps_list_by_curvature: [20.0, 20.0, 20.0] # steering angle rate limit list depending on curvature [deg/s]
52+
curvature_list_for_steer_rate_lim: [0.001, 0.002, 0.01] # curvature list for steering angle rate limit interpolation in ascending order [/m]
53+
steer_rate_lim_dps_list_by_velocity: [18.0, 18.0, 15.0, 12.0, 5.0, 2.25, 1.5 , 1.5 , 1.5] # steering angle rate limit list depending on velocity [deg/s] [72, 72, 36, 18, 9, 3.6, 3.6]
54+
velocity_list_for_steer_rate_lim: [0.0, 1.388, 2.778, 4.167, 5.556, 6.944, 8.333, 9.722, 11.11] # velocity list for steering angle rate limit interpolation in ascending order [m/s]
55+
acceleration_limit: 1.0 # acceleration limit for trajectory velocity modification [m/ss]
56+
velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s]
57+
58+
# -- lowpass filter for noise reduction --
59+
steering_lpf_cutoff_hz: 10.0 # cutoff frequency of lowpass filter for steering command [Hz]
60+
error_deriv_lpf_cutoff_hz: 5.0
61+
62+
# stop state: steering command is kept in the previous value in the stop state.
63+
stop_state_entry_ego_speed: 0.2
64+
stop_state_entry_target_speed: 0.2
65+
converged_steer_rad: 0.1
66+
keep_steer_control_until_converged: true
67+
new_traj_duration_time: 1.0
68+
new_traj_end_dist: 0.3
69+
mpc_converged_threshold_rps: 0.01 # threshold of mpc convergence check [rad/s]
70+
71+
# steer offset
72+
steering_offset:
73+
enable_auto_steering_offset_removal: true
74+
update_vel_threshold: 5.56
75+
update_steer_threshold: 0.035
76+
average_num: 1000
77+
steering_offset_limit: 0.02
78+
79+
publish_debug_trajectories: true # flag to publish predicted trajectory and resampled reference trajectory for debug purpose
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
/**:
2+
ros__parameters:
3+
delay_compensation_time: 0.40
4+
5+
enable_smooth_stop: true
6+
enable_overshoot_emergency: false
7+
enable_large_tracking_error_emergency: false
8+
enable_slope_compensation: true
9+
enable_keep_stopped_until_steer_convergence: true
10+
11+
# state transition
12+
drive_state_stop_dist: 0.5
13+
drive_state_offset_stop_dist: 1.0
14+
stopping_state_stop_dist: 0.49
15+
stopped_state_entry_duration_time: 0.1
16+
stopped_state_entry_vel: 0.01
17+
stopped_state_entry_acc: 0.1
18+
emergency_state_overshoot_stop_dist: 1.5
19+
emergency_state_traj_trans_dev: 3.0
20+
emergency_state_traj_rot_dev: 0.7854
21+
22+
# drive state
23+
kp: 2.0
24+
ki: 0.02
25+
kd: 0.0
26+
max_out: 1.0
27+
min_out: -5.0
28+
max_p_effort: 0.5
29+
min_p_effort: -5.0
30+
max_i_effort: 0.3
31+
min_i_effort: -0.3
32+
max_d_effort: 0.0
33+
min_d_effort: 0.0
34+
lpf_vel_error_gain: 0.9
35+
enable_integration_at_low_speed: false
36+
current_vel_threshold_pid_integration: 0.5
37+
time_threshold_before_pid_integration: 2.0
38+
enable_brake_keeping_before_stop: false
39+
brake_keeping_acc: -0.2
40+
41+
# smooth stop state
42+
smooth_stop_max_strong_acc: -0.8
43+
smooth_stop_min_strong_acc: -1.3
44+
smooth_stop_weak_acc: -0.6
45+
smooth_stop_weak_stop_acc: -0.8
46+
smooth_stop_strong_stop_acc: -3.4
47+
smooth_stop_max_fast_vel: 0.5
48+
smooth_stop_min_running_vel: 0.01
49+
smooth_stop_min_running_acc: 0.01
50+
smooth_stop_weak_stop_time: 0.8
51+
smooth_stop_weak_stop_dist: -0.3
52+
smooth_stop_strong_stop_dist: -0.5
53+
54+
# stopped state
55+
stopped_vel: 0.0
56+
stopped_acc: -3.4 # denotes acceleration
57+
58+
# emergency state
59+
emergency_vel: 0.0
60+
emergency_acc: -5.0 # denotes acceleration
61+
62+
emergency_jerk: -3.0
63+
64+
# acceleration feedback
65+
lpf_acc_error_gain: 0.98
66+
acc_feedback_gain: 0.0
67+
68+
# acceleration limit
69+
max_acc: 3.0
70+
min_acc: -5.0
71+
72+
# jerk limit
73+
max_jerk: 3.5
74+
min_jerk: -5.0
75+
max_acc_cmd_diff: 50.0 # [m/s^2 * s^-1]
76+
77+
# slope compensation
78+
lpf_pitch_gain: 0.95
79+
slope_source: "raw_pitch" # raw_pitch, trajectory_pitch or trajectory_adaptive
80+
adaptive_trajectory_velocity_th: 1.0
81+
max_pitch_rad: 0.1
82+
min_pitch_rad: -0.1

0 commit comments

Comments
 (0)