diff --git a/tiago-data/Makefile b/tiago-data/Makefile
index 586777f18a50010291fd0e0ee5401b74f09b9b46..c017bf376e65d15cfb683c53373977997ed72f81 100644
--- a/tiago-data/Makefile
+++ b/tiago-data/Makefile
@@ -10,6 +10,7 @@ PKGNAME=		${PKGBASE}-${VERSION}
 ROSNAME=		$(subst -,_,${PKGBASE})
 WRKSRC=			${WRKDIR}/${ROSNAME}-${VERSION}
 DIST_SUBDIR=		${PKGBASE}
+PKGREVISION=		1
 
 CATEGORIES=		wip
 
diff --git a/tiago-data/distinfo b/tiago-data/distinfo
index 45f8f74117abde58bf38b746a18c45de378b8114..02bf57085f19cac694171db9e82d2956f729e0e2 100644
--- a/tiago-data/distinfo
+++ b/tiago-data/distinfo
@@ -1,3 +1,4 @@
 SHA1 (tiago-data/1.0.0.tar.gz) = b1a528c212de6d972607138869c8e4d1977855e5
 RMD160 (tiago-data/1.0.0.tar.gz) = 1141f351b4d9b7bbe6f526aa87dfac994c151fe8
 Size (tiago-data/1.0.0.tar.gz) = 5309877 bytes
+SHA1 (patch-aa) = e71d2c9b4c579440fdb702f3b457a1146dbf2726
diff --git a/tiago-data/patches/patch-aa b/tiago-data/patches/patch-aa
new file mode 100644
index 0000000000000000000000000000000000000000..9959882a9fddf519a95b6bc765aaca055c8806e8
--- /dev/null
+++ b/tiago-data/patches/patch-aa
@@ -0,0 +1,33 @@
+--- robots/tiago_steel.urdf
++++ robots/tiago_steel.urdf
+@@ -562,12 +562,12 @@
+     <dynamics damping="100"/>
+     <safety_controller k_position="0" k_velocity="10" soft_lower_limit="-0.005" soft_upper_limit="0.005"/>
+   </joint>
+-  <joint name="wheel_right_joint" type="fixed">
++  <joint name="wheel_right_joint" type="revolute">
+     <parent link="suspension_right_link"/>
+     <child link="wheel_right_link"/>
+     <origin rpy="-1.57079632679 0 0" xyz="0 -0.2022 0"/>
+     <axis xyz="0 0 1"/>
+-    <limit effort="6.0" velocity="10.152284264"/>
++    <limit effort="6.0" velocity="10.152284264" lower="-inf" upper="inf"/>
+   </joint>
+   <transmission name="wheel_right_trans">
+     <type>transmission_interface/SimpleTransmission</type>
+@@ -630,12 +630,12 @@
+     <dynamics damping="100"/>
+     <safety_controller k_position="0" k_velocity="10" soft_lower_limit="-0.005" soft_upper_limit="0.005"/>
+   </joint>
+-  <joint name="wheel_left_joint" type="fixed">
++  <joint name="wheel_left_joint" type="revolute">
+     <parent link="suspension_left_link"/>
+     <child link="wheel_left_link"/>
+     <origin rpy="-1.57079632679 0 0" xyz="0 0.2022 0"/>
+     <axis xyz="0 0 1"/>
+-    <limit effort="6.0" velocity="10.152284264"/>
++    <limit effort="6.0" velocity="10.152284264" lower="-inf" upper="inf"/>
+   </joint>
+   <transmission name="wheel_left_trans">
+     <type>transmission_interface/SimpleTransmission</type>
+