使用 Xacro 清理您的代码

目标: 学习使用 Xacro 减少 URDF 文件中的代码量的一些技巧

教程级别: 中级

**时间:**20分钟

到目前为止,如果你在家里跟着这些步骤自己设计机器人,你可能已经对进行各种数学计算来正确解析非常简单的机器人描述感到厌烦了。幸运的是,你可以使用 xacro 包来简化你的生活。它有三个非常有帮助的功能。

  • 常量

  • 简单数学

在本教程中,我们将介绍所有这些快捷方式,以帮助减少URDF文件的整体大小,并使其更易于阅读和维护。

使用Xacro

正如其名称所示,xacro 是一种用于 XML 的宏语言。xacro 程序运行所有的宏并输出结果。典型的用法如下所示:

xacro model.xacro > model.urdf

您还可以在启动文件中自动生成 URDF。这很方便,因为它会保持最新状态并且不占用硬盘空间。然而,生成过程需要时间,所以请注意您的启动文件可能需要更长的启动时间。

path_to_urdf = get_package_share_path('pr2_description') / 'robots' / 'pr2.urdf.xacro'
robot_state_publisher_node = launch_ros.actions.Node(
    package='robot_state_publisher',
    executable='robot_state_publisher',
    parameters=[{
        'robot_description': ParameterValue(
            Command(['xacro ', str(path_to_urdf)]), value_type=str
        )
    }]
)

在 URDF 文件的顶部,您必须指定一个命名空间,以便文件能够正确解析。例如,下面是有效 xacro 文件的前两行:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="firefighter">

常量

让我们快速查看一下 R2D2 中的 base_link。

<link name="base_link">
  <visual>
    <geometry>
      <cylinder length="0.6" radius="0.2"/>
    </geometry>
    <material name="blue"/>
  </visual>
  <collision>
    <geometry>
      <cylinder length="0.6" radius="0.2"/>
    </geometry>
  </collision>
</link>

这里的信息有些冗余。我们重复指定了圆柱体的长度和半径。更糟糕的是,如果我们想要更改它,我们需要在两个不同的位置进行修改。

幸运的是,xacro 允许您指定属性作为常量。因此,我们可以将上述代码改写为以下形式。

<xacro:property name="width" value="0.2" />
<xacro:property name="bodylen" value="0.6" />
<link name="base_link">
    <visual>
        <geometry>
            <cylinder radius="${width}" length="${bodylen}"/>
        </geometry>
        <material name="blue"/>
    </visual>
    <collision>
        <geometry>
            <cylinder radius="${width}" length="${bodylen}"/>
        </geometry>
    </collision>
</link>
  • 两个值在前两行中指定。它们可以在任何地方(假设是有效的XML),在任何级别上定义,并且可以在使用之前或之后定义。通常它们放在顶部。

  • 在geometry元素中,我们使用美元符号和大括号表示值,而不是指定实际半径。

  • 此代码将生成上述显示的相同代码。

然后使用${}构造的内容值来替换${}。这意味着您可以将其与属性中的其他文本组合使用。

<xacro:property name=”robotname” value=”marvin” />
<link name=”${robotname}s_leg” />

这将生成

<link name=”marvins_leg” />

然而,${}中的内容不仅限于属性,这引出了我们的下一个要点...

数学

您可以使用四种基本运算符(+、-、*、/)、一元减号和括号在 ${} 结构中构建任意复杂的表达式。例如:

<cylinder radius="${wheeldiam/2}" length="0.1"/>
<origin xyz="${reflect*(width+.02)} 0 0.25" />

您还可以使用更多的基本数学运算,例如 sincos

这是 xacro 包中最大且最有用的组件。

简单宏

让我们来看一个简单无用的宏。

<xacro:macro name="default_origin">
    <origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:macro>
<xacro:default_origin />

(这是无用的,因为如果未指定原点,它与此值相同。) 此代码将生成以下内容。

<origin rpy="0 0 0" xyz="0 0 0"/>
  • 从技术上讲,名称不是必需的元素,但您需要指定它才能使用它。

  • 每个``<xacro:$NAME />``的实例都将替换为``xacro:macro``标记的内容。

  • 请注意,即使它们不完全相同(两个属性的顺序已交换),生成的 XML 是等效的。

  • 如果找不到具有指定名称的 xacro,则不会扩展它,并且不会生成错误。

参数化宏

你还可以对宏进行参数化,这样它们每次生成的文本就不会完全相同。当与数学功能结合使用时,这更加强大。

首先,让我们以一个在R2D2中使用的简单宏的例子来说明。

<xacro:macro name="default_inertial" params="mass">
    <inertial>
            <mass value="${mass}" />
            <inertia ixx="1e-3" ixy="0.0" ixz="0.0"
                 iyy="1e-3" iyz="0.0"
                 izz="1e-3" />
    </inertial>
</xacro:macro>

可以与以下代码一起使用

<xacro:default_inertial mass="10"/>

参数的作用类似于属性,你可以在表达式中使用它们。

你还可以使用整个代码块作为参数。

<xacro:macro name="blue_shape" params="name *shape">
    <link name="${name}">
        <visual>
            <geometry>
                <xacro:insert_block name="shape" />
            </geometry>
            <material name="blue"/>
        </visual>
        <collision>
            <geometry>
                <xacro:insert_block name="shape" />
            </geometry>
        </collision>
    </link>
</xacro:macro>

<xacro:blue_shape name="base_link">
    <cylinder radius=".42" length=".01" />
</xacro:blue_shape>
  • 要指定一个代码块参数,在其参数名之前加上一个星号。

  • 可以使用insert_block命令插入一个块

  • 按需插入块,可以插入多次

实际应用

xacro语言非常灵活,允许你做很多事情。除了上面显示的默认惯性宏之外,在`R2D2模型 <https://github.com/ros/urdf_tutorial/blob/master/urdf/08-macroed.urdf.xacro>`_ 中还有一些有用的使用xacro的方法。

要查看由xacro文件生成的模型,请运行与之前教程相同的命令:

ros2 launch urdf_tutorial display.launch.py model:=urdf/08-macroed.urdf.xacro

(启动文件一直在运行xacro命令,但是因为没有需要扩展的宏,所以没有关系)

腿宏

通常情况下,您希望在不同位置创建多个外观相似的对象。您可以使用宏和一些简单的数学计算来减少需要编写的代码量,就像我们在 R2 的两条腿上所做的一样。

<xacro:macro name="leg" params="prefix reflect">
    <link name="${prefix}_leg">
        <visual>
            <geometry>
                <box size="${leglen} 0.1 0.2"/>
            </geometry>
            <origin xyz="0 0 -${leglen/2}" rpy="0 ${pi/2} 0"/>
            <material name="white"/>
        </visual>
        <collision>
            <geometry>
                <box size="${leglen} 0.1 0.2"/>
            </geometry>
            <origin xyz="0 0 -${leglen/2}" rpy="0 ${pi/2} 0"/>
        </collision>
        <xacro:default_inertial mass="10"/>
    </link>

    <joint name="base_to_${prefix}_leg" type="fixed">
        <parent link="base_link"/>
        <child link="${prefix}_leg"/>
        <origin xyz="0 ${reflect*(width+.02)} 0.25" />
    </joint>
    <!-- A bunch of stuff cut -->
</xacro:macro>
<xacro:leg prefix="right" reflect="1" />
<xacro:leg prefix="left" reflect="-1" />
  • 常见技巧 1:使用名称前缀获取两个名称相似的对象。

  • 常见技巧 2:使用数学计算来计算关节起源。在改变机器人的尺寸时,通过使用一些数学计算来计算关节偏移量的属性,可以节省很多麻烦。

  • 常见技巧 3:使用反射参数,并将其设置为 1 或 -1。请看看我们如何使用反射参数将腿放置在身体的 base_to_${prefix}_leg 起源的两侧。