Skip to content

Commit 33abcfa

Browse files
apply default param to the param file used for test
delete unused test files Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent c24c3b0 commit 33abcfa

File tree

5 files changed

+46
-956
lines changed

5 files changed

+46
-956
lines changed

control/mpc_lateral_controller/param/lateral_controller_defaults.param.yaml

+41-41
Original file line numberDiff line numberDiff line change
@@ -1,58 +1,58 @@
11
/**:
22
ros__parameters:
33
# -- 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
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
88

99
# -- path smoothing --
10-
enable_path_smoothing: false # flag for path smoothing
10+
enable_path_smoothing: false # flag for path smoothing
1111
path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing
12-
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)
13-
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)
12+
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)
13+
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)
1414

1515
# -- trajectory extending --
16-
extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control
16+
extend_trajectory_for_end_yaw_control: false # flag of trajectory extending for terminal yaw control
1717

1818
# -- mpc optimization --
19-
qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp)
20-
mpc_prediction_horizon: 50 # prediction horizon step
21-
mpc_prediction_dt: 0.1 # prediction horizon period [s]
22-
mpc_weight_lat_error: 0.1 # lateral error weight in matrix Q
23-
mpc_weight_heading_error: 0.0 # heading error weight in matrix Q
24-
mpc_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q
25-
mpc_weight_steering_input: 1.0 # steering error weight in matrix R
26-
mpc_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R
27-
mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R
28-
mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R
29-
mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R
30-
mpc_low_curvature_weight_lat_error: 0.1 # lateral error weight in matrix Q in low curvature point
31-
mpc_low_curvature_weight_heading_error: 0.0 # heading error weight in matrix Q in low curvature point
32-
mpc_low_curvature_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q in low curvature point
33-
mpc_low_curvature_weight_steering_input: 1.0 # steering error weight in matrix R in low curvature point
34-
mpc_low_curvature_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R in low curvature point
35-
mpc_low_curvature_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R in low curvature point
36-
mpc_low_curvature_weight_steer_rate: 0.0 # steering rate weight in matrix R in low curvature point
37-
mpc_low_curvature_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R in low curvature point
38-
mpc_low_curvature_thresh_curvature: 0.0 # threshold of curvature to use "low_curvature" parameter (recommend: 0.01~0.03)
39-
mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability
40-
mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability
41-
mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero
42-
mpc_acceleration_limit: 2.0 # limit on the vehicle's acceleration
43-
mpc_velocity_time_constant: 0.3 # time constant used for velocity smoothing
44-
mpc_min_prediction_length: 5.0 # minimum prediction length
19+
qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp)
20+
mpc_prediction_horizon: 50 # prediction horizon step
21+
mpc_prediction_dt: 0.1 # prediction horizon period [s]
22+
mpc_weight_lat_error: 1.0 # lateral error weight in matrix Q
23+
mpc_weight_heading_error: 0.0 # heading error weight in matrix Q
24+
mpc_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q
25+
mpc_weight_steering_input: 1.0 # steering error weight in matrix R
26+
mpc_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R
27+
mpc_weight_lat_jerk: 0.1 # lateral jerk weight in matrix R
28+
mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R
29+
mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R
30+
mpc_low_curvature_weight_lat_error: 0.1 # lateral error weight in matrix Q in low curvature point
31+
mpc_low_curvature_weight_heading_error: 0.0 # heading error weight in matrix Q in low curvature point
32+
mpc_low_curvature_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q in low curvature point
33+
mpc_low_curvature_weight_steering_input: 1.0 # steering error weight in matrix R in low curvature point
34+
mpc_low_curvature_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R in low curvature point
35+
mpc_low_curvature_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R in low curvature point
36+
mpc_low_curvature_weight_steer_rate: 0.0 # steering rate weight in matrix R in low curvature point
37+
mpc_low_curvature_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R in low curvature point
38+
mpc_low_curvature_thresh_curvature: 0.0 # threshold of curvature to use "low_curvature" parameter (recommend: 0.01~0.03)
39+
mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability
40+
mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability
41+
mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero
42+
mpc_acceleration_limit: 2.0 # limit on the vehicle's acceleration
43+
mpc_velocity_time_constant: 0.3 # time constant used for velocity smoothing
44+
mpc_min_prediction_length: 5.0 # minimum prediction length
4545

4646
# -- vehicle model --
4747
vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics
48-
input_delay: 0.24 # steering input delay time for delay compensation
49-
vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approximation) [s]
50-
steer_rate_lim_dps_list_by_curvature: [10.0, 20.0, 30.0] # steering angle rate limit list depending on curvature [deg/s]
48+
input_delay: 0.24 # steering input delay time for delay compensation
49+
vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approximation) [s]
50+
steer_rate_lim_dps_list_by_curvature: [40.0, 50.0, 60.0] # steering angle rate limit list depending on curvature [deg/s]
5151
curvature_list_for_steer_rate_lim: [0.001, 0.002, 0.01] # curvature list for steering angle rate limit interpolation in ascending order [/m]
52-
steer_rate_lim_dps_list_by_velocity: [40.0, 30.0, 20.0] # steering angle rate limit list depending on velocity [deg/s]
52+
steer_rate_lim_dps_list_by_velocity: [60.0, 50.0, 40.0] # steering angle rate limit list depending on velocity [deg/s]
5353
velocity_list_for_steer_rate_lim: [10.0, 15.0, 20.0] # velocity list for steering angle rate limit interpolation in ascending order [m/s]
54-
acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss]
55-
velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s]
54+
acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss]
55+
velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s]
5656

5757
# -- lowpass filter for noise reduction --
5858
steering_lpf_cutoff_hz: 3.0 # cutoff frequency of lowpass filter for steering command [Hz]
@@ -65,7 +65,7 @@
6565
keep_steer_control_until_converged: true
6666
new_traj_duration_time: 1.0
6767
new_traj_end_dist: 0.3
68-
mpc_converged_threshold_rps: 0.01 # threshold of mpc convergence check [rad/s]
68+
mpc_converged_threshold_rps: 0.01 # threshold of mpc convergence check [rad/s]
6969

7070
# steer offset
7171
steering_offset:

control/pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml

+5-5
Original file line numberDiff line numberDiff line change
@@ -5,19 +5,19 @@
55
enable_smooth_stop: true
66
enable_overshoot_emergency: true
77
enable_large_tracking_error_emergency: true
8-
enable_slope_compensation: false
8+
enable_slope_compensation: true
99
enable_keep_stopped_until_steer_convergence: true
1010

1111
# state transition
1212
drive_state_stop_dist: 0.5
1313
drive_state_offset_stop_dist: 1.0
14-
stopping_state_stop_dist: 0.49
14+
stopping_state_stop_dist: 0.5
1515
stopped_state_entry_duration_time: 0.1
16-
stopped_state_entry_vel: 0.1
16+
stopped_state_entry_vel: 0.01
1717
stopped_state_entry_acc: 0.1
1818
emergency_state_overshoot_stop_dist: 1.5
1919
emergency_state_traj_trans_dev: 3.0
20-
emergency_state_traj_rot_dev: 0.7
20+
emergency_state_traj_rot_dev: 0.7854
2121

2222
# drive state
2323
kp: 1.0
@@ -40,7 +40,7 @@
4040

4141
# smooth stop state
4242
smooth_stop_max_strong_acc: -0.5
43-
smooth_stop_min_strong_acc: -1.0
43+
smooth_stop_min_strong_acc: -0.8
4444
smooth_stop_weak_acc: -0.3
4545
smooth_stop_weak_stop_acc: -0.8
4646
smooth_stop_strong_stop_acc: -3.4

control/trajectory_follower_node/test/test_controller_node.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -56,8 +56,6 @@ rclcpp::NodeOptions makeNodeOptions(const bool enable_keep_stopped_until_steer_c
5656
const auto lateral_share_dir =
5757
ament_index_cpp::get_package_share_directory("mpc_lateral_controller");
5858
rclcpp::NodeOptions node_options;
59-
node_options.append_parameter_override("ctrl_period", 0.03);
60-
node_options.append_parameter_override("timeout_thr_sec", 0.5);
6159
node_options.append_parameter_override("lateral_controller_mode", "mpc");
6260
node_options.append_parameter_override("longitudinal_controller_mode", "pid");
6361
node_options.append_parameter_override(

0 commit comments

Comments
 (0)