XACRO案例:SCARA
需求介绍¶
采用xacro
方式模拟建造一个类似于ABB的SCARA类似的产品。
实现需求¶
模型分析¶
两个可以旋转的轴,一个可以上下滑动的轴。
总共是3个joint,4个link.
建立模型¶
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="scara">
<xacro:property name="base_width" value="0.3"/>
<xacro:property name="base_height" value="0.4"/>
<xacro:property name="base_len" value="0.6"/>
<xacro:property name="link1_width" value="0.2"/>
<xacro:property name="link1_height" value="0.8"/>
<xacro:property name="link1_len" value="0.1"/>
<xacro:property name="link2_width" value="0.2"/>
<xacro:property name="link2_height" value="0.6"/>
<xacro:property name="link2_len" value="0.3"/>
<xacro:property name="link3_len" value="1"/>
<xacro:property name="link3_radius" value="0.01"/>
<xacro:macro name="HMColor" params="name">
<material name="${name}">
<xacro:if value="${name=='red'}">
<color rgba="1.0 0 0 1.0"/>
</xacro:if>
<xacro:if value="${name=='green'}">
<color rgba="0 1.0 0 1.0"/>
</xacro:if>
<xacro:if value="${name=='blue'}">
<color rgba="0 0 1.0 1.0"/>
</xacro:if>
<xacro:if value="${name=='white'}">
<color rgba="1.0 1.0 1.0 1.0"/>
</xacro:if>
</material>
</xacro:macro>
<!-- base link -->
<link name="base_link">
<visual>
<origin xyz="0 0 ${base_len / 2}" rpy="0 0 0"/>
<geometry>
<box size="${base_width} ${base_height} ${base_len}"/>
</geometry>
<xacro:HMColor name="white"/>
</visual>
</link>
<!-- link1 -->
<link name="link1">
<visual>
<origin xyz="0 -${link1_height/2 + base_width/2 - base_height/2} ${link1_len/2}" rpy="0 0 0"/>
<geometry>
<box size="${link1_width} ${link1_height} ${link1_len}"/>
</geometry>
<xacro:HMColor name="blue"/>
</visual>
</link>
<!-- joint: toggle link -->
<joint name="joint0" type="revolute">
<origin xyz="0 -${base_height/2 - base_width/2} ${base_len}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="link1"/>
<limit effort="30" velocity="1.0" lower="-2.5" upper="2.5"/>
</joint>
<!-- link2 -->
<link name="link2">
<visual>
<origin xyz="0 -0.2 ${link2_len/2}" rpy="0 0 0"/>
<geometry>
<box size="${link2_width} ${link2_height} ${link2_len}"/>
</geometry>
<xacro:HMColor name="green"/>
</visual>
</link>
<!-- joint: toggle link -->
<joint name="joint1" type="revolute">
<origin xyz="0 -${link1_height - link1_width} ${link1_len}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="link1"/>
<child link="link2"/>
<limit effort="30" velocity="1.0" lower="-2.5" upper="2.5"/>
</joint>
<!-- link3 -->
<link name="link3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="${link3_len}" radius="${link3_radius}"/>
</geometry>
<xacro:HMColor name="red"/>
</visual>
</link>
<!-- joint: toggle link -->
<joint name="joint2" type="prismatic">
<origin xyz="0 -${link2_height - link2_width} ${link2_len/2}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="link2"/>
<child link="link3"/>
<limit effort="30" velocity="1.0" lower="-0.35" upper="0.35"/>
</joint>
</robot>