27 lines
1.2 KiB
XML
27 lines
1.2 KiB
XML
<?xml version="1.0" encoding="UTF-8"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
|
|
<xacro:macro name="group_definition" params="group_name arm_id tip_link">
|
|
<group name="${group_name}">
|
|
<chain base_link="${arm_id}_link0" tip_link="${tip_link}"/>
|
|
</group>
|
|
|
|
<group_state name="ready" group="${group_name}">
|
|
<joint name="${arm_id}_joint1" value="0"/>
|
|
<joint name="${arm_id}_joint2" value="${-pi/4}"/>
|
|
<joint name="${arm_id}_joint3" value="0"/>
|
|
<joint name="${arm_id}_joint4" value="${-3*pi/4}"/>
|
|
<joint name="${arm_id}_joint5" value="0"/>
|
|
<joint name="${arm_id}_joint6" value="${pi/2}"/>
|
|
<joint name="${arm_id}_joint7" value="${pi/4}"/>
|
|
</group_state>
|
|
<group_state name="extended" group="${group_name}">
|
|
<joint name="${arm_id}_joint1" value="0"/>
|
|
<joint name="${arm_id}_joint2" value="0"/>
|
|
<joint name="${arm_id}_joint3" value="0"/>
|
|
<joint name="${arm_id}_joint4" value="-0.1"/>
|
|
<joint name="${arm_id}_joint5" value="0"/>
|
|
<joint name="${arm_id}_joint6" value="${pi/2}"/>
|
|
<joint name="${arm_id}_joint7" value="${pi/4}"/>
|
|
</group_state>
|
|
</xacro:macro>
|
|
</robot> |