108 lines
3.5 KiB
XML
108 lines
3.5 KiB
XML
<?xml version="1.0" ?>
|
|
<robot name="dual_arm_leg_robot">
|
|
<!-- 左右手臂和腿部的规划组定义 -->
|
|
<group name="left_arm_group">
|
|
<joint name="left_arm_joint1"/>
|
|
<joint name="left_arm_joint2"/>
|
|
<joint name="left_arm_joint3"/>
|
|
<joint name="left_arm_joint4"/>
|
|
<joint name="left_arm_joint5"/>
|
|
<joint name="left_arm_joint6"/>
|
|
<link name="left_arm_link1"/>
|
|
<link name="left_arm_link2"/>
|
|
<link name="left_arm_link3"/>
|
|
<link name="left_arm_link4"/>
|
|
<link name="left_arm_link5"/>
|
|
<link name="left_arm_end_effector"/>
|
|
</group>
|
|
|
|
<group name="right_arm_group">
|
|
<joint name="right_arm_joint1"/>
|
|
<joint name="right_arm_joint2"/>
|
|
<joint name="right_arm_joint3"/>
|
|
<joint name="right_arm_joint4"/>
|
|
<joint name="right_arm_joint5"/>
|
|
<joint name="right_arm_joint6"/>
|
|
<link name="right_arm_link1"/>
|
|
<link name="right_arm_link2"/>
|
|
<link name="right_arm_link3"/>
|
|
<link name="right_arm_link4"/>
|
|
<link name="right_arm_link5"/>
|
|
<link name="right_arm_end_effector"/>
|
|
</group>
|
|
|
|
<group name="left_front_leg_group">
|
|
<joint name="left_leg_joint1"/>
|
|
<joint name="left_leg_joint2"/>
|
|
<joint name="left_leg_joint3"/>
|
|
<link name="left_leg_link1"/>
|
|
<link name="left_leg_link2"/>
|
|
<link name="left_foot"/>
|
|
</group>
|
|
|
|
<group name="left_behind_leg_group">
|
|
<joint name="left_behind_leg_joint1"/>
|
|
<joint name="left_behind_leg_joint2"/>
|
|
<joint name="left_behind_leg_joint3"/>
|
|
<link name="left_behind_leg_link1"/>
|
|
<link name="left_behind_leg_link2"/>
|
|
<link name="left_behind_foot"/>
|
|
</group>
|
|
|
|
<group name="right_frount_leg_group">
|
|
<joint name="right_leg_joint1"/>
|
|
<joint name="right_leg_joint2"/>
|
|
<joint name="right_leg_joint3"/>
|
|
<link name="right_leg_link1"/>
|
|
<link name="right_leg_link2"/>
|
|
<link name="right_foot"/>
|
|
</group>
|
|
|
|
<!-- 末端执行器定义 -->
|
|
<end_effector name="left_end_effector" parent_link="left_arm_end_effector" group="left_arm_group">
|
|
<touch_links>
|
|
<link name="left_arm_end_effector"/>
|
|
</touch_links>
|
|
</end_effector>
|
|
|
|
<end_effector name="right_end_effector" parent_link="right_arm_end_effector" group="right_arm_group">
|
|
<touch_links>
|
|
<link name="right_arm_end_effector"/>
|
|
</touch_links>
|
|
</end_effector>
|
|
|
|
<!-- 默认姿态 -->
|
|
<group_state name="home" group="left_arm_group">
|
|
<joint name="left_arm_joint1" value="0"/>
|
|
<joint name="left_arm_joint2" value="0"/>
|
|
<joint name="left_arm_joint3" value="0"/>
|
|
<joint name="left_arm_joint4" value="0"/>
|
|
<joint name="left_arm_joint5" value="0"/>
|
|
<joint name="left_arm_joint6" value="0"/>
|
|
</group_state>
|
|
|
|
<group_state name="home" group="right_arm_group">
|
|
<joint name="right_arm_joint1" value="0"/>
|
|
<joint name="right_arm_joint2" value="0"/>
|
|
<joint name="right_arm_joint3" value="0"/>
|
|
<joint name="right_arm_joint4" value="0"/>
|
|
<joint name="right_arm_joint5" value="0"/>
|
|
<joint name="right_arm_joint6" value="0"/>
|
|
</group_state>
|
|
|
|
<group_state name="home" group="left_leg_group">
|
|
<joint name="left_leg_joint1" value="0"/>
|
|
<joint name="left_leg_joint2" value="0.5"/>
|
|
<joint name="left_leg_joint3" value="0"/>
|
|
</group_state>
|
|
|
|
<group_state name="home" group="right_leg_group">
|
|
<joint name="right_leg_joint1" value="0"/>
|
|
<joint name="right_leg_joint2" value="0.5"/>
|
|
<joint name="right_leg_joint3" value="0"/>
|
|
</group_state>
|
|
|
|
<!-- 虚拟关节(可选) -->
|
|
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="base_link"/>
|
|
</robot>
|