Skip to content
Snippets Groups Projects
hand.xacro 3.52 KiB
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
    <xacro:macro name="hand">
        <!--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="$(arg arm_id)_hand">
            <link name="$(arg arm_id)_hand"/>
            <link name="$(arg arm_id)_leftfinger"/>
            <link name="$(arg arm_id)_rightfinger"/>
        </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="open" group="$(arg arm_id)_hand">
            <joint name="$(arg arm_id)_finger_joint1" value="0.035"/>
            <joint name="$(arg arm_id)_finger_joint2" value="0.035"/>
        </group_state>
        <group_state name="close" group="$(arg arm_id)_hand">
            <joint name="$(arg arm_id)_finger_joint1" value="0"/>
            <joint name="$(arg arm_id)_finger_joint2" value="0"/>
        </group_state>
        <!--END EFFECTOR: Purpose: Represent information about an end effector.-->
        <!--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)-->
        <!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
        <!--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 for hand_sc by default (with environment) -->
        <disable_default_collisions link="$(arg arm_id)_hand_sc" />
        <!-- Reenable collision of hand_sc for selected arm sc links -->
        <xacro:property name="link_fmt" value="$(arg arm_id)_link{}_sc" />
        <xacro:enable_collisions_for link="$(arg arm_id)_hand_sc" others="${[link_fmt.format(i) for i in [0,1,2,3]]}" />
        <!-- Disable collision of hand link with all arm links. These are handled by the *_sc links -->
        <xacro:property name="link_fmt" value="$(arg arm_id)_link{}" />
        <xacro:disable_collisions_for link="$(arg arm_id)_hand" others="${[link_fmt.format(i) for i in python.range(9)]}" />
        <!-- Disable collision of fingers with all arm links -->
        <xacro:property name="others" value="${[link_fmt.format(i) for i in python.range(9)] + [xacro.arg('arm_id') + '_hand']}" />
        <xacro:disable_collisions_for link="$(arg arm_id)_leftfinger" others="${list(others)}" />
        <xacro:disable_collisions_for link="$(arg arm_id)_rightfinger" others="${list(others)}" />
        <disable_collisions link1="$(arg arm_id)_leftfinger" link2="$(arg arm_id)_rightfinger" reason="Never" />
    </xacro:macro>
</robot>