diff --git a/cfg/ModelCarControl.cfg b/cfg/ModelCarControl.cfg
index 74abfafe3c4905c04f6bd65344a775cb6c4349bf..834c1905aac93fb59d43cd2eb28ed579d1ec971c 100755
--- a/cfg/ModelCarControl.cfg
+++ b/cfg/ModelCarControl.cfg
@@ -45,7 +45,7 @@ gen.add("speed_Kd",         double_t,  0,           "Differential constant of th
 gen.add("speed_i_max",      double_t,  0,           "Maximum integral value pf the speed PID",    10.0,   0.0, 1000.0)
 gen.add("speed_deadband",   double_t,  0,           "Minimum valid speed command",                0.1,    0.1, 1.0)
 gen.add("watchdog_time",    double_t,  0,           "Maximum time between two control commands",  0.5,    0.0, 1000.0)
-gen.add("axel_distance",    double_t,  0,           "Distance between the two axels in meters",   0.3662, 0.0, 10.0)
+gen.add("axel_distance",    double_t,  0,           "Distance between the two axels in meters",   0.36,   0.0, 10.0)
 gen.add("max_steer_angle",  double_t,  0,           "Maximum steering angle",                     0.4,    -1.0,1.0)
 gen.add("min_steer_angle",  double_t,  0,           "Minimum steering angle",                     -0.4,   -1.0,1.0)
 gen.add("max_speed_control",double_t,  0,           "Maximum output speed command value",         10.0,   -100.0,  100.0)
diff --git a/config/car1_params.yaml b/config/car1_params.yaml
index 8e606f68e34dfab38013828d96c8a7572d595f63..dfab18d5dd2b4275d13323590b803e2b50ae4ca6 100644
--- a/config/car1_params.yaml
+++ b/config/car1_params.yaml
@@ -5,7 +5,7 @@ speed_Kd: 0.00
 speed_i_max: 20.0
 speed_deadband: 0.1
 watchdog_time: 0.5
-axel_distance: 0.3662
+axel_distance: 0.36
 max_steer_angle: 0.5
 min_steer_angle: -0.5
 max_speed_control: 20.0
diff --git a/config/car2_params.yaml b/config/car2_params.yaml
index 8e606f68e34dfab38013828d96c8a7572d595f63..dfab18d5dd2b4275d13323590b803e2b50ae4ca6 100644
--- a/config/car2_params.yaml
+++ b/config/car2_params.yaml
@@ -5,7 +5,7 @@ speed_Kd: 0.00
 speed_i_max: 20.0
 speed_deadband: 0.1
 watchdog_time: 0.5
-axel_distance: 0.3662
+axel_distance: 0.36
 max_steer_angle: 0.5
 min_steer_angle: -0.5
 max_speed_control: 20.0
diff --git a/config/params.yaml b/config/params.yaml
index 41c07292099fca45336bc22e4e5cd2468466f796..cb2a7bdb92e204b66febbb3319f51f7a16ebb6ae 100644
--- a/config/params.yaml
+++ b/config/params.yaml
@@ -5,7 +5,7 @@ speed_Kd: 0.00
 speed_i_max: 20.0
 speed_deadband: 0.1
 watchdog_time: 0.5
-axel_distance: 0.3662
+axel_distance: 0.36
 max_steer_angle: 0.5
 min_steer_angle: -0.5
 max_speed_control: 20.0