diff --git a/params/global_planner/sbpl_params.yaml b/params/global_planner/sbpl_params.yaml
index 4eb28a34d5964249572bb794f98a3a4fb7e94ca6..7a04ffd3971b44a593c7b577687c4cd078b50a10 100644
--- a/params/global_planner/sbpl_params.yaml
+++ b/params/global_planner/sbpl_params.yaml
@@ -1 +1,2 @@
 base_global_planner: "SBPLLatticePlanner"
+SBPLLatticePlanner:
diff --git a/params/local_planner/ackermann_params.yaml b/params/local_planner/ackermann_params.yaml
index c200188958d6df21e37062b6dc33ed68d7090262..5481d7b2fd3b4fd20e05d1bd880daa3663a7d1c5 100644
--- a/params/local_planner/ackermann_params.yaml
+++ b/params/local_planner/ackermann_params.yaml
@@ -38,8 +38,8 @@ AckermannPlannerROS:
   max_steer_vel: 0.3
   min_steer_vel: -0.3
   max_steer_acc: 1.0
-  axis_distance: 0.3662
-  wheel_distance: 0.216
+  axis_distance: 0.36
+  wheel_distance: 0.265
   wheel_radius: 0.05
 
   split_ignore_length: 0.1