一.利用xacro理解机器人建模

当我们创建复杂的机器人模型时,URDF的灵活性将会降低,URDF缺少的主要特性是简单的、可重用性,模块化和可编程性。

URDF是一个单独的文件我们不能在它里面包含其他的URDF文件。这降低了代码的模块化特性。所有代码都必须放在一个文件中,这会降低代码的简单性。

使用xacro的机器人模型将满足所有这些条件。xacro的一些主要的特点如下:

*简化URDF : xacro是URDF的高级版本,他在机器人描述中创建宏并重用宏。这可以减少代码长度。此外,它还可以包含来自其他文件的宏,使代码更简单、更易读和更模块化。

*可编程性 : xacro语言在其描述中支持简单的编程语句。有变量、常量、数值表达式、条件语句等使描述更加智能和高效。

我们可以说xacro是URDF的高级版本,在需要的时候,我们可以利用ros工具将xacro定义转换为URDF。

我们可以用xacro创建

  1 <?xml version="1.0"?>
2
3 <robot xmlns:xacro="http://www.ros.org/wiki/xacro"
4 xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sen sor"
5 xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlsch ema/#controller"
6 xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlsche ma/#interface"
7 name="pan_tilt">
8
9
10 <xacro:property name="base_link_length" value="0.01" />
11 <xacro:property name="base_link_radius" value="0.2" />
12
13 <xacro:property name="pan_link_length" value="0.4" />
14 <xacro:property name="pan_link_radius" value="0.04" />
15
16 <xacro:property name="tilt_link_length" value="0.4" />
17 <xacro:property name="tilt_link_radius" value="0.04" />
18
19
20 <xacro:macro name="inertial_matrix" params="mass">
21 <inertial>
22 <mass value="${mass}" />
23 <inertia ixx="0.5" ixy="0.0" ixz="0.0"
24 iyy="0.5" iyz="0.0"
25 izz="0.5" />
26 </inertial>
27 </xacro:macro>
28
29
30
31 <link name="base_link">
32
33 <visual>
34 <geometry>
35 <cylinder length="${base_link_length}" radius="${base_link_radius}"/>
36 </geometry>
37 <origin rpy="0 0 0" xyz="0 0 0"/>
38 <material name="yellow">
39 <color rgba="1 1 0 1"/>
40 </material>
41 </visual>
42
43 <collision>
44 <geometry>
45 <cylinder length="${base_link_length+0.02}" radius="0.2"/>
46 </geometry>
47 <origin rpy="0 0 0" xyz="0 0 0"/>
48 </collision>
49 <xacro:inertial_matrix mass="1"/>
50 </link>
51
52 <joint name="pan_joint" type="revolute">
53 <parent link="base_link"/>
54 <child link="pan_link"/>
55 <origin xyz="0 0 0.1"/>
56 <axis xyz="0 0 1" />
57 <limit effort="300" velocity="0.1" lower="-3.14" upper="3.14"/>
58 <dynamics damping="50" friction="1"/>
59 </joint>
60
61 <link name="pan_link">
62 <visual>
63 <geometry>
64 <cylinder length="${pan_link_length}" radius="${pan_link_radius}"/>
65 </geometry>
66 <origin rpy="0 0 0" xyz="0 0 0.09"/>
67 <material name="red">
68 <color rgba="0 0 1 1"/>
69 </material>
70 </visual>
71 <collision>
72 <geometry>
73 <cylinder length="${pan_link_length}" radius="${pan_link_radius+0.02}" />
74 </geometry>
75 <origin rpy="0 0 0" xyz="0 0 0.09"/>
76 </collision>
77 <xacro:inertial_matrix mass="1"/>
78 </link>
79
80 <joint name="tilt_joint" type="revolute">
81 <parent link="pan_link"/>
82 <child link="tilt_link"/>
83 <origin xyz="0 0 0.2"/>
84 <axis xyz="0 1 0" />
85 <limit effort="300" velocity="0.1" lower="-4.64" upper="-1.5"/>
86 <dynamics damping="50" friction="1"/>
87 </joint>
88
89 <link name="tilt_link">
90 <visual>
91 <geometry>
92 <cylinder length="${tilt_link_length}" radius="${tilt_link_radius}"/>
93 </geometry>
94 <origin rpy="0 1.5 0" xyz="0 0 0"/>
95 <material name="green">
96 <color rgba="1 0 0 1"/>
97 </material>
98 </visual>
99 <collision>
100 <geometry>
101 <cylinder length="${tilt_link_length}" radius="${tilt_link_radius+0.2} "/>
102 </geometry>
103 <origin rpy="0 1.5 0" xyz="0 0 0"/>
104 </collision>
105 <xacro:inertial_matrix mass="1"/>
106 </link>
107
108
109 </robot>

前面两行代码指定了解析xacro文件所需的所有xacro文件的命名空间。在指定命名空间后,我们需要添加xacro文件名称。

1.使用属性

使用xacro,我们可以在xacro文件中声明常量和属性,即以名称表示的值,这些常量或属性可以在代码中的任何地方使用。常量的主要用途是,避免在连杆和关节上提供硬编码的值,而是保持一些常量,

这样就更容易更改这些值了,而不是查找并替换这些硬编码的值。

这里给出一个使用属性的例子。我们声明了基座连杆和平移连杆的长度和半径。因此,在这里很容易改变尺寸而不是改变每个尺寸的值。

<xacro:property name="base_link_length" value="0.01" />

<xacro:property name="base_link_radius" value="0.2" />

<xacro:property name="pan_link_length" value="0.4" />
 <xacro:property name="pan_link_radius" value="0.04" />

我们可以通过下面的定义,使用变量的值来替换硬编码的值。

<cylinder length= "${pan_link_length}"

radius="${pan_link_radius}"/>

在这里,旧值0.4被替换为{pan_link_length},  0.04被替换为{pan_link_radius}.

2.使用数学表达式

我们可以使用基本操作(如+、-、*、/、一元求负运算和括号)在${}中构建数学表达式。目前还不支持指数和模数。下面是一个代码中使用简单的数学表达式的例子

<cylinder length="${pan_link_length}"

radius="${pan_link_radius+0.02}"/>

3.使用宏

xacro的一个主要特性就是它支持宏(macro).我们可以使用宏来减少复杂定义的长度。

这是一个我们在惯性代码中使用的宏定义:

<xacro:macro name="inertial_matrix" params="mass">
           <inertial>
                    <mass value="${mass}" />
                      <inertia ixx="0.5" ixy="0.0" ixz="0.0"
                           iyy="0.5" iyz="0.0"izz="0.5" />
             </inertial>
 </xacro:macro>
这里宏被命名为inertial_matrix,他的参数是mass。mass参数可以在惯性定义中使用${mass}。我们可以用一行命令来替换每一个惯性码,如下所示:

<xacro : inertial_matrix mass="1"/>

与URDF相比,xacro定义提高了代码可读性并减少了行数。接下来,我们将学习如何将xacro转换为URDF文件。

二.将xacro转换为URDF

设计完成xacro文件后,我们可以使用以下命令将其转换为URDF文件:

$ rosrun xacro xacro pan_tilt.xacro --inorder > pan_tilt_generated.urdf

我们还可以在ROS启动文件中使用下面的命令将xacro转换为URDF,并将其作为robot_description的参数:

<param name="robot_descriptipn" command="${find xacro)/xacro --inorder

${find mastering_ros_robot_description_pkg)/urdf/pan_tilt.xacro"

我们可以通过启动文件来查看pan_tilt的xacro文件,并使用以下命令来启动它:

$ roslaunch mastering_ros_robot_description_pkg view_pan_tilt_xacro.launch

05-15 13:10