机器人的URDF建模及其Gazebo仿真(unfinished)
零、这一节你会学到什么
在这一节里,你要从零开始,亲手写一个差速驱动机器人的 URDF 模型文件,在 Gazebo 仿真器中把它"造"出来,用键盘遥控它满地跑,最后再给它装上激光雷达和相机——让它不仅能动,还能"看见"周围的世界。
🗺️ 迷宫挑战:代码包里藏着一个 maze.sdf 迷宫世界。给机器人装上激光雷达,试着只靠 RViz2 里的激光点云,用键盘遥控走出迷宫。提示:看 /scan 话题,找最近的墙壁在哪个方向~
学习路径: 认识差速驱动 → 学 URDF 基础 → 写 URDF 文件 → 在 Gazebo 里跑起来 → 装传感器
前置知识: 你已完成 01~05 课,理解 ROS2 的话题(Topic)通信和节点(Node)概念。
一、认识差速驱动机器人
1.1 什么是差速驱动
你见过超市的购物车轮子吗?前面的两个小轮子可以自由转向,但不能自己转——它们只是"万向轮",跟着车身走。真正提供动力的,是后面两个不会转向但能自己转的驱动轮。
差速驱动机器人也是这个原理:
- 两个独立的驱动轮——左边一个,右边一个,各自能正转、反转
- 一个或两个万向轮——不提供动力,只是支撑车身不翻倒
怎么转弯? 靠左右轮的速度差:
其中 是机器人前进速度, 是旋转角速度, 是左右轮的间距。
- 左右轮同速正转 → 直走
- 左轮慢、右轮快 → 左转
- 左轮正转、右轮反转 → 原地旋转(坦克掉头!)
非完整约束:差速机器人不能横着走——就像汽车不能侧方平移一样。这不是 bug,是物理规律。
1.2 我们要建的机器人长什么样
这个机器人叫 mbot,结构很简单:
- 🟡 一个黄色圆柱底盘(半径 20cm,高 16cm)
- ⚫ 两个黑色圆柱驱动轮(左右各一个,半径 6cm)
- ⚫ 前后两个小球体万向轮(半径 1.5cm)
- 📡 可以选装激光雷达、RGB 相机或深度相机(三选一)
它通过 ROS2 的 /cmd_vel 话题接收速度指令,Gazebo 里的 DiffDrive 插件会自动把指令翻译成左右轮的转速。
1.3 为什么不直接用现成的机器人模型
网上有 TurtleBot4 的现成 URDF 文件,复制粘贴就能用。但我们不这么做,因为:
- ✍️ 亲手写一遍,你才知道每个
<link>、<joint>、<inertial>标签是什么意思 - 🔧 以后你想改造机器人(换大轮子?加传感器?),改自己的文件随手就来
- 📐 ROS2 世界里,URDF 是描述机器人的"通用语言"——Nav2 导航、MoveIt2 抓取、RViz2 可视化,全都靠它
二、准备 Gazebo 仿真环境
2.1 安装 ros_gz
Gazebo 是一个独立的机器人仿真器。要让 ROS2 和 Gazebo 对话,需要一座"桥梁"——ros_gz 包。
# 一行命令安装(会自动带上 Gazebo Ionic)
sudo apt install ros-kilted-ros-gz
说明:ROS2 Kilted 的官方仿真配对是 Gazebo Ionic。
ros-kilted-ros-gz会自动安装正确版本,不需要额外配置。
验证安装:
gz sim --versions
应该输出类似 Gazebo Sim, version 9.x.x 的信息。
2.2 冒烟测试
装好了,先跑一个空世界看看 Gazebo 能不能正常启动:
ros2 launch ros_gz_sim gz_sim.launch.py gz_args:="empty.sdf"
看到 Gazebo 窗口打开,里面是一片灰色的地面,就成功了 ✅
再打开一个新终端,检查话题是否正常:
ros2 topic list
你应该看到 /clock 和 /stats 话题——这说明 ROS2 和 Gazebo 已经连上了。
gz sim: command not found → ros_gz 没装好,回到 2.1 重装。
GUI 不显示 → 可能是 X11/Wayland 问题。试试 export QT_QPA_PLATFORM=xcb。
话题看不到 → 检查是否 source 了 ROS2 环境:source /opt/ros/kilted/setup.bash
三、URDF 建模基础
3.1 URDF 是什么
URDF(Unified Robot Description Format)是一种 XML 格式的文件,用来描述机器人长什么样、关节怎么动、有多重。Gazebo、RViz2、MoveIt2……几乎所有 ROS2 工具都靠 URDF 来"认识"你的机器人。
一个 URDF 文件的核心就两种标签:<link>(刚体) 和 <joint>(关节)。
3.2 Link:刚体的三要素
每个 <link> 描述机器人的一个"零件"(底盘、轮子、传感器支架……),它身上有三个关键属性:
| 标签 | 作用 | 缺了会怎样 |
|---|---|---|
<visual> | 长什么样(几何体 + 颜色) | Gazebo 里看不到这个零件 |
<collision> | 碰撞检测的边界 | 机器人会穿墙而过 🧱 |
<inertial> | 质量和惯性张量 | 物理引擎无法计算运动,Gazebo 会报错 |
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.16" radius="0.20"/>
</geometry>
<material name="yellow"/>
</visual>
<collision>
<geometry>
<cylinder length="0.16" radius="0.20"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.02"/>
</inertial>
</link>
3.3 Joint:连接两个 Link 的关节
<joint> 把两个 link 连起来,并且定义它们之间的运动关系:
| 关节类型 | 含义 | 我们的机器人里用在 |
|---|---|---|
fixed | 焊死的,不能动 | 把万向轮固定在底盘上 |
continuous | 可以无限旋转 | 驱动轮(正转反转随便转) |
每个 joint 都有三个关键属性:
<parent>/<child>:谁连着谁(父子关系)<origin>:关节装在 parent 的哪个位置(xyz 偏移 + rpy 朝向)<axis>:绕着哪个轴旋转(xyz="0 1 0"表示绕 Y 轴转)
<joint name="left_wheel_joint" type="continuous">
<origin xyz="0 0.19 -0.05" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="left_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>
这段代码的意思是:在底盘(base_link)的左侧 0.19m、下方 0.05m 处,装一个可以绕 Y 轴无限旋转的左轮。
3.4 惯性参数怎么填
<inertial> 里的 <inertia> 填的是惯性张量——你可以把它理解为"旋转运动中的质量"。数值越大,这个零件越"抗拒"被转动。
对于简单几何体,有现成公式:
- 实心圆柱绕 Z 轴:
- 实心球:
我们的代码里已经把公式写成了 xacro 宏(macro)——你只需要传入质量和尺寸,宏会自动算出惯性张量。后面会看到。
四、亲自动手:写差速机器人的 URDF
现在我们来拆解 mbot_base_gazebo_ionic.xacro——这就是机器人的"身体"定义文件。
4.1 整体结构——父子关系树
先看大局。机器人所有零件形成一棵树:
base_footprint 是机器人在地面上的投影点。ROS2 导航时,所有坐标都以它为参考。它通过
fixed关节焊在 base_link 上——永远在底盘正下方。
4.2 底盘建模(base_link)
底盘是一个黄色圆柱体,高 16cm,半径 20cm。看代码:
<link name="base_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.16" radius="0.20"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.16" radius="0.20"/>
</geometry>
<material name="yellow"/>
</visual>
<xacro:cylinder_inertial_matrix m="1" r="0.20" h="0.16"/>
</link>
注意:<visual> 和 <collision> 的几何体需要一模一样——不然 Gazebo 看到的外观和物理碰撞边界对不上,会出现"看起来撞上了但实际穿过去了"的诡异现象。
cylinder_inertial_matrix 是我们自己写的 xacro 宏,自动算惯性张量:
<xacro:macro name="cylinder_inertial_matrix" params="m r h">
<inertial>
<mass value="${m}"/>
<inertia ixx="${m*(3*r*r+h*h)/12}" ixy="0" ixz="0"
iyy="${m*(3*r*r+h*h)/12}" iyz="0"
izz="${m*r*r/2}"/>
</inertial>
</xacro:macro>
4.3 驱动轮建模
两个驱动轮用 continuous 关节——可以一直转,不限角度。
<xacro:macro name="wheel" params="prefix reflect">
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="0 ${reflect*0.19} ${-0.05}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>
<link name="${prefix}_wheel_link">
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
<geometry>
<cylinder radius="0.06" length="0.025"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
<geometry>
<cylinder radius="0.06" length="0.025"/>
</geometry>
<material name="gray"/>
</visual>
<xacro:cylinder_inertial_matrix m="0.2" r="0.06" h="0.025"/>
</link>
</xacro:macro>
几个值得注意的细节:
prefix参数:wheel宏被调用了两次——<xacro:wheel prefix="left" reflect="1"/>和<xacro:wheel prefix="right" reflect="-1"/>。一次定义,左右复用。rpy="${M_PI/2} 0 0":Gazebo 里的圆柱体默认是竖着的(轴线沿 Z)。轮子需要横着装(轴线沿 Y),所以要绕 X 轴旋转 90°(π/2)。reflect控制 y 方向偏移的正负号:左轮在 +y(reflect=1),右轮在 -y(reflect=-1)。
4.4 万向轮建模
万向轮不提供动力,只是支撑,所以用 fixed 关节——焊死在底盘上。
<xacro:macro name="caster" params="prefix reflect">
<joint name="${prefix}_caster_joint" type="fixed">
<origin xyz="${reflect*0.18} 0 ${-(0.16/2 + 0.015)}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_caster_link"/>
</joint>
<link name="${prefix}_caster_link">
<collision>
<geometry>
<sphere radius="0.015"/>
</geometry>
</collision>
<visual>
<geometry>
<sphere radius="0.015"/>
</geometry>
<material name="black"/>
</visual>
<xacro:sphere_inertial_matrix m="0.2" r="0.015"/>
</link>
</xacro:macro>
万向轮是球体,半径只有 1.5cm——因为它只是"撑着",不需要太大。
4.5 DiffDrive 插件:让轮子听懂 /cmd_vel
有了 link 和 joint,Gazebo 知道机器人长什么样、关节怎么动——但还不知道谁来驱动这些关节。
DiffDrive 插件就是干这个的:
<gazebo>
<plugin filename="libgz-sim-diff-drive-system.so"
name="gz::sim::systems::DiffDrive">
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>0.38</wheel_separation>
<wheel_radius>0.06</wheel_radius>
<topic>cmd_vel</topic>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>true</publish_wheel_tf>
<odometry_topic>odom</odometry_topic>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_footprint</robot_base_frame>
</plugin>
</gazebo>
它的工作流程:
收到 /cmd_vel (v, ω)
→ DiffDrive 插件算左右轮各自需要的转速
→ 驱动 left_wheel_joint / right_wheel_joint 旋转
→ 同时发布 /odom(里程计)告诉你机器人走了多远
关键参数:
| 参数 | 值 | 含义 |
|---|---|---|
wheel_separation | 0.38m | 左右轮间距(= 0.19 × 2) |
wheel_radius | 0.06m | 轮子半径 |
topic | cmd_vel | 订阅的话题名(ROS2 端发 /cmd_vel 就行) |
4.6 完整代码在哪里
在你的 workspace 里找到这个文件:
~/guyuhome_ws/src/ros2_21_tutorials/learning_gazebo_ionic/urdf/mbot_base_gazebo_ionic.xacro
用 VSCode 打开,对照上面的讲解读一遍。你会在文件末尾看到除了 DiffDrive 插件之外,还有几个辅助插件:
- Sensors 插件 → 让传感器能工作
- UserCommands 插件 → 让你能在 Gazebo 里用快捷键
- SceneBroadcaster 插件 → 把 Gazebo 场景状态发给 ROS2
- JointStatePublisher 插件 → 发布关节状态到
/joint_states - OdometryPublisher 插件 → 发布里程计到
/odom
这些不用深究——你知道 Gazebo 自动帮你做了这些事就够了。
五、在 Gazebo 中跑起来
5.1 代码包里有什么
先了解你手上的武器库。learning_gazebo_ionic 包里准备了:
learning_gazebo_ionic/
├── launch/
│ ├── load_urdf_into_gazebo_ionic.launch.py # 基础版:空世界跑 base 机器人
│ ├── load_mbot_lidar_into_gazebo_ionic.launch.py # LiDAR 版:空世界 + 激光雷达
│ ├── load_mbot_lidar_into_maze_gazebo_ionic.launch.py # LiDAR 迷宫版
│ ├── load_mbot_camera_into_gazebo_ionic.launch.py # 相机版
│ ├── load_mbot_rgbd_into_gazebo_ionic.launch.py # 深度相机版
│ └── load_mbot_rgbd_into_maze_gazebo_ionic.launch.py # 深度相机迷宫版
├── urdf/
│ ├── mbot_base_gazebo_ionic.xacro # 底盘定义(上一节刚学过!)
│ ├── mbot_gazebo_ionic.xacro # 基础版(只用底盘)
│ ├── mbot_with_lidar_gazebo_ionic.xacro # + 激光雷达
│ ├── mbot_with_camera_gazebo_ionic.xacro # + RGB 相机
│ ├── mbot_with_rgbd_gazebo_ionic.xacro # + 深度相机
│ └── sensors/ # 传感器定义
├── worlds/
│ ├── empty.sdf # 空世界(一片平地)
│ ├── maze.sdf # 迷宫世界(练习遥控的好地方)
│ └── depot.sdf # 仓库世界
└── config/
├── ros_gz_bridge_mbot.yaml # 基础桥接
├── ros_gz_bridge_mbot_lidar.yaml # + LiDAR 桥接
├── ros_gz_bridge_mbot_camera.yaml # + 相机桥接
└── ros_gz_bridge_mbot_rgbd.yaml # + RGBD 桥接
5.2 启动你的机器人
先确保 workspace 已编译:
cd ~/guyuhome_ws
colcon build --packages-select learning_gazebo_ionic
source install/setup.bash
最简启动——基础版机器人在空世界里:
ros2 launch learning_gazebo_ionic load_urdf_into_gazebo_ionic.launch.py
这条命令背后做了四件事:
- 🚀 启动 Gazebo,加载
empty.sdf空世界 - 🤖 把
mbot_gazebo_ionic.xacro转成 URDF,spawn 到 Gazebo 里 - 🌉 启动
ros_gz_bridge,桥接 ROS2 ↔ Gazebo 的话题 - 📐 启动
robot_state_publisher,持续发布机器人的 TF 坐标变换
打开新终端,看看有哪些话题:
ros2 topic list
你应该看到 /cmd_vel、/odom、/clock、/joint_states、/tf、/tf_static。
5.3 键盘遥控
现在让机器人动起来:
ros2 run teleop_twist_keyboard teleop_twist_keyboard
按键说明:
| 按键 | 动作 |
|---|---|
I | 前进 ↑ |
, | 后退 ↓ |
J | 左转 ↺ |
L | 右转 ↻ |
U | 左前 |
O | 右前 |
M | 左后 |
. | 右后 |
K | 停止 ✋ |
按 I 键,Gazebo 窗口里的机器人应该开始向前移动了!🎉
再开一个终端:
ros2 topic echo /cmd_vel
然后按键盘的 I 键,你会看到:
linear:
x: 0.5
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 0.0
这就是 DiffDrive 插件收到的指令——告诉机器人"以 0.5 m/s 直线前进"。
再看看机器人发布的里程计:
ros2 topic echo /odom
六、给机器人装上传感器
机器人能动了,但它还是个"瞎子"——不知道周围有什么。现在给它装上眼睛。
6.1 激光雷达(LiDAR)
激光雷达发射数百条射线,测量每条射线碰到障碍物后反射回来的时间,算出障碍物的距离和方向。我们用的 gpu_lidar 配置:
- 🔄 360 个采样点,覆盖 360°(全方位扫描)
- 📏 测距范围 0.08m ~ 10m
- ⏱️ 更新频率 20Hz(每秒扫 20 圈)
ros2 launch learning_gazebo_ionic load_mbot_lidar_into_gazebo_ionic.launch.py
启动 RViz2 来看激光数据:
rviz2
在 RViz2 里:
- 把 Fixed Frame 设为
base_footprint - 点击 Add → By topic → 选择
/scan→ LaserScan - 你会看到机器人周围出现一圈红色点云——这就是激光雷达看到的障碍物!
核心传感器代码在 urdf/sensors/lidar_gazebo_ionic.xacro,关键的 SDF 配置:
<sensor type="gpu_lidar" name="gpu_lidar">
<topic>lidar</topic>
<update_rate>20</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-3.14</min_angle>
<max_angle>3.14</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<alwaysOn>1</alwaysOn>
<visualize>true</visualize>
<gz_frame_id>laser_link</gz_frame_id>
</sensor>
Gazebo 里发的话题叫
/lidar,但ros_gz_bridge把它桥接成了 ROS2 标准的/scan(sensor_msgs/msg/LaserScan格式)。这就是为什么在 RViz2 里你选的是/scan而不是/lidar。
6.2 RGB 相机
一个普通的 USB 相机,装在机器人前方:
- 📷 分辨率 640×480
- 🎨 色彩格式 R8G8B8
- ⏱️ 帧率 10Hz
ros2 launch learning_gazebo_ionic load_mbot_camera_into_gazebo_ionic.launch.py
查看相机画面:
ros2 run rqt_image_view rqt_image_view
在 rqt_image_view 的下拉菜单里选择 /camera 话题,你就能看到机器人在 Gazebo 世界里"看到"的画面。
6.3 深度相机(RGBD)
深度相机同时输出 RGB 彩色图像 + 深度图(每个像素除了颜色,还有一个"距离"值):
ros2 launch learning_gazebo_ionic load_mbot_rgbd_into_gazebo_ionic.launch.py
深度相机装在机器人前方(x=0.15m, z=0.11m),和 RGB 相机位置略有不同。
6.4 🗺️ 迷宫挑战
把激光雷达和迷宫世界组合起来——这是最有意思的部分:
ros2 launch learning_gazebo_ionic load_mbot_lidar_into_maze_gazebo_ionic.launch.py
打开 RViz2,加载 /scan 激光点云,然后用键盘遥控:
- 👀 观察 RViz2 里的激光点云——红色点就是墙壁
- 🧭 找到离你最近的墙在哪个方向
- 🕹️ 用
J/L转弯,I前进——但别撞墙!
Gazebo 里也可以直接看激光线:在 Gazebo 窗口右上角点击三个点 → 勾选 "Laser" 或 "Visualize Laser",你就能看到从机器人发出的红线。
七、小结与验证清单
你已经从头到尾完成了一个完整的仿真机器人项目。对照这个清单:
| 你会了 | 怎么验证 |
|---|---|
| 差速驱动原理 | 能说出左右轮速度差如何产生转向( 和 公式) |
| URDF 建模 | 认得 <link>(三要素)、<joint>(fixed vs continuous)、<inertial> |
| Gazebo 启动 | ros2 launch 后 Gazebo 窗口正常出现 |
| 键盘遥控 | teleop_twist_keyboard 能让机器人动起来 |
| 激光雷达 | RViz2 里能看到 /scan 的红色激光点云 |
| RGB 相机 | rqt_image_view 里能看到机器人视角 |
你写的 URDF 文件、跑的 launch 命令、看的传感器数据——这些都是真机开发中每天都在用的技能。唯一的区别是:真机上你面对的是真实的硬件而不是 Gazebo——但 ROS2 的话题、消息、TF 坐标变换,一模一样。
八、参考资料
- 📦 learning_gazebo_ionic 包源码:
~/guyuhome_ws/src/ros2_21_tutorials/learning_gazebo_ionic/——本节所有代码都在这里 - 🔗 ros_gz GitHub:https://github.com/gazebosim/ros_gz
- 📖 Gazebo Ionic 文档:https://gazebosim.org/docs/ionic
- 📐 URDF 官方教程:https://docs.ros.org/en/kilted/Tutorials/Intermediate/URDF/URDF-Main.html