diff --git a/urdf/include/wheel.xacro b/urdf/include/wheel.xacro
index 9bc453925e3672e5cd6a76a36084ac66f0d95e8b..4e124dce99fc9c54ede696d87fc6a8f83076dec7 100644
--- a/urdf/include/wheel.xacro
+++ b/urdf/include/wheel.xacro
@@ -35,7 +35,7 @@
       <parent link="${parent}"/>
       <child link="${name}_wheel"/>
       <axis xyz="0 0 ${direction}"/>
-      <limit effort="0.1" velocity="20.0" upper="1e16" lower="-1e16"/>
+      <limit effort="1.0" velocity="20.0" upper="1e16" lower="-1e16"/>
       <!-- the limits only apply to revolute and prismatic joints -->
       <dynamics damping="0.001"/>
     </joint>