简介:
机器人建模也是可视化实现中的比较重要的一部分内容,ROS2 中的建模是由 URDF 实现的。
URDF 是 Unified Robot Description Format 的首字母缩写,直译为统一(标准化)机器人描述格式,可以以一种 XML 的方式描述机器人的部分结构,比如:底盘、摄像头、激光雷达、机械臂以及不同关节的自由度等,该文件可以被 C++ 内置的解释器转换成 rviz 或仿真环境中的可视化机器人模型。
在 rviz2 中如何显示机器人模型呢? URDF 是一种机器人建模文件,rviz2 可以按照该文件渲染出图形化的机器人模型。换言之,rviz2 必须集成 URDF 文件才能显示机器人模型,本节就将主要介绍该二者集成的基本实现流程。
案例1:在 rviz2 中显示一个简单的盒状机器人。(演示创建URDF文件的基本流程)
(1)安装案例所需的两个功能包:
sudo apt install ros-humble-joint-state-publisher
sudo apt install ros-humble-joint-state-publisher-gui
(2)终端下进入工作空间的src目录,调用如下命令创建C++功能包:
ros2 pkg create cpp06_urdf --build-type ament_cmake
(3)功能包下新建 urdf、rviz、launch、meshes目录以备用,其中 urdf 目录下再新建子目录 urdf 与 xacro,分别用于存储 urdf 文件和 xacro 文件。
(4)功能包 cpp06_urdf 的 urdf/urdf 目录下,新建 urdf 文件 demo01_helloworld.urdf,并编辑文件,输入如下内容:
XML
<!--
需求:显示一盒状机器人
-->
<robot name="hello_world">
<link name="base_link">
<visual>
<geometry>
<box size="0.5 0.2 0.1"/>
</geometry>
</visual>
</link>
</robot>
(5)功能包 cpp06_urdf 的 launch 目录下,新建 launch 文件 display.launch.py,并编辑文件,输入如下内容:
python
from launch import LaunchDescription
from launch_ros.actions import Node
import os
from ament_index_python.packages import get_package_share_directory
from launch_ros.parameter_descriptions import ParameterValue
from launch.substitutions import Command,LaunchConfiguration
from launch.actions import DeclareLaunchArgument
#示例: ros2 launch cpp06_urdf display.launch.py model:=`ros2 pkg prefix --share cpp06_urdf`/urdf/urdf/demo01_helloworld.urdf
def generate_launch_description():
cpp06_urdf_dir = get_package_share_directory("cpp06_urdf")
default_model_path = os.path.join(cpp06_urdf_dir,"urdf/urdf","demo01_helloworld.urdf")
default_rviz_path = os.path.join(cpp06_urdf_dir,"rviz","display.rviz")
model = DeclareLaunchArgument(name="model", default_value=default_model_path)
# 加载机器人模型
# 1.启动 robot_state_publisher 节点并以参数方式加载 urdf 文件
robot_description = ParameterValue(Command(["xacro ",LaunchConfiguration("model")]))
robot_state_publisher = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
parameters=[{"robot_description": robot_description}]
)
# 2.启动 joint_state_publisher 节点发布非固定关节状态
joint_state_publisher = Node(
package="joint_state_publisher",
executable="joint_state_publisher"
)
# rviz2 节点
rviz2 = Node(
package="rviz2",
executable="rviz2"
# arguments=["-d", default_rviz_path]
)
return LaunchDescription([
model,
robot_state_publisher,
joint_state_publisher,
rviz2
])
launch 文件启动时,可以通过参数 model 动态传入被加载的 urdf 文件
(6)在 package.xml 中需要手动添加一些执行时依赖,核心内容如下:

(7)在功能包下,新建了若干目录,需要为这些目录配置安装路径,核心内容如下:

(8)编译,执行
python
colcon build --packages-select cpp06_urdf
. install/setup.bash
ros2 launch cpp06_urdf display.launch.py
(9)rviz配置:
- Global Options 中的 Fixed Frame 设置为 base_link(和 urdf 文件中 link 标签的 name 一致);
- 添加机器人模型插件,并将参数 Description Topic 的值设置为 /robot_description,即可显示机器人模型。
在本文的后续案例中,所有实现都遵循上述步骤,在后续案例中我们只需要关注 urdf 实现即可,launch 文件和 配置文件无需修改。
URDF文件语法及实现:
URDF 文件是一个标准的 XML 文件,在 ROS 中预定义了一系列的标签用于描述机器人模型,ROS 的 URDF 中机器人的组成却是较为简单的,主要标签如下:
- robot 标签,这是整个 urdf 文件的根标签;
- link 标签,用于描述机器人刚体部分的标签;
- joint 标签,是用于连接不同刚体的"关节"。
Robot的第一个子标签----link
属性:
- name(必填):为连杆命名。
子标签
<visual>(可选):用于描述link的可视化属性,可以设置link的形状(立方体、球体、圆柱等)。
- name(可选):指定link名称,此名称会映射为同名坐标系,还可以通过引用该值定位定位link。
- <geometry> (必填):用于设置link的形状,比如:立方体、球体或圆柱。
- <box>:立方体标签,通过size属性设置立方体的边长,原点为其几何中心。
- <cylinder>:圆柱标签,通过radius属性设置圆柱半径,通过length属性设置圆柱高度,原点为其几何中心。
- <sphere>:球体标签,通过radius属性设置球体半径,原点为其几何中心。
- <mesh>:通过属性filename引用"皮肤"文件,为link设置外观,该文件必须是本地文件。使用 package://<packagename>/<path>为文件名添加前缀。
- <origin> (可选):用于设置link的相对偏移量以及旋转角度,如未指定则使用默认值(无偏移且无旋转)。
- xyz:表示x、y、z三个维度上的偏移量(以米为单位),不同数值之间使用空格分隔,如未指定则使用默认值(三个维度无偏移)。
- rpy:表示翻滚、俯仰与偏航的角度(以弧度为单位),不同数值之间使用空格分隔,如未指定则使用默认值(三个维度无旋转)。
- <material> (可选):视觉元素的材质。也可以在根标签robot中定义material标签,然后,可以在link中按名称进行引用。
- name(可选):为material指定名称,可以通过该值进行引用。
- <color>(可选):rgba 材质的颜色,由代表red/green/blue/alpha 的四个数字组成,每个数字的范围为 [0,1]。
- <texture>(可选):材质的纹理,可以由属性filename设置。
<collision>(可选):link的碰撞属性。可以与link的视觉属性一致,也可以不同,比如:我们会通常使用更简单的碰撞模型来减少计算时间,或者设置的值大于link的视觉属性,以尽量避免碰撞。另外,同一链接可以存在多个 <collision>标签实例,多个几何图形组合表示link的碰撞属性。
- name(可选):为collision设置名称。
- <geometry>(必须):请参考visual标签的geometry使用规则。
- <origin>(可选):请参考visual标签的origin使用规则。
<inertial>(可选):用于设置link的质量、质心位置和中心惯性特性,如果未指定,则默认为质量为0、惯性为0。
- <origin> (可选):该位姿(平移、旋转)描述了链接的质心框架 C 相对于链接框架 L 的位置和方向。
- xyz:表示从 Lo(链接框架原点)到 Co(链接的质心)的位置向量为 x L̂x + y L̂y + z L̂z,其中 L̂x、L̂y、L̂z 是链接框架 L 的正交单位向量。
- rpy:将 C 的单位向量 Ĉx、Ĉy、Ĉz 相对于链接框架 L 的方向表示为以弧度为单位的欧拉旋转序列 (r p y)。注意:Ĉx、Ĉy、Ĉz 不需要与连杆的惯性主轴对齐。
- <mass>(必填):通过其value属性设置link的质量。
- <inertia>(必填):对于固定在质心坐标系 C 中的单位向量 Ĉx、Ĉy、Ĉz,该连杆的惯性矩 ixx、iyy、izz 以及关于 Co(连杆的质心)的惯性 ixy、ixz、iyz 的乘积。
注意:<collision> 和 <inertial> 在仿真环境下才需要使用到,如果只是在 rviz2 中集成 urdf,那么不必须为 link 定义这两个标签。
案例二:分别生成长方体、圆柱与球体的机器人部件
(1)功能包 cpp06_urdf 的 urdf/urdf 目录下,新建 urdf 文件 demo02_link.urdf,并编辑文件,输入如下内容:
XML
<robot name="link_demo">
<!-- 定义颜色 -->
<material name="yellow">
<color rgba="0.7 0.7 0 0.8" />
</material>
<link name="base_link">
<visual>
<!-- 形状 -->
<geometry>
<!-- 长方体的长宽高 -->
<box size="0.5 0.3 0.1" />
<!-- 圆柱,半径和长度 -->
<!-- <cylinder radius="0.5" length="1.0" /> -->
<!-- 球体,半径-->
<!-- <sphere radius="0.3" /> -->
</geometry>
<!-- xyz坐标 rpy翻滚俯仰与偏航角度(3.14=180度) -->
<origin xyz="0 0 0" rpy="0 0 0" />
<!-- 调用已定义的颜色 -->
<material name="yellow"/>
</visual>
</link>
</robot>
(2)终端运行:
XML
ros2 launch cpp06_urdf display.launch.py model:=`ros2 pkg prefix --share cpp06_urdf`/urdf/urdf/demo02_link.urdf
#启动一个cpp06_urdf`/urdf/urdf/demo02_link.urdf 路径下的URDF机器人模型并在RViz中显示它
案例三:利用mesh子标签为机器人更方便地设置外观
知识点:
<mesh>:通过属性filename引用"皮肤"文件,为link设置外观,该文件必须是本地文件。使用 package://<packagename>/<path>为文件名添加前缀。
mesh文件地制作其实比较麻烦,一般机器人厂家会制作好并给你使用,或者我们去github上面使用别人制作的皮肤文件
具体步骤:
(1)到我的资源博客里下载一个mesh文件
(2)将该mesh文件拖到meshes文件夹中

(3)功能包 cpp06_urdf 的 urdf/urdf 目录下,新建 urdf 文件 demo03_link_mesh.urdf,并编辑文件,输入如下内容:
XML
<robot name="link_demo">
<!-- 定义颜色 -->
<material name="yellow">
<color rgba="0.7 0.7 0 0.8" />
</material>
<link name="base_link">
<visual>
<!-- 形状 -->
<geometry>
<!-- 长方体的长宽高 -->
<!-- <box size="0.5 0.3 0.1" /> -->
<!-- 圆柱,半径和长度 -->
<!-- <cylinder radius="0.5" length="1.0" /> -->
<!-- 球体,半径-->
<!-- <sphere radius="0.3" /> -->
<mesh filename="package://cpp06_urdf/meshes/waffle_base.stl" scale="0.01 0.01 0.01"/>
</geometry>
<!-- xyz坐标 rpy翻滚俯仰与偏航角度(3.14=180度) -->
<origin xyz="0 0 0" rpy="0 0 0" />
<!-- 调用已定义的颜色 -->
<material name="yellow"/>
</visual>
</link>
</robot>
**提醒:**在xml文件中,报错提示非常不明显,所以一定要小心编写,或者编写完之后丢给豆包,让他检查一下哪里有错误。比如我在 scale="0.01 0.01 .0.01中多打了一个小数点, mesh文件的路径写错了,都是能够正常编译运行通过的,但是就是无法展示想要的显示效果。
<mesh filename="package://cpp06_urdf/meshes/waffle_base.stl" scale="0.01 0.01 .0.01"/>语法解析:"package://cpp06_urdf/meshes/waffle_base.stl" scale="0.01 0.01 .0.01"也就是"package://所在功能包名/上级文件夹名/皮肤文件名" scale="x缩放比例 y缩放比例 z缩放比例"
(4)编译,配置环境变量
(5)启动
XML
ros2 launch cpp06_urdf display.launch.py model:=`ros2 pkg prefix --share cpp06_urdf`/urdf/urdf/demo03_link_mesh.urdf
#启动一个cpp06_urdf`/urdf/urdf/demo02_link.urdf 路径下的URDF机器人模型并在RViz中显示它
(6)rviz配置:
- Global Options 中的 Fixed Frame 设置为 base_link(和 urdf 文件中 link 标签的 name 一致);
- 添加机器人模型插件,并将参数 Description Topic 的值设置为 /robot_description,即可显示机器人模型。
(7)效果展示:

Robot的第二个子标签----joint
joint 标签用于描述机器人关节的运动学和动力学属性,还可以指定关节运动的安全极限,机器人的两个部件(分别称之为 parent link 与 child link)以"关节"的形式相连接,不同的关节有不同的运动形式: 旋转、滑动、固定、旋转速度、旋转角度限制....,比如:安装在底座上的轮子可以360度旋转,而摄像头则可能是完全固定在底座上。
属性:
-
name(必填):为关节命名,名称需要唯一。
-
type(必填):设置关节类型,可用类型如下:
-
continuous:旋转关节,可以绕单轴无限旋转。
-
revolute:旋转关节,类似于 continues,但是有旋转角度限制。
-
prismatic:滑动关节,沿某一轴线移动的关节,有位置极限。
-
planer:平面关节,允许在平面正交方向上平移或旋转。
-
floating:浮动关节,允许进行平移、旋转运动。
-
fixed:固定关节,不允许运动的特殊关节。
-
子标签
-
<parent>(必填):指定父级link。
- link(必填):父级link的名字,是这个link在机器人结构树中的名字。
-
<child>(必填):指定子级link。
- link(必填):子级link的名字,是这个link在机器人结构树中的名字。
-
<origin>(可选):这是从父link到子link的转换,关节位于子link的原点。
- xyz:各轴线上的偏移量。
- rpy:各轴线上的偏移弧度。
-
<axis>(可选):如不设置,默认值为(1,0,0)。
- xyz:用于设置围绕哪个关节轴运动。
-
<calibration>(可选):关节的参考位置,用于校准关节的绝对位置。
-
rising(可选):当关节向正方向移动时,该参考位置将触发上升沿。
-
falling(可选):当关节向正方向移动时,该参考位置将触发下降沿。
-
-
<dynamics>(可选):指定接头物理特性的元素。这些值用于指定关节的建模属性,对仿真较为有用。
-
damping(可选):关节的物理阻尼值,默认为0。
-
friction(可选):关节的物理静摩擦值,默认为0。
-
-
<limit>(关节类型是revolute或prismatic时为必须的):
-
lower(可选):指定关节下限的属性(旋转关节以弧度为单位,棱柱关节以米为单位)。如果关节是连续的,则省略。
-
upper(可选):指定关节上限的属性(旋转关节以弧度为单位,棱柱关节以米为单位)。如果关节是连续的,则省略。
-
effort(必填):指定关节可受力的最大值。
-
velocity(必填):用于设置最大关节速度(旋转关节以弧度每秒 [rad/s] 为单位,棱柱关节以米每秒 [m/s] 为单位)。
-
-
<mimic> (可选):此标签用于指定定义的关节模仿另一个现有关节。该关节的值可以计算为value = multiplier * other_joint_value + offset。
-
joint(必填):指定要模拟的关节的名称。
-
multiplier(可选):指定上述公式中的乘法因子。
-
offset(可选):指定要在上述公式中添加的偏移量,默认为 0(旋转关节的单位是弧度,棱柱关节的单位是米)。
-
-
<safety_controller>(可选):安全控制器。
-
soft_lower_limit(可选):指定安全控制器开始限制关节位置的下关节边界,此限制需要大于joint下限。
-
soft_upper_limit(可选):指定安全控制器开始限制关节位置的关节上边界的属性,此限制需要小于joint上限。
-
k_position(可选):指定位置和速度限制之间的关系。
-
k_velocity(必填):指定力和速度限制之间的关系。
-
案例二:创建机器人模型,底盘为长方体,在长方体的前面添加一摄像头,摄像头可以沿着 Z 轴 360 度旋转。
(1)功能包 cpp06_urdf 的 urdf/urdf 目录下,新建 urdf 文件 demo03_joint.urdf,并编辑文件,输入如下内容:
XML
<!--
需求:创建机器人模型,底盘为长方体,
在长方体的前面添加一摄像头,
摄像头可以沿着 Z 轴 360 度旋转
-->
<robot name="joint_demo">
<!-- 定义颜色 -->
<material name="yellow">
<color rgba="0.7 0.7 0 0.8" />
</material>
<material name="red">
<color rgba="0.8 0.1 0.1 0.8" />
</material>
<link name="base_link">
<visual>
<!-- 形状 -->
<geometry>
<box size="0.5 0.3 0.1" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="yellow"/>
</visual>
</link>
<!-- 摄像头 -->
<link name="camera">
<visual>
<geometry>
<box size="0.02 0.05 0.05" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="red" />
</visual>
</link>
<!-- 关节 -->
<joint name="camera2baselink" type="continuous">
<parent link="base_link"/>
<child link="camera" />
<!-- 需要计算两个 link 的物理中心之间的偏移量 -->
<origin xyz="0.2 0 0.075" rpy="0 0 0" />
<axis xyz="0 0 1" />
</joint>
</robot>
(2)编译,配置环境变量,终端运行,弹出rviz:
XML
ros2 launch cpp06_urdf display.launch.py model:=`ros2 pkg prefix --share cpp06_urdf`/urdf/urdf/demo03_joint.urdf
(3)配置rviz
(4)新建终端,执行如下命令,在该窗口中有一个"进度条",通过拖拽进度条可以控制相机旋转。ros2 run joint_state_publisher_gui joint_state_publisher_gui
(5)效果展示:

bug分析:
问题:
通过joint_state_publisher_gui关节运行到指定位置之后,关节在初始位置和指定位置之间抖动。
原因:
1.joint_state_publisher与joint_state_publisher_gui作用一致,都会发布非固定关节的运动信息。
2.robot_state_publisher会订阅关节的运动信息,并生成坐标变换数据广播。
3.joint_state_publisher或joint_state_publisher_gui有一个存在时,就会发布关节运动信息,进而就能生成坐标变换。
当两个都不启动时,坐标树生成不了,机器人模型显示异常。
当两个都存在时 joint_state_publisher一直发布初始关节位姿信息[joint_state_publist发布指定的关节位姿信息,最终,两个消息都要订阅,最终产生了抖动的效果。
解决:
不再启动joint_state_publisherr_gui节点进行调试旋转。使用joint_state_publisher进行控制
优化:使用base_footprint优化urdf
策略:
前面实现的机器人模型是半沉到地下的,因为默认情况下: 底盘的中心点位于地图原点上,所以会导致这种情况产生,可以使用的优化策略,将初始 link 设置为一个尺寸极小的 link(比如半径为 0.001m 的球体,或边长为 0.001m 的立方体),然后再在初始 link 上添加底盘等刚体,这样实现,虽然仍然存在初始link半沉的现象,但是基本可以忽略了,这个初始 link 一般称之为 base_footprint。

XML
<!--
需求:为机器人模型添加 base_footprint
-->
<robot name="base_footprint_demo">
<!-- 定义颜色 -->
<material name="yellow">
<color rgba="0.7 0.7 0 0.8" />
</material>
<material name="red">
<color rgba="0.8 0.1 0.1 0.8" />
</material>
<link name="base_footprint">
<visual>
<geometry>
<sphere radius="0.001"/>
</geometry>
</visual>
</link>
<link name="base_link">
<visual>
<!-- 形状 -->
<geometry>
<box size="0.5 0.3 0.1" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="yellow"/>
</visual>
</link>
<joint name="baselink2basefootprint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 0.05"/>
</joint>
<!-- 摄像头 -->
<link name="camera">
<visual>
<geometry>
<box size="0.02 0.05 0.05" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="red" />
</visual>
</link>
<!-- 关节 -->
<joint name="camera2baselink" type="fixed">
<parent link="base_link"/>
<child link="camera" />
<!-- 需要计算两个 link 的物理中心之间的偏移量 -->
<origin xyz="0.2 0 0.075" rpy="0 0 0" />
<axis xyz="0 0 1" />
</joint>
</robot>
运行demo后,在 rviz2 将Fixed Frame设置为base_footprint,机器人模型将正常显示在"地面"上。