3D

仿真环境

sapien

sapien官方教程

urdf 文件

Articulated Robotics 博客 urdf 专题页

ROS wiki

ROS 2 教程

总体架构

采用 link (构件)加 joint (关节)的方式描述可动物体,采用树形结构。

区分构件的两种方式:

  • 可动的每一个 part

  • 不可动但特征性强的(e.g. camera)

几种常见的 joint:

  1. Revolute:限制旋转关节(最小/最大角度限制)。
  2. Continuous:无限制旋转关节 (e.g. a wheel)。
  3. Prismatic:直线滑动关节(最小/最大运动限制)。
  4. Fixed:父子构件刚连接(区分构件的第二种方式)。

QQ_1766383582450

基本语法结构

urdf 基于 XML(可扩展标记语言),只关心逻辑结构,有严谨的嵌套关系。

第一行声明这是 XML 语言并声明版本,头尾封装所有内容。

点击查看代码
<?xml version="1.0"?>
<robot name="my_robot">
   ...
   all the rest of the tags
   ...
</robot>

除了 link 的名字(name),其他都是可选的。

  • Visual
    • Geometry:几何图形及其参数,或是一个 mesh 模型(从外部文件导入)
    • Origin:改变固有中心(几何图形的几何中心,mesh 文件导出时的原点)的位置,使 link 的位置符合关节逻辑
    • Material
      • Color:采用 RGBA 格式(RGBA 取值均为 0 ~ 1,A 是透明度(1是不透明))
      • Texture:可以传贴图(e.g. .jpg)
  • Collision
    Geometry and Origin: 一般照搬 Visual 里的,但为了计算方便,会把 mesh 抽象成更简单的几何图形
  • Inertial(惯性属性)
    • Mass:link 的质量
    • Origin:link 的质心,简单情况下一般为 link 的固有中心
    • Inertia:惯性矩阵(惯性矩与惯性积)

visual 与 collision 的 tag 可以有很多个。sapien 中自动合成多个 collision 形成复合碰撞体。

Joint tags

  • Name:关节名字(有时候不命名也没事,但命了一定没事)
  • Type:关节类型 (最常见的 fixed, prismatic, revolute, continuous).
  • Parent and child links:标明父子 links
  • Origin:两个 links 的关节位置间的位移

对于 fixed 以外的 joint 类型,还需包括:

  • Axis:关节运动(平移/旋转)的轴(axis)
  • Limits:
    • Upper and Lower position limits:距离(米)或角度(弧度制)
    • Velocity limits:速度限制(m/s 或 rad/s)
    • Effort limits:最大力或力矩限制(N 或 Nm)

Extra Tags

还有一些其他的 tag (这里考虑适用于 sapien 环境的)

material:定义颜色或贴图

mimic:模仿关节,用于 joint 标签内部

<mimic joint="joint_a" multiplier="1.0" offset="0.0" />

sapien 支持解析此标签。当你驱动 \(\text{joint_a}\) 时,被设置了 \(\text{mimic}\) 的从动关节会根据公式 \(\theta_{mimic} = \text{mult} * \theta_a + \text{offset}\) 自动同步。

transmission:传动系统,但在 sapien 中只判断那些是主动,哪些是从动。

对于 link 和 joint 的起名要符合命名规范,一般分别加 _link_joint

ROS conventions for humanoid robots

ROS conventions for mobile platforms

xacro

拆分 urdf

拆分后的文件通过“包含”机制重新组合。可以将其理解为一种逻辑上的“复制粘贴”,将子文件的内容嵌入到主文件中。

<xacro:include filename="other_file.xacro" />

层级关系:

  • 主文件:必须拥有完整的 robot 标签,并定义机器人名称 name 以及 xmlns:xacro 命名空间。
  • 子文件(被包含文件):同样需要 robot 标签和命名空间,但不需要指定 name。如果子文件指定了 name,它也可以作为一个独立的 URDF 文件使用。

为了区分文件功能,通常采用以下后缀规范:

  • 顶层总装文件:通常以 .urdf.xacro 结尾。
  • 子模块文件:后缀较为灵活,可以是 .xacro、.urdf.xacro 或其他自定义后缀。

变量定义与全局修改 (Properties)

<xacro:property name="arm_radius" value="0.5" />`
...
<cylinder radius="${arm_radius}" length="7" />

宏定义与模块复用 (Macros):可以定义一个“零件模板”,然后通过传入不同的参数来多次实例化。

<xacro:macro name="inertial_box" params="mass x y z *origin">
    <inertial>
        <xacro:insert_block name="origin"/>
        <mass value="${mass}" />
        <inertia ixx="${(1/12) * mass * (y*y+z*z)}" ixy="0.0" ixz="0.0"
                iyy="${(1/12) * mass * (x*x+z*z)}" iyz="0.0"
                izz="${(1/12) * mass * (x*x+y*y)}" />
    </inertial>
</xacro:macro>

...then ...

<xacro:inertial_box mass="12" x="2" y="3" z="4">
    <origin xyz="0 2 4" rpy="0 0 0"/>
</xacro:inertial_box>

... will expand to ...

<inertial>
    <origin xyz="0 2 4" rpy="0 0 0"/>
    <mass value="12" />
    <inertia ixx="25" ixy="0.0" ixz="0.0"
            iyy="20" iyz="0.0"
            izz="13" />
</inertial>

数学运算 (Math Expressions):URDF 只能填死数字,而 Xacro 允许在 ${} 中写数学表达式。

<cylinder length="${4*arm_radius + pi}">

Example

QQ_1766414458786

File:

点击查看代码
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="robot">

    <!-- This is an example of a URDF. -->
    <!-- As we move through the file, new things to note will be pointed out. -->
    <!-- It's not meant an example of GOOD design, but an example of some of the various features of URDF/xacro. -->



    <!-- This will include all the contents of example_include.xacro first. Go check it out! -->
    <xacro:include filename="example_include.xacro" />



    <!-- This first link called "world" is empty -->
    <link name="world"></link>


    <!-- A simple fixed joint from our empty world link, to our base. -->
    <!-- The base origin is offset from the world origin. -->
    <joint name="base_joint" type="fixed">
        <origin xyz="1.5 1.0 0" rpy="0 0 0"/>
        <parent link="world"/>
        <child link="base_link"/>
    </joint>


    <!-- base_link is a large rectangular plate. Some things to note: -->
    <!-- - We set the visual origin Z to half the box height, so that the link origin sits at the bottom of the box -->
    <!-- - We set the collision to be identical to the visual -->
    <!-- - We specified the colour manually (but still need to enter a name) -->
    <!-- - We specified all the inertial parameters manually -->
    <link name="base_link">
        <visual>
            <origin xyz="0 0 0.05" rpy="0 0 0"/>
            <geometry>
                <box size="2.5 1.5 0.1" />
            </geometry>
            <material name="green">
                <color rgba="0.2 1 0.2 1"/>
            </material>
        </visual>
        <collision>
            <origin xyz="0 0 0.05" rpy="0 0 0"/>
            <geometry>
                <box size="2.5 1.5 0.1" />
            </geometry>
        </collision>
        <inertial>
            <origin xyz="0 0 0.05" rpy="0 0 0"/>
            <mass value="12" />
            <inertia ixx="2.26" ixy="0.0" ixz="0.0" iyy="6.26" iyz="0.0" izz="8.5" />
        </inertial>
    </link>



    <!-- slider_joint lets slider_link move back and forth along the top of the base in one dimension.  -->
    <!-- - Origin is set to one of the top edges of the base_link box, so that our link skims across the top  -->
    <!-- - It moves along the X axis -->
    <!-- - We need to specify limits for the motion -->
    <joint name="slider_joint" type="prismatic">
        <origin xyz="-1.25 0 0.1" rpy="0 0 0"/>
        <parent link="base_link"/>
        <child link="slider_link"/>
        <axis xyz="1 0 0"/>
        <limit lower="0" upper="2" velocity="100" effort="100"/>
    </joint>


    <!-- slider_link is the box skimming across the top of the base. Its parameters are similar to the base_link, however: -->
    <!-- - Instead of explicitly describing a colour, it uses the named material "blue". It knows about "blue" that material was included in example_include.xacro. -->
    <!-- - Instead of explicitly describing the inertia, we use a macro that was defined in the example_include.xacro -->

    <link name="slider_link">
        <visual>
            <origin xyz="0 0 0.075" rpy="0 0 0"/>
            <geometry>
                <box size="0.5 0.25 0.15" />
            </geometry>
            <material name="blue" />
        </visual>
        <collision>
            <origin xyz="0 0 0.075" rpy="0 0 0"/>
            <geometry>
                <box size="0.5 0.25 0.15" />
            </geometry>
        </collision>
        <xacro:inertial_box mass="0.5" x="0.5" y="0.25" z="0.15">
            <origin xyz="0 0 0.075" rpy="0 0 0"/>
        </xacro:inertial_box>
    </link>



    <!-- arm_joint describes the rotation of the arm and is centred around the top corner of the slider box. -->
    <!-- - The axis of rotation is -1 in Y, so that positive is "up" -->
    <!-- - The upper limit uses xacro's mathematical features -->
    <joint name="arm_joint" type="revolute">
        <origin xyz="0.25 0 0.15" rpy="0 0 0"/>
        <parent link="slider_link"/>
        <child link="arm_link"/>
        <axis xyz="0 -1 0"/>
        <limit lower="0" upper="${pi/2}" velocity="100" effort="100"/>
    </joint>


    <!-- arm_link describes the arm -->
    <!-- - We use the "property" feature to define the arm length and radius and use them multiple times -->
    <!-- - The visual/collision origin is set to halfway along the length (similar to the box), but also with a rotation (again using the mathematical features). -->
    <!--   This is because the cylinder extends along the Z axis by default, but we want it to be along the X axis (when the joint is at 0) -->

    <xacro:property name="arm_length" value="1" />
    <xacro:property name="arm_radius" value="0.1" />
    <link name="arm_link">
        <visual>
            <origin xyz="${arm_length/2} 0 0" rpy="0 ${pi/2} 0"/>
            <geometry>
                <cylinder length="${arm_length}" radius="${arm_radius}" />
            </geometry>
            <material name="orange" />
        </visual>
        <collision>
            <origin xyz="${arm_length/2} 0 0" rpy="0 ${pi/2} 0"/>
            <geometry>
                <cylinder length="${arm_length}" radius="${arm_radius}" />
            </geometry>
        </collision>
        <xacro:inertial_cylinder mass="1.0" length="${arm_length}" radius="${arm_radius}">
            <origin xyz="${arm_length/2} 0 0" rpy="0 ${pi/2} 0"/>
        </xacro:inertial_cylinder>
    </link>


    <!-- camera_joint describes where the camera is relative to the arm -->
    <!-- - Even though the camera isn't moving relative to the arm, it will probably be helpful to have its own link/frame rather than just adding more visuals to the arm -->
    <!-- - For this example, the camera_link origin will be at the centre of the camera's "sensor" -->
    <joint name="camera_joint" type="fixed">
        <origin xyz="${arm_length} 0 ${arm_radius + 0.075}" rpy="0 0 0"/>
        <parent link="arm_link"/>
        <child link="camera_link"/>
    </joint>


    <!-- camera_link describes the camera at the end of the arm -->
    <!-- - It has multiple visual elements, which ultimately get combined together -->
    <!-- - Even if we specify different materials, RViz will just colour them all the same as the first -->
    <!-- - Although we could also specify multiple collision geometries, instead we just use a single box that encompasses the whole camera -->
    <link name="camera_link">
        <visual>
            <origin xyz="-0.03 0 0" rpy="0 0 0"/>
            <geometry>
                <box size="0.06 0.15 0.15" />
            </geometry>
            <material name="white" />
        </visual>
        <visual>
            <origin xyz="0.03 0 0" rpy="0 ${pi/2} 0"/>
            <geometry>
                <cylinder length="0.06" radius="0.04" />
            </geometry>
            <material name="blue" />
        </visual>
        <collision>
            <origin xyz="0.0 0 0" rpy="0 0 0"/>
            <geometry>
                <box size="0.12 0.15 0.15" />
            </geometry>
        </collision>
        <xacro:inertial_box mass="0.1" x="0.12" y="0.15" z="0.15">
            <origin xyz="0.0 0 0" rpy="0 0 0"/>
        </xacro:inertial_box>
    </link>


    <xacro:include filename="example_gazebo.xacro" />


</robot>

Include File:

点击查看代码
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

    <!-- This file is not a robot in and of itself, it just contains some useful tags that could be included in any robot -->

    <!-- Specify some colours -->

    <material name="white">
        <color rgba="1 1 1 1"/>
    </material>

    <material name="orange">
        <color rgba="1 0.3 0.1 1"/>
    </material>

    <material name="blue">
        <color rgba="0.2 0.2 1 1"/>
    </material>



    <!-- Specify some standard inertial calculations https://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
    <!-- These make use of xacro's mathematical functionality -->

    <xacro:macro name="inertial_sphere" params="mass radius *origin">
        <inertial>
            <xacro:insert_block name="origin"/>
            <mass value="${mass}" />
            <inertia ixx="${(2/5) * mass * (radius*radius)}" ixy="0.0" ixz="0.0" iyy="${(2/5) * mass * (radius*radius)}" iyz="0.0" izz="${(2/5) * mass * (radius*radius)}" />
        </inertial>
    </xacro:macro>


    <xacro:macro name="inertial_box" params="mass x y z *origin">
        <inertial>
            <xacro:insert_block name="origin"/>
            <mass value="${mass}" />
            <inertia ixx="${(1/12) * mass * (y*y+z*z)}" ixy="0.0" ixz="0.0" iyy="${(1/12) * mass * (x*x+z*z)}" iyz="0.0" izz="${(1/12) * mass * (x*x+y*y)}" />
        </inertial>
    </xacro:macro>


    <xacro:macro name="inertial_cylinder" params="mass length radius *origin">
        <inertial>
            <xacro:insert_block name="origin"/>
            <mass value="${mass}" />
            <inertia ixx="${(1/12) * mass * (3*radius*radius + length*length)}" ixy="0.0" ixz="0.0" iyy="${(1/12) * mass * (3*radius*radius + length*length)}" iyz="0.0" izz="${(1/2) * mass * (radius*radius)}" />
        </inertial>
    </xacro:macro>


</robot>

```
posted @ 2025-12-21 17:01  Semorius  阅读(2)  评论(0)    收藏  举报