首页 关于
树枝想去撕裂天空 / 却只戳了几个微小的窟窿 / 它透出天外的光亮 / 人们把它叫做月亮和星星
目录

Xacro

在前面几篇文章中,我们用URDF描述了一个双足机器人的模型GRobot.urdf。 在这个URDF文件中,我们写了很多重复的代码,对每个Link和Joint都单独写了很多参数,如果可以重用代码的话这个描述文件可以变短一些, 可读性也会增加很多。

在本文中我们介绍xacro,它可以用来简化URDF文件。它主要有三种有用的工具,用于定义一些常数、提供一些简单的数学运算、宏定义。 在使用xacro来描述机器人模型的时候,我们一般使用"*.xacro"后缀来命名文件。此外还需要在文件的开始写下如下两行xml语句, 添加xacro命名空间,用于解析xacro文件。

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

1. 定义变量

首先,让我们看一下GRobot的base_link的urdf描述。我们用一个box来表示机器人的躯干, 分别用0.05, 0.2, 0.3指定了躯干在xyz三个轴上的几何尺寸。但这很不直观,一般情况下,我们期望的描述是躯干长多少、有多宽、有多厚。 这点可以通过Xacro的property特性来实现。

        <link name="base_link">
            <visual>
                <geometry><box size="0.05 0.2 0.3"/></geometry>
                <material name="blue"/>
            </visual>
        </link>

我们可以通过标签xacro:property定义一些常数来描述躯干的长宽厚。这些property的标签可以放到XML文档中的任意位置, 通常我习惯将它们集中放在文档的开头,这样可以比较方便的找到并修改它们。

        <xacro:property name="body_length" value="0.3" />
        <xacro:property name="body_width" value="0.2" />
        <xacro:property name="body_depth" value="0.05" />

在机器人模型中,我们可以像下面所示的代码一样直接使用这些property,有点类似Unix系统中使用系统变量。 这样就避免了硬编码,为我们提供了很大的灵活度。而且物理意义一目了然,提高了文件的可读性。

        <link name="base_link">
            <visual>
                <geometry><box size="${body_depth} ${body_width} ${body_length}"/></geometry>
                <material name="blue"/>
            </visual>
        </link>

对urdf的这些修改都会体现在本文的例程文件GRobot.xacro中,我们可以使用ROS提供的xacro工具将其解析成urdf文件:

        $ roscd learning_urdf
        $ rosrun xacro xacro urdf/GRobot.xacro --inorder > GRobot.urdf
节点xacro会把解析之后的文件内容打印到标准输出里,上面指令最后的" > GRobot.urdf"使用了一个Unix系统中非常强大的输出重定向的功能, 将标准输出的内容重定向到文件GRobot.urdf中。下图是解析后文件的片选,我们可以关注一下图中黄色光标所在的位置,它是"base_link"的几何描述, 与我们之前手写的内容一致。

实际上Xacro的解析器会把${property}的内容用property的值替换掉,在刚刚的例程当中,就是用0.05, 0.2和0.3分别替换了${body_depth}, ${body_width}和${body_length}。它的实现过程不仅仅是替换变量,而有点像是C语言中的宏定义,是字符替换。比如说如下的xacro描述:

        <xacro:property name="robotname" value="marvin" />
        <link name="${robotname}s_leg" />
经解析之后就可以得到:
        <link name="marvins_leg" />

2. 数学表达式

下面让我们再来看一下如下的代码,它描述了左肩上的一个自由度。这里我们主要关注origin标签,它描述了link的坐标系,希望将它绕X轴旋转90度。 在URDF中采用的是弧度制,所以这里的用1.57079来近似\(\frac{\pi}{2}\)。这个很不直观,我们需要做一系列的换算才能得到最后的结果。

        <link name="left_shoulder_y">
            <visual>
                <geometry><cylinder length="0.06" radius="0.02"/></geometry>
                <origin xyz="0 0 0" rpy="1.57079 0 0"/>
                <material name="white"/>
            </visual>
        </link>
如果URDF文件能够支持数学表达式,就会方便很多。这里我们可以用如下的语句替代origin标签,用${}把数学表达式包含在其中。 表达式中的pi是xacro中定义的\(\pi\)。
        <origin xyz="0 0 0" rpy="${0.5 * pi} 0 0"/>
经xacro工具解析后就变成了:

3. 宏

定义变量和应用数学公式都还只是基础,下面我们将介绍xacro的宏,它可以大幅简化机器人模型的描述。

下面的代码列举了左肩绕xyz三个轴自由度的描述形式。可以看到它们基本都是一样的,只是坐标原点略有不同而已。 我们实际上写了三遍,虽然可以复制粘贴,但过程仍然十分繁琐而且容易出错,而且阅读起来很麻烦。

        <link name="left_shoulder_y">
            <visual>
                <geometry><cylinder length="0.06" radius="0.02"/></geometry>
                <origin xyz="0 0 0" rpy="1.57079 0 0"/>
                <material name="white"/>
            </visual>
        </link>
        <link name="left_shoulder_x">
            <visual>
                <geometry><cylinder length="0.06" radius="0.02"/></geometry>
                <origin xyz="0 0 0" rpy="0 1.57079 0"/>
                <material name="white"/>
            </visual>
        </link>
        <link name="left_shoulder_z">
            <visual>
                <geometry><cylinder length="0.06" radius="0.02"/></geometry>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <material name="white"/>
            </visual>
        </link>
xacro的宏就为我们提供了解决这一问题的方法。我们可以像下面的代码所示的那样,定义一个宏:
        <xacro:macro name="freedom_link">
            <visual>
                <geometry><cylinder length="0.06" radius="0.02"/></geometry>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <material name="white"/>
            </visual>
        </xacro:macro>
然后在需要的地方用这个宏来代替,比如这里的z轴自由度:
        <link name="left_shoulder_z">
            <xacro:freedom_link />
        </link>
在原来的urdf文件中,所有的23个自由度都用同一个尺寸的圆柱体来表示,只是方向上略有差异。上面的宏还有些不足,它不能够直接替换所有的这些圆柱体。 xacro的宏是支持定制参数的,比如说:
        <xacro:macro name="freedom_link" params="rpy xyz">
            <visual>
                <geometry><cylinder length="0.06" radius="0.02"/></geometry>
                <origin xyz="${xyz}" rpy="${rpy}"/>
                <material name="white"/>
            </visual>
        </xacro:macro>
这样我们就可以通过参数来描述各个自由度的细微差异:
        <link name="left_shoulder_y"><xacro:freedom_link xyz="0 0 0" rpy="${0.5 * pi} 0 0"/></link>
        <link name="left_shoulder_x"><xacro:freedom_link xyz="0 0 0" rpy="0 ${0.5 * pi} 0"/></link>
        <link name="left_shoulder_z"><xacro:freedom_link xyz="0 0 0" rpy="0 0 0"/></link>

4. 在ROS中使用Xacro

我们有两种使用.xacro文件的方法,第一种就是先用xacro工具将之转换为.urdf文件,然后正常使用之。

        $ roscd learning_urdf
        $ rosrun xacro xacro urdf/GRobot.xacro --inorder > GRobot.xacro.urdf
        $ roslaunch learning_urdf display.launch model:=urdf/GRobot.xacro.urdf
另一种方法就是在roslaunch中通过脚本使用,这种方法不必显式的将.xacro文件转换为.urdf文件,在文件管理上有些方便。但是在每次通过launch文件使用它的时候,系统后台都会先进行一次转换, 这增加了系统的计算负担。我们再写一个launch文件内容如下:
        <launch>
            <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find learning_urdf)/urdf/GRobot.xacro'"/>
            <node name="joint_state_publisher" pkg="learning_urdf" type="joint_state_publisher" />
            <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
            <node name="rviz" pkg="rviz" type="rviz" args="-d $(find urdf_tutorial)/urdf.rviz" required="true" />
        </launch>
将之保存为display.xacro.launch文件,这个文件与上一节中最后给出的launch文件类似。 这里只是在第二行中用command属性调用了xacro工具对描述文件进行了解析,而不是直接用textfile指出描述文件路径。这样我们可以直接通过如下指令, 让GRobot在空间中扭曲。
        $ roscd learning_urdf
        $ roslaunch learning_urdf display.xacro.launch

5. 总结

在本文中我们介绍了Xacro的三个主要功能:定义变量、数学表达式、可带参数的宏定义。借助这三个基本的功能,我们可以简化描述机器人结构的urdf文件。 它的便利性在一些复杂的机器人结构中将得到更深刻的体现。




Copyright @ 高乙超. All Rights Reserved. 京ICP备16033081号-1