Radar: Record of Practical Operations for Handheld Laser Radar Mapping Preparation
03 - 手持激光雷达建图实操记录
1. 概述
手持 TG30 激光雷达进行 Cartographer 建图测试,验证 SLAM 软件链路是否跑通。
与官方教程的区别:
| 项目 | 官方教程 | 我们的方案 |
|---|---|---|
| SLAM 算法 | Gmapping(粒子滤波) | Cartographer(图优化) |
| 里程计 | 有底盘 odom | 无 odom,纯激光匹配 |
| 雷达型号 | 4ROS(三角测距型) | TG30(TOF 飞行时间型) |
| 安装方式 | 编译源码 | apt 一键安装 |
| 启动方式 | ros2 launch slam_gmapping ... | ros2 launch yahboomcar_nav map_cartographer_test_launch.py |
官方教程使用 Gmapping,因 TG30 每圈 2020 点超过 Gmapping 的 1440 点上限,改用 Cartographer。
2. 前提条件
| 条件 | 状态 |
|---|---|
| ROS2 Humble 已安装 | 已确认 |
| YDLidar SDK 已安装 | 已确认(v1.0.6) |
| 雷达驱动已编译 | 已确认(ydlidar_ros2_driver) |
| 雷达串口已绑定 | 已确认(/dev/ydlidar -> ttyUSB0) |
| Cartographer 已安装 | sudo apt install -y ros-humble-cartographer ros-humble-cartographer-ros |
| Nav2 地图服务器已安装 | sudo apt install -y ros-humble-nav2-map-server |
| yahboomcar_nav 已编译 | 已确认(含自定义 launch 和配置) |
| LIDAR_TYPE 环境变量 | 已设置 export LIDAR_TYPE=4ros(写入 ~/.bashrc) |
3. 系统架构
3.1 数据流
TG30 雷达 → /scan(2020点/圈,10Hz) ↓ Cartographer(纯激光匹配,无 odom) ↓ /map(栅格地图) → RViz 可视化 与有底盘的正式建图不同,手持模式下 Cartographer 配置了 use_odometry = false,完全靠前后两帧激光的扫描匹配来推算位移。3.2 节点通讯
/ydlidar_ros2_driver_node ──→ /scan ──→ /cartographer_node ──→ /map ↓ /submap_list /scan_matched_points2 /trajectory_node_list /constraint_list /static_tf_footprint_to_base ──→ /tf_static(base_footprint → base_link) /static_tf_base_to_laser ──→ /tf_static(base_link → laser) /cartographer_node ──→ /tf(map → odom → base_link,由 Cartographer 自动生成) /cartographer_occupancy_grid_node ←── /submap_list ──→ /map 实际运行的节点列表:
| 节点 | 作用 |
|---|---|
/ydlidar_ros2_driver_node | 雷达驱动,发布 /scan |
/cartographer_node | SLAM 建图核心 |
/occupancy_grid_node | 将子图转换为栅格地图发布到 /map |
/static_tf_base_to_laser | 发布 base_link → laser 静态变换 |
/static_tf_footprint_to_base | 发布 base_footprint → base_link 静态变换 |
/rviz | 可视化 |
3.3 TF 坐标链
map → odom → base_link → laser ↑ ↑ ↑ ↑ └──────┘ │ │ Cartographer 静态TF 静态TF 自动生成 z=0.0815 x=0.0435 z=0.11 yaw=π 对比官方教程的 TF 树(map → odom → laser → base_link),我们的坐标链更符合 REP-105 标准:base_link 是机器人本体,laser 作为传感器挂在 base_link 下面。4. 启动步骤
4.1 启动建图
# 确保没有残留的雷达进程pkill-f ydlidar 2>/dev/null pkill-f cartographer 2>/dev/null sleep2# 启动建图(一条命令启动所有节点)source ~/ydlidar_ws/install/setup.bash ros2 launch yahboomcar_nav map_cartographer_test_launch.py 启动成功的标志性日志:
[ydlidar_ros2_driver_node] LiDAR successfully connected [ydlidar_ros2_driver_node] [YDLIDAR]:Lidar running correctly ! The health status: good [ydlidar_ros2_driver_node] Model: TG30 [ydlidar_ros2_driver_node] [YDLIDAR] Fixed Size: 2020 [ydlidar_ros2_driver_node] [YDLIDAR INFO] Now YDLIDAR is scanning ...... [cartographer_node] All sensor data for trajectory 0 is available [cartographer_node] Inserted submap (0, 0). 常见问题:如果雷达报cannot retrieve YDLidar health code,说明串口被之前的进程占用。先pkill -f ydlidar,等 2 秒再启动。
4.2 打开 RViz 可视化
在另一个终端中:
rviz2 RViz 配置步骤:
- 设置 Fixed Frame:左侧 Displays → Global Options → Fixed Frame 改为
map - 添加地图显示:
- 点左下角 Add → 选择 By topic 标签页
- 找到
/map→ 展开 → 选 Map → 点 OK
- 添加激光扫描显示:
- 再点 Add → By topic 标签页
- 找到
/scan→ 展开 → 选 LaserScan → 点 OK
- 调整 LaserScan 显示参数(参考官方教程 RViz 设置):
- Topic:
/scan - Style:
Flat Squares - Size:
0.05(官方用 0.1,但 TG30 点更密可以用更小值)
- Topic:
- 调整视角:滚轮缩放,中键拖动平移
4.3 手持雷达扫描环境
雷达必须保持水平:
水平拿(正确): 激光扫描面 ─────────────── 扫到墙壁、家具轮廓 桌子 椅子 门 歪着拿(错误): 激光扫描面 ╲ ╲─────────── 扫到天花板/地板边缘 地图出现虚假障碍物 TG30 是 2D 激光雷达,只发射一个水平面的扫描线。倾斜会导致:
- 地图出现不存在的障碍物(实际是地面或天花板)
- 墙壁距离测量不准
- 帧间匹配失败,地图扭曲
手持建图操作要点:
| 要点 | 说明 |
|---|---|
| 保持水平 | 小幅晃动(< 5°)可接受,持续倾斜不行 |
| 移动要慢 | 每秒不超过 0.3m,给 Cartographer 足够时间做帧间匹配 |
| 转弯要慢 | 角速度不能太快,否则相邻帧差异太大匹配失败 |
| 路径要有重叠 | 走过的区域要有重叠覆盖,方便特征匹配 |
| 走闭环 | 走一圈回到起点,触发回环检测,地图会自动校正 |
建议:把雷达放在平板(书、硬纸板)上端着走,更容易保持水平。
4.4 保存地图
建图满意后,不要关闭建图终端,在新终端中执行:
source ~/ydlidar_ws/install/setup.bash ros2 launch yahboomcar_nav save_map_launch.py 保存的文件:
~/ydlidar_ws/src/yahboomcar_nav/maps/ ├── yahboomcar.pgm # 栅格地图图片(灰度图) └── yahboomcar.yaml # 地图元数据 地图 YAML 文件格式:
image: yahboomcar.pgm mode: trinary resolution:0.05# 分辨率:0.05 米/像素origin:[-5.95,-3.26,0]# 地图左下角坐标 (x, y, yaw)negate:0occupied_thresh:0.65# 占用概率 > 0.65 → 障碍物(黑色)free_thresh:0.25# 占用概率 < 0.25 → 自由空间(白色)灰色区域为未探索区域。
4.5 重新建图
如果对当前地图不满意,想从零开始重建:
# 第一步:杀掉当前建图进程pkill-f cartographer pkill-f ydlidar pkill-f occupancy_grid # 第二步:等串口释放sleep2# 第三步:重新启动(全新地图,不会叠加上一次数据)source ~/ydlidar_ws/install/setup.bash ros2 launch yahboomcar_nav map_cartographer_test_launch.py RViz 不用关,重启后地图会自动清空。每次启动 Cartographer 都是全新建图。
4.6 停止建图
# 方法1:在启动建图的终端按 Ctrl+C# 方法2:命令行杀进程pkill-f cartographer pkill-f ydlidar pkill-f occupancy_grid 5. 核心配置文件
5.1 Cartographer 配置(无 odom 手持模式)
文件:~/ydlidar_ws/src/yahboomcar_nav/params/tg30_2d_no_odom.lua
-- 关键参数 options ={ tracking_frame ="base_link",-- 无 odom,直接跟踪 base_link published_frame ="base_link", provide_odom_frame =true,-- Cartographer 自行生成 odom frame use_odometry =false,-- 不使用里程计}-- TG30 雷达参数(手持调优版) TRAJECTORY_BUILDER_2D.min_range =0.1 TRAJECTORY_BUILDER_2D.max_range =8.0-- 缩小到 8m,减少远距离噪声干扰匹配 TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching =true-- 扫描匹配搜索窗口(关键!无 odom 时加大搜索范围防止匹配丢失) TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window =0.15 TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(30.) TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight =1e-1 TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight =1e-1-- Ceres 精细匹配 TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight =10. TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight =40.-- 运动滤波:更频繁地接受扫描帧 TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters =0.1 TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.3) TRAJECTORY_BUILDER_2D.motion_filter.max_time_seconds =3.-- 无 odom 模式下的特殊调整 TRAJECTORY_BUILDER_2D.submaps.num_range_data =30-- 更小的子图,减少单个子图内漂移 POSE_GRAPH.optimize_every_n_nodes =15-- 每 15 个节点就优化一次 POSE_GRAPH.constraint_builder.min_score =0.55-- 放宽匹配阈值调优说明:首次测试使用max_range=12、submaps.num_range_data=40时地图严重拉伸变形。
调优后将max_range缩小到 8m 减少噪声,加大扫描匹配搜索窗口(angular_search_window=30°)防止转弯丢失,
缩小子图帧数到 30、全局优化频率提高到每 15 个节点,地图质量显著改善。
5.2 Launch 文件
文件:~/ydlidar_ws/src/yahboomcar_nav/launch/map_cartographer_test_launch.py
启动内容:
| 序号 | 组件 | 说明 |
|---|---|---|
| 1 | 4ros_ydlidar_launch.py | 雷达驱动 |
| 2 | static_transform_publisher | base_link → laser(x=0.0435, z=0.11, yaw=π) |
| 3 | static_transform_publisher | base_footprint → base_link(z=0.0815) |
| 4 | cartographer_node | SLAM 建图(使用 tg30_2d_no_odom.lua) |
| 5 | cartographer_occupancy_grid_node | 栅格地图发布(分辨率 0.05m) |
6. 排错指南
6.1 雷达启动失败
报错 1:cannot retrieve YDLidar health code: ffffffff
原因:串口被之前的进程占用
解决:
pkill-f ydlidar sleep2# 重新启动报错 2:cannot bind to the specified serial port[/dev/ydlidar]
原因:上一轮进程未完全释放串口,或 /dev/ydlidar 设备消失
解决:
# 先确认设备是否存在ls-la /dev/ydlidar # 如果设备不存在,物理重新插拔雷达 USB 线# 插拔后等 udev 规则生效,再检查ls-la /dev/ydlidar # 应显示:/dev/ydlidar -> ttyUSB06.2 启动时出现 RTPS_TRANSPORT_SHM 警告
[RTPS_TRANSPORT_SHM Error] Failed init_port fastrtps_port7429: open_and_lock_file failed 结论:无害警告,不影响任何功能。是 DDS 共享内存传输的非关键错误,可忽略。
6.3 RViz 启动时出现 Stereo NOT SUPPORTED
[rviz2]: Stereo is NOT SUPPORTED 结论:无害提示,显卡不支持立体显示,不影响 2D 地图可视化。
6.4 tf2_echo 崩溃(BrokenPipeError)
报错:ros2 crashed with BrokenPipeError in run_executable()
原因:系统提示 ros-humble-ros2cli 等包版本过旧
解决(可选):
sudoapt update &&sudoapt upgrade -y此崩溃只影响 ros2 run tf2_ros tf2_echo 等调试命令,不影响建图功能。6.5 RViz 中看不到地图
检查清单:
- Fixed Frame 是否设为
map? - 是否添加了 Map 显示(topic:
/map)? - 检查话题是否有数据:
ros2 topic echo /map --once - 检查 TF 是否正常:
ros2 run tf2_ros tf2_echo map base_link - RViz 视角是否合适?建议使用 TopDownOrtho(俯视图)查看地图
6.6 地图扭曲或飘移
原因:移动过快、雷达倾斜、或特征不足的空旷区域
解决:
- 降低移动速度
- 保持雷达水平
- 尽量在有特征(墙角、家具)的区域建图
- 走闭环让 Cartographer 触发回环校正
- 如果地图严重变形,直接重新建图(见 4.5 节)
6.7 查看节点通讯和 TF 树
# 查看节点通讯图(需要安装 rqt) ros2 run rqt_graph rqt_graph # 查看 TF 树(生成 frames.pdf) ros2 run tf2_tools view_frames 7. 手持建图的局限性
| 局限 | 说明 |
|---|---|
| 精度较低 | 没有里程计,纯靠激光匹配,累积误差较大 |
| 对操作要求高 | 必须慢、稳、水平,否则地图质量差 |
| 不适合大场景 | 无 odom 的漂移在大空间中会更明显 |
| 仅供测试验证 | 正式地图需等底盘到了以后用有 odom 的模式重建 |
本次手持建图的目的:验证 Cartographer 软件链路跑通,熟悉建图操作流程,为底盘到后正式建图做准备。
8. 底盘到了以后的变化
底盘到后,切换到正式建图模式:
# 使用有 odom 的配置和 launch ros2 launch yahboomcar_nav map_cartographer_tg30_launch.py
| 项目 | 手持模式(当前) | 正式模式(底盘到后) |
|---|---|---|
| 配置文件 | tg30_2d_no_odom.lua | tg30_2d.lua |
| Launch 文件 | map_cartographer_test_launch.py | map_cartographer_tg30_launch.py |
| 里程计 | 无 | 底盘编码器 + EKF |
| tracking_frame | base_link | base_footprint |
| use_odometry | false | true |
| provide_odom_frame | true | false |
| 建图精度 | 低 | 高 |
| 操作方式 | 手持慢走 | 遥控/自动巡逻 |
9. 实测踩坑记录
9.1 occupancy_grid_node 可执行文件名不对
现象:启动 launch 时报 executable 'occupancy_grid_node' not found on the libexec directory
原因:ros-humble-cartographer-ros 中的可执行文件实际名为 cartographer_occupancy_grid_node,而非源码 launch 中写的 occupancy_grid_node
修复:在所有 launch 文件中将 executable='occupancy_grid_node' 改为 executable='cartographer_occupancy_grid_node'
已修复的文件:
map_cartographer_test_launch.pymap_cartographer_tg30_launch.pyoccupancy_grid_launch.py
9.2 首次建图地图严重拉伸变形
现象:手持走了一圈,地图呈窄长条形,与实际房间结构完全不符
原因:初始配置参数不适合无 odom 手持场景
max_range = 12.0过大,远距离噪声干扰扫描匹配- 扫描匹配搜索窗口使用默认值,转弯时容易丢失
- 子图帧数过多(40),单个子图内漂移积累
解决:调优 tg30_2d_no_odom.lua(详见第 5.1 节),核心改动:
max_range从 12 缩到 8- 显式设置
angular_search_window = 30° submaps.num_range_data从 40 降到 30optimize_every_n_nodes从 20 降到 15- 增加 Ceres 精细匹配权重
效果:调优后重新建图,地图质量显著改善,能清晰看到房间结构、墙壁和门口轮廓
9.3 串口占用导致雷达无法启动
现象:第二次启动时雷达报 cannot bind to the specified serial port 或 cannot retrieve YDLidar health code
原因:上一轮进程未完全退出,仍占用 /dev/ttyUSB0
解决:启动前必须先确保旧进程全部杀干净,等待 2 秒让串口释放
pkill-f ydlidar &&pkill-f cartographer &&sleep2极端情况下需要物理重新插拔 USB