You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
 
 

408 lines
33 KiB

<?xml version="1.0" encoding="UTF-8"?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="stretch_description">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="stretch_arm">
<joint name="joint_lift"/>
<joint name="joint_arm_l4"/>
<joint name="joint_arm_l3"/>
<joint name="joint_arm_l2"/>
<joint name="joint_arm_l1"/>
<joint name="joint_arm_l0"/>
<joint name="joint_wrist_yaw"/>
</group>
<group name="stretch_gripper">
<link name="link_gripper"/>
<link name="link_grasp_center"/>
<link name="link_gripper_finger_left"/>
<link name="link_gripper_finger_right"/>
<link name="link_gripper_fingertip_left"/>
<link name="link_gripper_fingertip_right"/>
</group>
<group name="stretch_head">
<joint name="joint_head_pan" />
<joint name="joint_head_tilt" />
<link name="camera_link"/>
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="home" group="stretch_arm">
<joint name="joint_arm_l0" value="0"/>
<joint name="joint_arm_l1" value="0"/>
<joint name="joint_arm_l2" value="0"/>
<joint name="joint_arm_l3" value="0"/>
<joint name="joint_lift" value="0"/>
<joint name="joint_wrist_yaw" value="0"/>
</group_state>
<group_state name="extended" group="stretch_arm">
<joint name="joint_arm_l0" value="0.13"/>
<joint name="joint_arm_l1" value="0.13"/>
<joint name="joint_arm_l2" value="0.13"/>
<joint name="joint_arm_l3" value="0.13"/>
<joint name="joint_lift" value="0.9967"/>
<joint name="joint_wrist_yaw" value="4"/>
</group_state>
<group_state name="home" group="stretch_head">
<joint name="joint_head_pan" value="0.0"/>
<joint name="joint_head_tilt" value="0.0"/>
</group_state>
<group_state name="low_head" group="stretch_head">
<joint name="joint_head_pan" value="-3.5"/>
<joint name="joint_head_tilt" value="-1.2"/>
</group_state>
<group_state name="high_head" group="stretch_head">
<joint name="joint_head_pan" value="1.0"/>
<joint name="joint_head_tilt" value="0.5"/>
</group_state>
<group_state name="open" group="stretch_gripper">
<joint name="joint_gripper_finger_left" value="0.3"/>
<joint name="joint_gripper_finger_right" value="0.3"/>
</group_state>
<group_state name="closed" group="stretch_gripper">
<joint name="joint_gripper_finger_left" value="0.0"/>
<joint name="joint_gripper_finger_right" value="0.0"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="gripper" parent_link="link_grasp_center" group="stretch_arm"/>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<!--virtual_joint name="position" type="floating" parent_frame="map" child_link="base_link"/-->
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="base_link" link2="camera_link" reason="Never"/>
<disable_collisions link1="base_link" link2="laser" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_arm_l0" reason="Never"/>
<disable_collisions link1="base_link" link2="link_arm_l1" reason="Never"/>
<disable_collisions link1="base_link" link2="link_arm_l2" reason="Never"/>
<disable_collisions link1="base_link" link2="link_arm_l3" reason="Never"/>
<disable_collisions link1="base_link" link2="link_arm_l4" reason="Never"/>
<disable_collisions link1="base_link" link2="link_aruco_inner_wrist" reason="Never"/>
<disable_collisions link1="base_link" link2="link_aruco_left_base" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_aruco_right_base" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="base_link" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="base_link" link2="link_head" reason="Never"/>
<disable_collisions link1="base_link" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="base_link" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="base_link" link2="link_left_wheel" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_lift" reason="Never"/>
<disable_collisions link1="base_link" link2="link_mast" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_right_wheel" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="base_link" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="camera_link" link2="laser" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_arm_l0" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_arm_l1" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_arm_l2" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_arm_l3" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_arm_l4" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_aruco_inner_wrist" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_aruco_left_base" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_aruco_right_base" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_gripper" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_head_tilt" reason="Adjacent"/>
<disable_collisions link1="camera_link" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_lift" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_mast" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="camera_link" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="camera_link" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="laser" link2="link_arm_l0" reason="Never"/>
<disable_collisions link1="laser" link2="link_arm_l1" reason="Never"/>
<disable_collisions link1="laser" link2="link_arm_l2" reason="Never"/>
<disable_collisions link1="laser" link2="link_arm_l3" reason="Never"/>
<disable_collisions link1="laser" link2="link_arm_l4" reason="Never"/>
<disable_collisions link1="laser" link2="link_aruco_inner_wrist" reason="Never"/>
<disable_collisions link1="laser" link2="link_aruco_left_base" reason="Never"/>
<disable_collisions link1="laser" link2="link_aruco_right_base" reason="Never"/>
<disable_collisions link1="laser" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="laser" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="laser" link2="link_gripper" reason="Never"/>
<disable_collisions link1="laser" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="laser" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="laser" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="laser" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="laser" link2="link_head" reason="Never"/>
<disable_collisions link1="laser" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="laser" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="laser" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="laser" link2="link_lift" reason="Never"/>
<disable_collisions link1="laser" link2="link_mast" reason="Never"/>
<disable_collisions link1="laser" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="laser" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="laser" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_arm_l1" reason="Adjacent"/>
<disable_collisions link1="link_arm_l0" link2="link_arm_l2" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_arm_l3" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_arm_l4" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_aruco_inner_wrist" reason="Adjacent"/>
<disable_collisions link1="link_arm_l0" link2="link_aruco_left_base" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_aruco_right_base" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_aruco_top_wrist" reason="Adjacent"/>
<disable_collisions link1="link_arm_l0" link2="link_gripper" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_head" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l0" link2="link_wrist_yaw" reason="Adjacent"/>
<disable_collisions link1="link_arm_l0" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_arm_l2" reason="Adjacent"/>
<disable_collisions link1="link_arm_l1" link2="link_arm_l3" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_arm_l4" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_aruco_inner_wrist" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_aruco_left_base" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_aruco_right_base" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_gripper" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_head" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_arm_l1" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_arm_l3" reason="Adjacent"/>
<disable_collisions link1="link_arm_l2" link2="link_arm_l4" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_aruco_inner_wrist" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_aruco_left_base" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_aruco_right_base" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_gripper" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_head" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_arm_l2" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_arm_l4" reason="Adjacent"/>
<disable_collisions link1="link_arm_l3" link2="link_aruco_inner_wrist" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_aruco_left_base" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_aruco_right_base" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_gripper" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_head" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_arm_l3" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_aruco_inner_wrist" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_aruco_left_base" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_aruco_right_base" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_gripper" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_head" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_lift" reason="Adjacent"/>
<disable_collisions link1="link_arm_l4" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_arm_l4" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_aruco_left_base" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_aruco_right_base" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_gripper" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_head" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_aruco_inner_wrist" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_aruco_right_base" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_gripper" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_head" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_aruco_left_base" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_aruco_shoulder" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_gripper" reason="Default"/>
<disable_collisions link1="link_aruco_right_base" link2="link_head" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_aruco_right_base" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_aruco_top_wrist" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_gripper" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_head" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_lift" reason="Adjacent"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_aruco_shoulder" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_gripper" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_gripper_finger_left" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_gripper_finger_right" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_head" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_aruco_top_wrist" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_gripper" link2="link_gripper_finger_left" reason="Adjacent"/>
<disable_collisions link1="link_gripper" link2="link_gripper_finger_right" reason="Adjacent"/>
<disable_collisions link1="link_gripper" link2="link_gripper_fingertip_left" reason="Never"/>
<disable_collisions link1="link_gripper" link2="link_gripper_fingertip_right" reason="Never"/>
<disable_collisions link1="link_gripper" link2="link_head" reason="Never"/>
<disable_collisions link1="link_gripper" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_gripper" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_gripper" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_gripper" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_gripper" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_gripper" link2="link_wrist_yaw" reason="Adjacent"/>
<disable_collisions link1="link_gripper" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_gripper_finger_left" link2="link_gripper_fingertip_left" reason="Adjacent"/>
<disable_collisions link1="link_gripper_finger_left" link2="link_head" reason="Never"/>
<disable_collisions link1="link_gripper_finger_left" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_gripper_finger_left" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_gripper_finger_left" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_gripper_finger_left" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_gripper_finger_left" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_gripper_finger_left" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_gripper_finger_left" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_gripper_finger_right" link2="link_gripper_fingertip_right" reason="Adjacent"/>
<disable_collisions link1="link_gripper_finger_right" link2="link_head" reason="Never"/>
<disable_collisions link1="link_gripper_finger_right" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_gripper_finger_right" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_gripper_finger_right" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_gripper_finger_right" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_gripper_finger_right" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_gripper_finger_right" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_gripper_finger_right" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_left" link2="link_head" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_left" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_left" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_left" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_left" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_left" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_left" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_left" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_right" link2="link_head" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_right" link2="link_head_pan" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_right" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_right" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_right" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_right" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_right" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_gripper_fingertip_right" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_head" link2="link_head_pan" reason="Adjacent"/>
<disable_collisions link1="link_head" link2="link_head_tilt" reason="Never"/>
<disable_collisions link1="link_head" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_head" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_head" link2="link_mast" reason="Adjacent"/>
<disable_collisions link1="link_head" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_head" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_head" link2="respeaker_base" reason="Default"/>
<disable_collisions link1="link_head_pan" link2="link_head_tilt" reason="Adjacent"/>
<disable_collisions link1="link_head_pan" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_head_pan" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_head_pan" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_head_pan" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_head_pan" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_head_pan" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_head_tilt" link2="link_left_wheel" reason="Never"/>
<disable_collisions link1="link_head_tilt" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_head_tilt" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_head_tilt" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_head_tilt" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_head_tilt" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_left_wheel" link2="link_lift" reason="Never"/>
<disable_collisions link1="link_left_wheel" link2="link_mast" reason="Never"/>
<disable_collisions link1="link_left_wheel" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_left_wheel" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_left_wheel" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_lift" link2="link_mast" reason="Adjacent"/>
<disable_collisions link1="link_lift" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_lift" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_lift" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_mast" link2="link_right_wheel" reason="Never"/>
<disable_collisions link1="link_mast" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_mast" link2="respeaker_base" reason="Adjacent"/>
<disable_collisions link1="link_right_wheel" link2="link_wrist_yaw" reason="Never"/>
<disable_collisions link1="link_right_wheel" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="link_wrist_yaw" link2="respeaker_base" reason="Never"/>
<disable_collisions link1="caster_link" link2="base_link" reason="Adjacent"/>
</robot>