比如下面这样的小车车身部分定义是下面这样的:
<!-- common link-->
<xacro:macro name="common_link" params="name material path *origin">
<!--
*origin是块参数,前面的都是字符串参数。使用*的话默认将调用这个comman_link的部件中第一个
模块(比如front_right_wheel中的inertial)
然后通过<xacro:insert_block name="origin"/>将该模块导入
-->
<link name="${ns}/${name}">
<visual>
<geometry>
<mesh filename="package://yahboomcar_description/meshes/${path}/${name}.STL"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="${material}"/>
</visual>
<collision>
<geometry>
<mesh filename="package://yahboomcar_description/meshes/${path}/${name}.STL"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
</collision>
<xacro:insert_block name="origin"/>
</link>
</xacro:macro>
<!-- fixed joint-->
<xacro:macro name="fixed_joint" params="name parent child xyz rpy">
<joint name="${ns}/${name}" type="fixed">
<parent link="${ns}/${parent}"/>
<child link="${ns}/${child}"/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>
</xacro:macro>
<common_link name="base_link" material="Green" path="mecanum">
<inertial>
<origin xyz="0.00498197982182523 5.70233829969297E-05 -0.0121008098068578" rpy="0 0 0"/>
<mass value="0.486218814966626"/>
<inertia
ixx="0.00196277727666921"
ixy="2.50447049446755E-07"
ixz="0.000140534767811098"
iyy="0.00457256033711368"
iyz="2.68618064993882E-07"
izz="0.00493927269870476"/>
</inertial>
</common_link>
<fixed_joint name="base_joint" parent="base_footprint" child="base_link" xyz="0.0 0.0 0.0815" rpy="0 0 0"/>
在Ubuntu20.04中,所有复用macro描述后,都要加上xacro前缀gazebo才能够识别,所以需要将上面改为:
<xacro:macro name="common_link" params="name material path rpy *origin">
<!--
*origin是块参数,前面的都是字符串参数。使用*的话默认将调用这个comman_link的部件中第一个模块(比如front_right_wheel中的inertial)
然后通过<xacro:insert_block name="origin"/>将该模块导入
-->
<link name="${name}">
<visual>
<geometry>
<mesh filename="package://yahboomcar_description/meshes/${path}/${name}.STL"/>
</geometry>
<origin xyz="0 0 0" rpy="${rpy}"/>
<material name="${material}"/>
</visual>
<collision>
<geometry>
<mesh filename="package://yahboomcar_description/meshes/${path}/${name}.STL"/>
</geometry>
<origin xyz="0 0 0" rpy="${rpy}"/>
</collision>
<xacro:insert_block name="origin"/>
</link>
</xacro:macro>
<!-- fixed joint-->
<xacro:macro name="fixed_joint" params="name parent child xyz rpy">
<joint name="${name}" type="fixed">
<parent link="${parent}"/>
<child link="${child}"/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>
</xacro:macro>
<xacro:common_link name="base_link" material="Green" path="mecanum" rpy="0 0 0">
<inertial>
<origin xyz="0.00498197982182523 5.70233829969297E-05 -0.0121008098068578" rpy="0 0 0"/>
<mass value="0.486218814966626"/>
<inertia
ixx="0.00196277727666921"
ixy="2.50447049446755E-07"
ixz="0.000140534767811098"
iyy="0.00457256033711368"
iyz="2.68618064993882E-07"
izz="0.00493927269870476"/>
</inertial>
</xacro:common_link>
<xacro:fixed_joint name="base_joint" parent="base_footprint" child="base_link" xyz="0.0 0.0 0.0815" rpy="0 0 0"/>
另外,如果想要在gazebo中给小车上色,就需要加上gazebo能够识别的颜色标签:
<gazebo reference="base_link">
<material value="Gazebo/Green"/>
</gazebo>