<?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="bluevolta_bravo7_gripper"> <group name="whole_body"> <joint name="joint1"/> <joint name="joint2"/> <joint name="joint3"/> <joint name="joint4"/> <joint name="joint5"/> <joint name="joint6"/> <joint name="bravo_finger1_joint"/> <joint name="bravo_finger2_joint"/> </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="standing" group="whole_body"> <joint name="joint1" value="1.851"/> <joint name="joint2" value="2.308"/> <joint name="joint3" value="1.211"/> <joint name="joint4" value="1.851"/> <joint name="joint5" value="1.646"/> <joint name="joint6" value="-0.357"/> <joint name="bravo_finger1_joint" value="0.2"/> <joint name="bravo_finger2_joint" value="0.2"/> </group_state> <!--END EFFECTOR: Purpose: Represent information about an end effector.--> <end_effector name="contact_point" parent_link="force_torque_sensor" group="whole_body"/> <!--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="root_joint" type="floating" parent_frame="world_frame" child_link="bluevolta_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="bluevolta_rov" link2="link1" reason="Adjacent"/> <disable_collisions link1="bravo_finger1_link" link2="bravo_finger_jaws_base_link" reason="Adjacent"/> <disable_collisions link1="bravo_finger1_link" link2="force_torque_sensor" reason="Never"/> <disable_collisions link1="bravo_finger1_link" link2="link4" reason="Never"/> <disable_collisions link1="bravo_finger1_link" link2="link5" reason="Never"/> <disable_collisions link1="bravo_finger1_link" link2="link6" reason="Never"/> <disable_collisions link1="bravo_finger1_link" link2="link7" reason="Never"/> <disable_collisions link1="bravo_finger2_link" link2="bravo_finger_jaws_base_link" reason="Adjacent"/> <disable_collisions link1="bravo_finger2_link" link2="force_torque_sensor" reason="Never"/> <disable_collisions link1="bravo_finger2_link" link2="link4" reason="Never"/> <disable_collisions link1="bravo_finger2_link" link2="link5" reason="Never"/> <disable_collisions link1="bravo_finger2_link" link2="link6" reason="Never"/> <disable_collisions link1="bravo_finger2_link" link2="link7" reason="Never"/> <disable_collisions link1="bravo_finger_jaws_base_link" link2="force_torque_sensor" reason="Never"/> <disable_collisions link1="bravo_finger_jaws_base_link" link2="link4" reason="Never"/> <disable_collisions link1="bravo_finger_jaws_base_link" link2="link5" reason="Never"/> <disable_collisions link1="bravo_finger_jaws_base_link" link2="link6" reason="Never"/> <disable_collisions link1="bravo_finger_jaws_base_link" link2="link7" reason="Adjacent"/> <disable_collisions link1="force_torque_sensor" link2="link5" reason="Never"/> <disable_collisions link1="force_torque_sensor" link2="link6" reason="Never"/> <disable_collisions link1="force_torque_sensor" link2="link7" reason="Adjacent"/> <disable_collisions link1="link1" link2="link2" reason="Adjacent"/> <disable_collisions link1="link1" link2="link4" reason="Never"/> <disable_collisions link1="link2" link2="link3" reason="Adjacent"/> <disable_collisions link1="link2" link2="link4" reason="Never"/> <disable_collisions link1="link2" link2="link5" reason="Never"/> <disable_collisions link1="link3" link2="link4" reason="Adjacent"/> <disable_collisions link1="link4" link2="link5" reason="Adjacent"/> <disable_collisions link1="link5" link2="link6" reason="Adjacent"/> <disable_collisions link1="link5" link2="link7" reason="Never"/> <disable_collisions link1="link6" link2="link7" reason="Adjacent"/> </robot>