Skip to content
Snippets Groups Projects
Commit 1d5e8ae7 authored by Dave Hershberger's avatar Dave Hershberger Committed by ipa-fxm
Browse files

Added collision object for ur5's ee_link to workaround moveit bug.

https://github.com/ros-planning/moveit_core/issues/158
parent 6e9e5949
Branches
Tags
No related merge requests found
...@@ -50,4 +50,5 @@ ...@@ -50,4 +50,5 @@
<disable_collisions link1="wrist_1_link" link2="wrist_2_link" reason="Adjacent" /> <disable_collisions link1="wrist_1_link" link2="wrist_2_link" reason="Adjacent" />
<disable_collisions link1="wrist_1_link" link2="wrist_3_link" reason="Never" /> <disable_collisions link1="wrist_1_link" link2="wrist_3_link" reason="Never" />
<disable_collisions link1="wrist_2_link" link2="wrist_3_link" reason="Adjacent" /> <disable_collisions link1="wrist_2_link" link2="wrist_3_link" reason="Adjacent" />
<disable_collisions link1="ee_link" link2="wrist_3_link" reason="Adjacent" />
</robot> </robot>
...@@ -282,7 +282,14 @@ ...@@ -282,7 +282,14 @@
<origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" /> <origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" />
</joint> </joint>
<link name="${prefix}ee_link" /> <link name="${prefix}ee_link">
<collision>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.01 0 0"/>
</collision>
</link>
<xacro:ur5_arm_transmission prefix="${prefix}" /> <xacro:ur5_arm_transmission prefix="${prefix}" />
<xacro:ur5_arm_gazebo prefix="${prefix}" /> <xacro:ur5_arm_gazebo prefix="${prefix}" />
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment