diff --git a/src/rove_description/config/tracks_controllers.yaml b/src/rove_description/config/tracks_controllers.yaml
index 4831d55..f0dcfa8 100644
--- a/src/rove_description/config/tracks_controllers.yaml
+++ b/src/rove_description/config/tracks_controllers.yaml
@@ -66,8 +66,8 @@ diff_drive_controller:
angular.z.has_velocity_limits: true
angular.z.has_acceleration_limits: true
angular.z.has_jerk_limits: false
- angular.z.max_velocity: 2.0
- angular.z.min_velocity: -2.0
+ angular.z.max_velocity: 5.0
+ angular.z.min_velocity: -5.0
angular.z.max_acceleration: 3.0
angular.z.min_acceleration: -3.0
angular.z.max_jerk: 0.0
diff --git a/src/rove_description/urdf/rove.urdf.xacro b/src/rove_description/urdf/rove.urdf.xacro
index b5a3744..dec91b8 100644
--- a/src/rove_description/urdf/rove.urdf.xacro
+++ b/src/rove_description/urdf/rove.urdf.xacro
@@ -51,7 +51,7 @@
-
+