ROS 2 Humble + Gazebo 搭建无人机仿真场景实战:从空旷起降场到 ROS2 话题桥接
适用范围
这篇文章默认你已经准备好了下面这套环境:
Ubuntu 22.04ROS 2 Humble- 可用的 Gazebo /
ros_gz
如果你还没有装环境,可以先看我前面两篇文章:
这篇文章不重复写环境安装,而是直接进入无人机场景本身的搭建。
这次搭的是什么场景
这次我搭的是一个“空旷起降场 + 本地四旋翼模型 + ROS 2 桥接接口”的无人机仿真场景,目标不是 PX4 那种飞控级高保真链路,而是先把一个适合算法开发、调试和演示的标准 ROS 2 仿真环境跑起来。
最终这个场景包含:
- 一个空旷起降场 world
- 一个本地四旋翼模型
IMU、GPS、前视相机、里程计ROS 2 <-> Gazebo桥接- 一个基础起飞演示脚本
这样做的好处是很直接:后面你想接自己的控制节点、视觉节点、定位节点,都可以直接基于这套结构往下扩展。
工作区结构
这次我把整个仿真场景放在一个独立工作区 ~/uav_sim_ws 里,目录结构如下:
uav_sim_ws/
├── src/
│ └── uav_open_field_sim/
│ ├── config/
│ │ └── bridge.yaml
│ ├── launch/
│ │ └── open_field_uav.launch.py
│ ├── models/
│ │ └── quadrotor/
│ │ ├── model.config
│ │ └── model.sdf
│ ├── rviz/
│ │ └── uav_open_field.rviz
│ ├── scripts/
│ │ └── takeoff_demo.py
│ ├── test/
│ ├── worlds/
│ │ └── open_field.sdf
│ ├── CMakeLists.txt
│ └── package.xml
└── README.md
我把它拆成这个结构,主要是为了把“场景资源”“桥接配置”“启动逻辑”“演示脚本”分开。后面你想换 world、换传感器或者换控制入口时,不会全堆在一个文件里。
核心文件说明
下面这几个文件是整个场景能跑起来的关键。
worlds/open_field.sdf
这个文件定义空旷起降场本身,包括:
- 地面
- 光照
- Gazebo 物理系统
- 传感器系统
- 起降标记和少量静态参照物
它的职责很单纯,就是提供一个稳定、简单、便于观察的场景底座。
models/quadrotor/model.sdf
这个文件定义无人机模型本身。里面除了机体、旋翼、惯性参数和关节,还挂了 Gazebo 的多旋翼控制插件和电机模型插件。
同时我在这个模型里挂了几类基础传感器:
IMUNavSat- 前视
Camera
它是整个仿真场景里最核心的文件。
config/bridge.yaml
这个文件负责整理桥接目标,也就是把哪些 Gazebo 话题映射到 ROS 2,哪些 ROS 2 控制命令转回 Gazebo。
我这次主要桥了这些接口:
/uav/cmd_vel/uav/enable/uav/imu/uav/navsat/uav/camera/image_raw/uav/odometry
这样你后面用 ROS 2 工具查看数据会很直接。
launch/open_field_uav.launch.py
这是整个场景的一键启动入口。它负责:
- 启动 Gazebo
- 加载
open_field.sdf - 生成四旋翼模型
- 启动
ros_gz_bridge - 按参数决定是否启动 RViz
正常情况下,你日常最常用的就是这个 launch 文件。
scripts/takeoff_demo.py
这个脚本不是必须的,但非常适合验证整个场景是不是已经真正打通。
它会往 /uav/enable 和 /uav/cmd_vel 发一组简单命令,让无人机先上升,再进入悬停附近状态。
如果这个脚本能跑通,通常就说明“模型、控制入口、桥接、运行环境”这几层已经基本通了。
实际搭建和运行步骤
如果你只是想把这个场景快速跑起来,可以直接照下面这套流程做。
1. 获取项目
我已经把这次场景整理成了一个独立仓库:
git clone https://github.com/goodniceqingwa/uav_sim_ws.git
cd uav_sim_ws
2. 安装依赖
如果你的机器已经装好了 ROS 2 Humble,但还没补齐 Gazebo 和桥接相关包,可以先装这一组:
sudo apt install -y \
ros-humble-ros-gz \
ros-humble-ros-gz-sim \
ros-humble-ros-gz-bridge \
ros-humble-ros-gz-image \
ros-humble-gps-msgs
3. 构建工作区
cd ~/uav_sim_ws
source /opt/ros/humble/setup.bash
colcon build --symlink-install
source install/setup.bash
如果 colcon build 这一步都过不了,不要急着继续 launch,先把构建问题解决掉。
4. 启动仿真场景
最直接的启动方式:
cd ~/uav_sim_ws
source /opt/ros/humble/setup.bash
source install/setup.bash
ros2 launch uav_open_field_sim open_field_uav.launch.py use_rviz:=false
如果你想一起打开 RViz:
ros2 launch uav_open_field_sim open_field_uav.launch.py use_rviz:=true
5. 运行基础起飞演示
另开一个终端,执行:
cd ~/uav_sim_ws
source /opt/ros/humble/setup.bash
source install/setup.bash
ros2 run uav_open_field_sim takeoff_demo.py
这个脚本会发一组最基础的起飞 / 悬停控制命令,适合确认场景是不是已经真正打通。
6. 检查 ROS 2 话题
如果 launch 成功,你至少应该能看到这些话题:
ros2 topic list | rg '^/uav/|^/clock$'
我这次场景里主要关注的是:
/clock/uav/cmd_vel/uav/enable/uav/imu/uav/navsat/uav/camera/image_raw/uav/odometry
如果你想进一步确认某个数据流是不是活的,可以直接查看:
ros2 topic echo /uav/imu --once
ros2 topic echo /uav/navsat --once
ros2 topic echo /uav/odometry --once
启动后你应该看到什么
如果一切正常,启动后通常会看到这些结果:
- Gazebo 打开一个空旷场地
- 原点附近生成一架四旋翼
create节点退出,但 Gazebo 和parameter_bridge保持运行- ROS 2 侧可以看到
/uav/...话题
这时候你就可以继续往下接自己的 ROS 2 节点了,比如控制节点、视觉节点或者定位节点。
这次真实踩到的几个坑
这次场景不是一次就跑通的,下面这几个问题都是真实出现过的。
1. Link quadrotor/base_link could not be found
我一开始在多旋翼控制插件里把 comLinkName、jointName、linkName 写成了带模型名前缀的形式,比如:
quadrotor/base_link
quadrotor/rotor_0_joint
但这个模型是通过 ros_gz_sim create -file 动态生成的,本质上更适合按模型内局部引用去写。
改成 base_link、rotor_0_joint 这类局部名称之后,这个错误就消失了。
2. allocation matrix rank is 3
这个问题更隐蔽一点。Gazebo 没有直接告诉你“哪个旋翼写错了”,只会报:
allocation matrix rank is 3
它的本质是四旋翼的旋向配置退化了,导致控制分配矩阵不满秩。
我最后回到模型文件里逐个检查:
turningDirection- 控制器里的
direction
把 4 个旋翼改成交替方向之后,控制器才能正常初始化。
3. ros2 run 提示 No executable found
我最开始虽然把 takeoff_demo.py 安装进了包里,但脚本本身没有执行权限,所以:
ros2 run uav_open_field_sim takeoff_demo.py
会直接报:
No executable found
这个问题最后不是改 launch,也不是改 Python 代码,而是给脚本补执行权限,并重新构建工作区。
别人怎么复用这个场景
现在这个场景已经整理到公开仓库里:
https://github.com/goodniceqingwa/uav_sim_ws
别人最短可以这样复现:
git clone https://github.com/goodniceqingwa/uav_sim_ws.git
cd uav_sim_ws
source /opt/ros/humble/setup.bash
colcon build --symlink-install
source install/setup.bash
ros2 launch uav_open_field_sim open_field_uav.launch.py use_rviz:=false
如果只想确认控制链路,再开第二个终端执行:
source /opt/ros/humble/setup.bash
source ~/uav_sim_ws/install/setup.bash
ros2 run uav_open_field_sim takeoff_demo.py
结语
这次场景搭建对我来说最有价值的一点,不是“把 Gazebo 打开了”,而是把一套可持续扩展的结构整理出来了。
到这里为止,这个工作区已经可以作为后续无人机算法开发的一个基础底座:
- 你可以继续加传感器
- 可以把空旷场地换成更复杂的场景
- 可以接自己的 ROS 2 控制节点
- 也可以继续往 PX4 / 更高保真链路扩展
如果你当前只需要一个“先跑起来、后面能继续改”的 ROS 2 无人机场景,这套结构已经够用了。