44 lines
1.7 KiB
XML
44 lines
1.7 KiB
XML
<?xml version="1.0"?>
|
|
|
|
<!-- b1z1_description: B1 quadruped mounted with Z1 robotic arm -->
|
|
<robot name="b1z1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
|
|
<!-- define arguments -->
|
|
<xacro:arg name="DEBUG" default="false"/> <!-- debug mode switch -->
|
|
<xacro:arg name="UnitreeGripper" default="true"/> <!-- include Z1 end-effector -->
|
|
|
|
<!-- include xacro files -->
|
|
<xacro:include filename="$(find b1_description)/xacro/b1.xacro"/>
|
|
<xacro:include filename="$(find z1_description)/xacro/z1.xacro"/>
|
|
<xacro:include filename="$(find b1z1_description)/xacro/const.xacro"/>
|
|
<xacro:include filename="$(find b1z1_description)/xacro/gazebo.xacro"/>
|
|
|
|
<!-- B1 macro: expands to describe B1 quadruped robot -->
|
|
<xacro:b1/>
|
|
|
|
<!-- Z1 macro: expands to describe Z1 robotic arm -->
|
|
<xacro:z1 UnitreeGripper="$(arg UnitreeGripper)"/>
|
|
|
|
<!-- define joint affixing Z1 to B1 -->
|
|
<joint name="trunk_arm_joint" type="fixed">
|
|
<!-- Z1 mounting point wrt B1 trunk; configurable in const.xacro -->
|
|
<origin rpy="${arm_offset_r} ${arm_offset_p} ${arm_offset_yaw}"
|
|
xyz="${arm_offset_x} ${arm_offset_y} ${arm_offset_z}"/>
|
|
<!-- define parent and child links -->
|
|
<parent link="trunk"/>
|
|
<child link="link00"/>
|
|
</joint>
|
|
|
|
<!-- debug mode configuration -->
|
|
<xacro:if value="$(arg DEBUG)">
|
|
<!-- statically affix B1 base to world; i.e. "hang up" the robot -->
|
|
<link name="world"/>
|
|
<joint name="base_static_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="world"/>
|
|
<child link="base"/>
|
|
</joint>
|
|
</xacro:if>
|
|
|
|
</robot>
|