diff --git a/control/trajectory_follower_nodes/design/lateral_controller-design.md b/control/trajectory_follower_nodes/design/lateral_controller-design.md
index 450e7d04707d3..668b96b4a7641 100644
--- a/control/trajectory_follower_nodes/design/lateral_controller-design.md
+++ b/control/trajectory_follower_nodes/design/lateral_controller-design.md
@@ -66,7 +66,7 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving.
| stop_state_entry_ego_speed \*1 | double | threshold value of the ego vehicle speed used to the stop state entry condition | 0.0 |
| stop_state_entry_target_speed \*1 | double | threshold value of the target speed used to the stop state entry condition | 0.0 |
| converged_steer_rad | double | threshold value of the steer convergence | 0.1 |
-| keep_steer_control_until_converged | bool | keep steer control until steer is converged | false |
+| keep_steer_control_until_converged | bool | keep steer control until steer is converged | true |
| new_traj_duration_time | double | threshold value of the time to be considered as new trajectory | 1.0 |
| new_traj_end_dist | double | threshold value of the distance between trajectory ends to be considered as new trajectory | 0.3 |
diff --git a/control/trajectory_follower_nodes/design/longitudinal_controller-design.md b/control/trajectory_follower_nodes/design/longitudinal_controller-design.md
index 207a9755d7117..d3512c0a36471 100644
--- a/control/trajectory_follower_nodes/design/longitudinal_controller-design.md
+++ b/control/trajectory_follower_nodes/design/longitudinal_controller-design.md
@@ -154,7 +154,7 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving.
| enable_large_tracking_error_emergency | bool | flag to enable transition to EMERGENCY when the closest trajectory point search is failed due to a large deviation between trajectory and ego pose. | true |
| enable_slope_compensation | bool | flag to modify output acceleration for slope compensation. The source of the slope angle can be selected from ego-pose or trajectory angle. See `use_trajectory_for_pitch_calculation`. | true |
| enable_brake_keeping_before_stop | bool | flag to keep a certain acceleration during DRIVE state before the ego stops. See [Brake keeping](#brake-keeping). | false |
-| enable_keep_stopped_until_steer_convergence | bool | flag to keep stopped condition until until the steer converges. | false |
+| enable_keep_stopped_until_steer_convergence | bool | flag to keep stopped condition until until the steer converges. | true |
| max_acc | double | max value of output acceleration [m/s^2] | 3.0 |
| min_acc | double | min value of output acceleration [m/s^2] | -5.0 |
| max_jerk | double | max value of jerk of output acceleration [m/s^3] | 2.0 |
diff --git a/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml b/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml
index f21ef8f81fa6c..a6d98fa682d74 100644
--- a/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml
+++ b/control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml
@@ -56,7 +56,7 @@
stop_state_entry_ego_speed: 0.001
stop_state_entry_target_speed: 0.001
converged_steer_rad: 0.1
- keep_steer_control_until_converged: false
+ keep_steer_control_until_converged: true
new_traj_duration_time: 1.0
new_traj_end_dist: 0.3
diff --git a/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml b/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml
index e5e82ec101be2..eb2ef443c4576 100644
--- a/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml
+++ b/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.param.yaml
@@ -6,7 +6,7 @@
enable_overshoot_emergency: true
enable_large_tracking_error_emergency: true
enable_slope_compensation: false
- enable_keep_stopped_until_steer_convergence: false
+ enable_keep_stopped_until_steer_convergence: true
# state transition
drive_state_stop_dist: 0.5
diff --git a/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml b/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml
index e69e599d198ec..c786daee07d24 100644
--- a/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml
+++ b/launch/tier4_control_launch/config/trajectory_follower/lateral_controller.param.yaml
@@ -57,7 +57,7 @@
stop_state_entry_ego_speed: 0.001
stop_state_entry_target_speed: 0.001
converged_steer_rad: 0.1
- keep_steer_control_until_converged: false
+ keep_steer_control_until_converged: true
new_traj_duration_time: 1.0
new_traj_end_dist: 0.3
diff --git a/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml b/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml
index 28fa297afbecb..b6e1c3a38c799 100644
--- a/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml
+++ b/launch/tier4_control_launch/config/trajectory_follower/longitudinal_controller.param.yaml
@@ -6,7 +6,7 @@
enable_overshoot_emergency: true
enable_large_tracking_error_emergency: true
enable_slope_compensation: false
- enable_keep_stopped_until_steer_convergence: false
+ enable_keep_stopped_until_steer_convergence: true
# state transition
drive_state_stop_dist: 0.5