Skip to content
Snippets Groups Projects
Commit d01b955e authored by Simon Gabl's avatar Simon Gabl
Browse files

Update soft limits of joint 4 in the URDF.

parent 39a67a48
No related branches found
No related tags found
No related merge requests found
...@@ -93,7 +93,7 @@ ...@@ -93,7 +93,7 @@
</collision> </collision>
</link> </link>
<joint name="${arm_id}_joint4" type="revolute"> <joint name="${arm_id}_joint4" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="0.0175"/> <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698"/>
<origin rpy="${pi/2} 0 0" xyz="0.0825 0 0"/> <origin rpy="${pi/2} 0 0" xyz="0.0825 0 0"/>
<parent link="${arm_id}_link3"/> <parent link="${arm_id}_link3"/>
<child link="${arm_id}_link4"/> <child link="${arm_id}_link4"/>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment