0. 架构概述
本笔记记录在 ROS2 Humble 仿真环境中,实现无需预建地图、基于 EKF 定位 + Nav2 导航的完整搭建过程。最终效果:在 Rviz 中点击目标点,Turtlebot3 自动规划路径并避障到达。
整体数据流:
/odom + /imu → robot_localization (EKF) → map→odom TF
/scan → Nav2 costmap → 路径规划 → /cmd_vel → 底盘运动1. 安装依赖
1.1 安装 Turtlebot3
sudo apt install -y ros-humble-turtlebot3 \
ros-humble-turtlebot3-simulations \
ros-humble-turtlebot3-gazebo设置机器人型号,加入 ~/.bashrc 永久生效
echo 'export TURTLEBOT3_MODEL=waffle' >> ~/.bashrc
source ~/.bashrc1.2 安装 robot_localization
sudo apt install -y ros-humble-robot-localization1.3 安装 Nav2
sudo apt install -y ros-humble-navigation2 ros-humble-nav2-bringup1.4 验证仿真环境
启动仿真,确认四个核心话题存在:
ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py另开终端验证话题
ros2 topic list | grep -E 'scan|odom|cmd_vel|imu'应看到: /cmd_vel /imu /odom /scan
2. 创建工程目录
mkdir -p ~/carplaning/nav_ws/src/campus_nav/config
mkdir -p ~/carplaning/nav_ws/src/campus_nav/launch3. 配置 EKF(robot_localization)
EKF 节点负责融合轮式里程计和 IMU,输出稳定的 map→odom TF。
3.1 编写 ekf.yaml
创建文件 ~/carplaning/nav_ws/src/campus_nav/config/ekf.yaml,内容如下:
ekf_filter_node:
ros__parameters:
use_sim_time: true # 必须与仿真时钟同步
frequency: 30.0
sensor_timeout: 0.1
two_d_mode: true # 地面机器人用 2D 模式
publish_tf: true
map_frame: map
odom_frame: odom
base_link_frame: base_footprint # Turtlebot3 用 base_footprint
world_frame: map # 关键:设为 map 才会发布 map→odom TF
odom0: /odom
odom0_config: [false, false, false,
false, false, false,
true, true, false, # 融合 vx vy
false, false, true, # 融合 yaw 速率
false, false, false]
odom0_differential: false
imu0: /imu
imu0_config: [false, false, false,
false, false, false,
false, false, false,
false, false, true, # 融合 yaw 速率
true, false, false] # 融合线加速度
imu0_differential: false
imu0_remove_gravitational_acceleration: true注意:world_frame 必须设为 map,否则 EKF 只发布 odom→base_footprint,不会发布 map 帧,Nav2 会一直报 transform not available。
3.2 启动 EKF 节点
ros2 run robot_localization ekf_node --ros-args \
--params-file ~/carplaning/nav_ws/src/campus_nav/config/ekf.yaml \
-p use_sim_time:=true3.3 验证 TF 树
ros2 run tf2_tools view_frames查看输出,应有:
map → odom → base_footprint → base_link常见坑:不加 use_sim_time:=true 启动 EKF,会出现大量 TF_OLD_DATA 警告,原因是 EKF 用系统时钟但 Gazebo 已经跑了几百秒,时间对不上。
4. 配置 Nav2
4.1 复制默认参数文件
cp /opt/ros/humble/share/nav2_bringup/params/nav2_params.yaml \
~/carplaning/nav_ws/src/campus_nav/config/nav2_params.yaml4.2 修改 global_costmap(无图模式)
默认配置依赖预建地图(static_layer),无图模式需要两处修改:
① 去掉 static_layer
找到 global_costmap 的 plugins 行(约第 237 行),改为:
修改前
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]修改后(去掉 static_layer)
plugins: ["obstacle_layer", "inflation_layer"]一行命令修改:
sed -i '237s/plugins: \["static_layer", "obstacle_layer", "inflation_layer"\]/plugins: ["obstacle_layer", "inflation_layer"]/' \
~/carplaning/nav_ws/src/campus_nav/config/nav2_params.yaml② 开启 rolling_window
在 global_costmap 的 resolution 行下方添加 rolling_window 配置,使地图随机器人滚动:
sed -i 's/ track_unknown_space: true/ rolling_window: true\n width: 20\n height: 20\n track_unknown_space: true/' \
~/carplaning/nav_ws/src/campus_nav/config/nav2_params.yaml常见坑:不开 rolling_window 的话,global_costmap 固定在初始位置(0,0到5,5),机器人稍微走远一点就会报 Robot is out of bounds of the costmap。
4.3 验证修改
确认 static_layer 已移除
grep -n 'static_layer\|rolling_window\|plugins:' \
~/carplaning/nav_ws/src/campus_nav/config/nav2_params.yaml | head -105. 启动完整系统
每次启动需要开 3 个终端,顺序如下:
终端 1:启动 Gazebo 仿真
ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py等待 Gazebo 完全加载(看到小车出现在场景中)再开后续终端
终端 2:启动 EKF 定位
ros2 run robot_localization ekf_node --ros-args \
--params-file ~/carplaning/nav_ws/src/campus_nav/config/ekf.yaml \
-p use_sim_time:=true终端 3:启动 Nav2
ros2 launch nav2_bringup navigation_launch.py \
use_sim_time:=true \
params_file:=$HOME/carplaning/nav_ws/src/campus_nav/config/nav2_params.yaml等待看到:Managed nodes are active
终端 4:启动 Rviz
ros2 launch nav2_bringup rviz_launch.py use_sim_time:=true6. 发送导航目标
1. Rviz 打开后,等待激光扫描红点出现(代表 /scan 数据正常)
2. 点击顶部工具栏的「Nav2 Goal」按钮
3. 在地图上点击一个目标位置并拖动设置朝向,松开鼠标
4. Gazebo 中小车开始自动导航,遇到障碍物会自动绕行
成功标志:Nav2 日志最后一行显示 Managed nodes are active,且 /cmd_vel 话题有速度指令输出。
7. 常见问题排错
| 报错信息 | 解决方法 |
|---|---|
| TF_OLD_DATA ignoring data from the past | EKF 启动时未加 use_sim_time:=true,重启 EKF 节点时加上该参数 |
| map frame does not exist | EKF 的 world_frame 设置为 odom 而非 map,修改 ekf.yaml 后重启 |
| Robot is out of bounds of the costmap | global_costmap 未开启 rolling_window,按第 4.2 节添加三行配置 |
| Not enough features / imageProjection crash | 点云缺少 ring 或 time 字段(LIO-SAM 问题),本方案不使用 LIO-SAM 不会出现 |
| Timed out waiting for transform base_link to map | Nav2 启动比 EKF 早,正常现象,等 EKF 就绪后警告自动消失 |
