diff --git a/config/adc_car_move_base/local_planner/ackermann_params.yaml b/config/adc_car_move_base/local_planner/ackermann_params.yaml
index 1aa1eeae513e55e06fc485653f943102f2faf192..46cc01c82005b80c5f1f8bc756eec0b31ae7b911 100644
--- a/config/adc_car_move_base/local_planner/ackermann_params.yaml
+++ b/config/adc_car_move_base/local_planner/ackermann_params.yaml
@@ -23,7 +23,7 @@ AckermannPlannerROS:
   steer_angle_samples: 21
 
   prune_plan: true
-  xy_goal_tolerance: 0.25
+  xy_goal_tolerance: 0.1
   yaw_goal_tolerance: 0.5
   trans_stopped_vel: 0.1
   rot_stopped_vel: 0.1
@@ -31,7 +31,7 @@ AckermannPlannerROS:
   restore_defaults: false
 
   max_trans_vel: 1.0
-  min_trans_vel: 0.0
+  min_trans_vel: -1.0
   max_trans_acc: 0.2
   max_steer_angle: 0.4
   min_steer_angle: -0.4
@@ -42,7 +42,7 @@ AckermannPlannerROS:
   wheel_distance: 0.216
   wheel_radius: 0.05
 
-  split_ignore_lenght: 0.1
+  split_ignore_length: 0.1
 
   cmd_vel_avg: 1
   odom_avg: 1