Radar: Record of Practical Operations for Handheld Laser Radar Mapping Preparation

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_nodeSLAM 建图核心
/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 配置步骤:

  1. 设置 Fixed Frame:左侧 Displays → Global Options → Fixed Frame 改为 map
  2. 添加地图显示
    • 点左下角 Add → 选择 By topic 标签页
    • 找到 /map → 展开 → 选 Map → 点 OK
  3. 添加激光扫描显示
    • 再点 AddBy topic 标签页
    • 找到 /scan → 展开 → 选 LaserScan → 点 OK
  4. 调整 LaserScan 显示参数(参考官方教程 RViz 设置):
    • Topic: /scan
    • Style: Flat Squares
    • Size: 0.05(官方用 0.1,但 TG30 点更密可以用更小值)
  5. 调整视角:滚轮缩放,中键拖动平移

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=12submaps.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

启动内容:

序号组件说明
14ros_ydlidar_launch.py雷达驱动
2static_transform_publisherbase_link → laser(x=0.0435, z=0.11, yaw=π)
3static_transform_publisherbase_footprint → base_link(z=0.0815)
4cartographer_nodeSLAM 建图(使用 tg30_2d_no_odom.lua
5cartographer_occupancy_grid_node栅格地图发布(分辨率 0.05m)

6. 排错指南

6.1 雷达启动失败

报错 1cannot retrieve YDLidar health code: ffffffff

原因:串口被之前的进程占用

解决

pkill-f ydlidar sleep2# 重新启动

报错 2cannot bind to the specified serial port[/dev/ydlidar]

原因:上一轮进程未完全释放串口,或 /dev/ydlidar 设备消失

解决

# 先确认设备是否存在ls-la /dev/ydlidar # 如果设备不存在,物理重新插拔雷达 USB 线# 插拔后等 udev 规则生效,再检查ls-la /dev/ydlidar # 应显示:/dev/ydlidar -> ttyUSB0

6.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 中看不到地图

检查清单

  1. Fixed Frame 是否设为 map
  2. 是否添加了 Map 显示(topic: /map)?
  3. 检查话题是否有数据:ros2 topic echo /map --once
  4. 检查 TF 是否正常:ros2 run tf2_ros tf2_echo map base_link
  5. 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.luatg30_2d.lua
Launch 文件map_cartographer_test_launch.pymap_cartographer_tg30_launch.py
里程计底盘编码器 + EKF
tracking_framebase_linkbase_footprint
use_odometryfalsetrue
provide_odom_frametruefalse
建图精度
操作方式手持慢走遥控/自动巡逻

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.py
  • map_cartographer_tg30_launch.py
  • occupancy_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 降到 30
  • optimize_every_n_nodes 从 20 降到 15
  • 增加 Ceres 精细匹配权重

效果:调优后重新建图,地图质量显著改善,能清晰看到房间结构、墙壁和门口轮廓

9.3 串口占用导致雷达无法启动

现象:第二次启动时雷达报 cannot bind to the specified serial portcannot retrieve YDLidar health code

原因:上一轮进程未完全退出,仍占用 /dev/ttyUSB0

解决:启动前必须先确保旧进程全部杀干净,等待 2 秒让串口释放

pkill-f ydlidar &&pkill-f cartographer &&sleep2

极端情况下需要物理重新插拔 USB

Read more

OpenClaw配置飞书机器人完整指南

OpenClaw配置飞书机器人完整指南 使用openclaw channels add配置飞书机器人需完成插件安装→飞书应用创建→通道配置→事件订阅→发布应用五个核心步骤,以下是可直接执行的详细流程。 文章目录 * OpenClaw配置飞书机器人完整指南 * 一、前置准备 * 二、通道配置(openclaw channels add) * 方法1:交互式向导配置(推荐) * 方法2:非交互式命令配置(适合脚本) * 方法3:手动编辑配置文件 * 三、事件订阅与发布(关键步骤) * 四、测试与验证 * 五、常见问题排查 一、前置准备 1. 飞书开放平台创建应用(获取凭证) 1. 访问飞书开放平台:https://open.feishu.cn/app 2. 创建企业自建应用,填写名称(如"

OpenClaw重塑机器人抓取未来

OpenClaw:重新定义机器人抓取的未来之手 在人工智能席卷全球的今天,当我们惊叹于ChatGPT流畅的对话、Midjourney惊艳的创作时,物理世界的智能化却显得步履蹒跚。机器人仍然笨拙地挣扎于最简单的任务:拿起一个鸡蛋、整理杂乱的桌面、或者分拣形状各异的物品。 这个困境的核心,在于机器人缺少一双灵巧而通用的"手"。而一个名为OpenClaw(又称Clawbot)的开源项目,正在以革命性的方式改变这一现状。 一、抓取技术的困境与突破 传统机器人抓取面临三大难题: 刚性的局限 工业机器人依赖专用夹具,每个新物件都需要重新设计和调试。这种刚性系统无法适应现代生产的小批量、多品种需求,更难以进入家庭、医院等非结构化环境。 成本的壁垒 先进的柔性抓手价格高达数千美元,将中小企业、科研机构和创客群体拒之门外,严重制约了机器人技术的普及和创新。 智能的断层 虽然机器视觉能识别数百万种物体,但执行端的匮乏让这种智能无法转化为实际行动。感知与操作的脱节,成为机器人发展的关键瓶颈。 OpenClaw的巧妙之处在于,它用极其简单的机械结构解决了这些复杂问题。 二、极简设计的智慧

Flutter 三方库 arcane_helper_utils 的鸿蒙化适配指南 - 实现具备通用逻辑增强与多维开发脚手架的实用工具集、支持端侧业务开发的效率倍增实战

Flutter 三方库 arcane_helper_utils 的鸿蒙化适配指南 - 实现具备通用逻辑增强与多维开发脚手架的实用工具集、支持端侧业务开发的效率倍增实战

欢迎加入开源鸿蒙跨平台社区:https://openharmonycrossplatform.ZEEKLOG.net Flutter 三方库 arcane_helper_utils 的鸿蒙化适配指南 - 实现具备通用逻辑增强与多维开发脚手架的实用工具集、支持端侧业务开发的效率倍增实战 前言 在进行 Flutter for OpenHarmony 开发时,如何快速处理常见的字符串格式化、色值转换、日期计算或布尔值增强?虽然每一个功能都很小,但如果每个项目都重复造轮子,开发效率将大打折扣。arcane_helper_utils 是一款专注于极致实用的“瑞士军刀”型工具集。本文将探讨如何在鸿蒙端通过这类高内聚的 Utility 集实现极致、丝滑的业务交付。 一、原直观解析 / 概念介绍 1.1 基础原理 该库通过对 Dart 原生类型(Object, String, List, Map, Bool)