|
<?xml version="1.0" ?> |
|
|
|
|
|
|
|
|
|
<robot name="panda"> |
|
|
|
|
|
|
|
|
|
|
|
<group name="panda_arm"> |
|
<joint name="virtual_joint"/> |
|
<joint name="panda_joint1"/> |
|
<joint name="panda_joint2"/> |
|
<joint name="panda_joint3"/> |
|
<joint name="panda_joint4"/> |
|
<joint name="panda_joint5"/> |
|
<joint name="panda_joint6"/> |
|
<joint name="panda_joint7"/> |
|
<joint name="panda_joint8"/> |
|
<joint name="panda_hand_joint"/> |
|
</group> |
|
<group name="hand"> |
|
<link name="panda_hand"/> |
|
<link name="panda_leftfinger"/> |
|
<link name="panda_rightfinger"/> |
|
</group> |
|
|
|
<group_state name="home" group="panda_arm"> |
|
<joint name="panda_joint1" value="0"/> |
|
<joint name="panda_joint2" value="0"/> |
|
<joint name="panda_joint3" value="0"/> |
|
<joint name="panda_joint4" value="0"/> |
|
<joint name="panda_joint5" value="0"/> |
|
<joint name="panda_joint6" value="3.1416"/> |
|
<joint name="panda_joint7" value="1.5708"/> |
|
</group_state> |
|
|
|
<end_effector name="eef" parent_link="panda_link8" group="hand"/> |
|
|
|
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="panda_link0"/> |
|
|
|
<disable_collisions link1="panda_hand" link2="panda_leftfinger" reason="Adjacent"/> |
|
<disable_collisions link1="panda_hand" link2="panda_link3" reason="Never"/> |
|
<disable_collisions link1="panda_hand" link2="panda_link4" reason="Never"/> |
|
<disable_collisions link1="panda_hand" link2="panda_link5" reason="Default"/> |
|
<disable_collisions link1="panda_hand" link2="panda_link6" reason="Never"/> |
|
<disable_collisions link1="panda_hand" link2="panda_link7" reason="Default"/> |
|
<disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent"/> |
|
<disable_collisions link1="panda_leftfinger" link2="panda_link3" reason="Never"/> |
|
<disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never"/> |
|
<disable_collisions link1="panda_leftfinger" link2="panda_link6" reason="Never"/> |
|
<disable_collisions link1="panda_leftfinger" link2="panda_link7" reason="Never"/> |
|
<disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default"/> |
|
<disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent"/> |
|
<disable_collisions link1="panda_link0" link2="panda_link2" reason="Never"/> |
|
<disable_collisions link1="panda_link0" link2="panda_link3" reason="Never"/> |
|
<disable_collisions link1="panda_link0" link2="panda_link4" reason="Never"/> |
|
<disable_collisions link1="panda_link1" link2="panda_link2" reason="Adjacent"/> |
|
<disable_collisions link1="panda_link1" link2="panda_link3" reason="Never"/> |
|
<disable_collisions link1="panda_link1" link2="panda_link4" reason="Never"/> |
|
<disable_collisions link1="panda_link2" link2="panda_link3" reason="Adjacent"/> |
|
<disable_collisions link1="panda_link2" link2="panda_link4" reason="Never"/> |
|
<disable_collisions link1="panda_link2" link2="panda_link6" reason="Never"/> |
|
<disable_collisions link1="panda_link3" link2="panda_link4" reason="Adjacent"/> |
|
<disable_collisions link1="panda_link3" link2="panda_link5" reason="Never"/> |
|
<disable_collisions link1="panda_link3" link2="panda_link6" reason="Never"/> |
|
<disable_collisions link1="panda_link3" link2="panda_link7" reason="Never"/> |
|
<disable_collisions link1="panda_link3" link2="panda_rightfinger" reason="Never"/> |
|
<disable_collisions link1="panda_link4" link2="panda_link5" reason="Adjacent"/> |
|
<disable_collisions link1="panda_link4" link2="panda_link6" reason="Never"/> |
|
<disable_collisions link1="panda_link4" link2="panda_link7" reason="Never"/> |
|
<disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never"/> |
|
<disable_collisions link1="panda_link5" link2="panda_link6" reason="Adjacent"/> |
|
<disable_collisions link1="panda_link5" link2="panda_link7" reason="Default"/> |
|
<disable_collisions link1="panda_link6" link2="panda_link7" reason="Adjacent"/> |
|
<disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never"/> |
|
<disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never"/> |
|
</robot> |
|
|