Skip to content

Commit

Permalink
load velocity_controller_param.yaml from launcher (autowarefoundation#52
Browse files Browse the repository at this point in the history
)

Signed-off-by: Shinnosuke Hirakawa <shinnosuke.hirakawa@tier4.jp>
  • Loading branch information
0x126 authored and tkimura4 committed Dec 10, 2021
1 parent e9da1b5 commit 0eee7c5
Show file tree
Hide file tree
Showing 2 changed files with 60 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
# closest waypoint threshold
closest_waypoint_distance_threshold: 3.0
closest_waypoint_angle_threshold: 0.7854

# stop state
stop_state_velocity: 0.0
stop_state_acc: -3.4
stop_state_entry_ego_speed: 0.2
stop_state_entry_target_speed: 0.1

# delay compensation
delay_compensation_time: 0.17

# emergency stop by this controller
emergency_stop_acc: -5.0
emergency_stop_jerk: -3.0

# smooth stop
smooth_stop:
exit_ego_speed: 1.0
entry_ego_speed: 0.8
exit_target_speed: 1.0
entry_target_speed: 0.2
weak_brake_time: 1.0
weak_brake_acc: -1.0
increasing_brake_time: 1.0
increasing_brake_gradient: -0.1
stop_brake_time: 1.0
stop_brake_acc: -3.4

# acceleration limit
max_acc: 3.0
min_acc: -5.0

# jerk limit
max_jerk: 2.0
min_jerk: -5.0

# slope compensation
max_pitch_rad: 0.1
min_pitch_rad: -0.1
lpf_pitch_gain: 0.95

# velocity feedback
pid_controller:
kp: 1.0
ki: 0.1
kd: 0
max_out: 1.0
min_out: -1.0
max_p_effort: 1.0
min_p_effort: -1.0
max_i_effort: 0.3
min_i_effort: -0.3
max_d_effort: 0
min_d_effort: 0
current_velocity_threshold_pid_integration: 0.5
lpf_velocity_error_gain: 0.9
2 changes: 2 additions & 0 deletions launch/control_launch/launch/control.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<!-- control parameter -->
<arg name="mpc_follower_param_path" default="$(find control_launch)/config/mpc_follower/mpc_follower_param.yaml"/>
<arg name="pure_pursuit_param_path" default="$(find control_launch)/config/pure_pursuit/pure_pursuit_param.yaml"/>
<arg name="velocity_controller_param_path" default="$(find control_launch)/config/velocity_controller/velocity_controller_param.yaml"/>

<!-- control module -->
<group ns="control">
Expand All @@ -25,6 +26,7 @@

<!-- longitudinal controller -->
<include file="$(find velocity_controller)/launch/velocity_controller.launch">
<arg name="velocity_controller_param_path" value="$(arg velocity_controller_param_path)"/>
</include>

<!-- latlon coupler -->
Expand Down

0 comments on commit 0eee7c5

Please sign in to comment.