cartographer内置评估工具使用流程:评估前端优化的误差
目的:评估前端(本地slam)优化参数是否合理,如偏差较大,则调整响应参数。
以下是使用 Cartographer 内置工具评估 SLAM 前端效果的完整流程整理,结合参数解析和实际应用建议:
1. 生成优化轨迹(开启后端)与未优化轨迹
目标
通过对比优化后的轨迹(optimized.pbstream
,含后端闭环)和未优化的前端轨迹(test.pbstream
),量化前端算法的精度。
步骤
-
录制建图数据包
rosbag record -O mapping.bag -a # 根据实际传感器话题调整
-
生成优化轨迹(开启后端)
roslaunch cartographer_ros offline_backpack_2d.launch bag_filenames:=${BAG_PATH}
- 关键参数:在
bacpack_2d.lua
中确保POSE_GRAPH.optimize_every_n_nodes
设置为非零值(如30
),以启用后端优化。 ${BAG_PATH}
需要使用绝对路径:可以适当简化$(pwd)/XX.bag
- 默认生成的pbstream文件,同名bag名,因此需要手动修改
XX.pbstream
->optimized.pbstream
- 关键参数:在
-
生成未优化轨迹(仅前端)
-
修改
bacpack_2d.lua
中的参数:POSE_GRAPH.optimize_every_n_nodes = 0 //关闭后端优化
-
重新运行轨迹生成的命令生成
test.pbstream
。
-
2. 提取伪真实值关系
指令
cartographer_autogenerate_ground_truth \-pose_graph_filename optimized.pbstream \-output_filename relations.pbstream \-min_covered_distance 10 \-outlier_threshold_meters 0.15 \-outlier_threshold_radians 0.02
参数解析
min_covered_distance
:仅选择移动超过 10米 的相邻节点作为候选约束,避免短距离噪声干扰。outlier_threshold_meters/radians
:过滤异常约束的阈值(平移>0.15米或旋转>0.02弧度),确保伪真实值的可靠性。- 原理:优化后的轨迹通过闭环检测修正了累计误差,其节点间关系可作为局部“真实值”参考。
3. 评估前端误差
指令
cartographer_compute_relations_metrics \-relations_filename relations.pbstream \-pose_graph_filename test.pbstream
输出示例与解读
Abs translational error 0.01944 +/- 0.01819 m
Sqr translational error 0.00071 +/- 0.00189 m^2
Abs rotational error 0.11197 +/- 0.12432 deg
Sqr rotational error 0.02799 +/- 0.07604 deg^2
- 平移误差:平均 1.94厘米,标准差 1.82厘米,说明前端定位在厘米级精度。
- 旋转误差:平均 0.11度,标准差 0.12度,表明方向估计较稳定。
- 误差来源:前端扫描匹配(如
ceres_scan_matcher
参数)、传感器噪声或运动畸变补偿不足。
4. 前端优化建议
根据误差结果调整前端参数(需修改 trajectory_builder_2d.lua
):
-
扫描匹配权重
TRAJECTORY_BUILDER_2D.ceres_scan_matcher = {translation_weight = 10, -- 若平移误差大,可增加至15rotation_weight = 80, -- 若旋转误差大,可降低至60 }
-
运动滤波阈值
TRAJECTORY_BUILDER_2D.motion_filter = {max_distance_meters = 0.03, -- 更小值提高更新频率,但增加计算量max_angle_radians = math.rad(0.5), }
-
IMU融合参数
TRAJECTORY_BUILDER_2D.use_imu_data = true -- 确保IMU数据用于旋转估计 TRAJECTORY_BUILDER_2D.imu_gravity_time_constant = 1.0 -- 动态场景可调至0.5
-
实时相关匹配
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher = {linear_search_window = 0.2, -- 特征稀疏环境可扩大至0.3angular_search_window = math.rad(40.), }
5. 可视化验证
-
RViz对比轨迹
roslaunch cartographer_ros visualize_pbstream.launch pbstream_filename:=$(pwd)/optimized.pbstream roslaunch cartographer_ros visualize_pbstream.launch pbstream_filename:=test.pbstream
- 观察未优化轨迹(红色)与优化轨迹(绿色)的偏离程度。
-
子图质量检查
- 检查
test.pbstream
中子图的边缘对齐和细节清晰度,模糊或错位可能需调整submaps.num_range_data
(如从20
增至30
)。
- 检查
注意事项
- 数据一致性:确保
optimized.pbstream
和test.pbstream
来自同一环境下的相同传感器数据。 - 参数迭代:每次调整后需重新生成轨迹并评估,建议使用脚本自动化流程。
- 硬件限制:高频率更新(如
motion_filter.max_distance_meters=0.03
)可能需更高性能计算单元支持。
通过上述流程,可系统性地量化前端性能并针对性优化,提升 Cartographer 在建图阶段的精度与鲁棒性。