Newer
Older
--- 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>