PL-SLAM — Points and Lines
- Description:PL-SLAM 论文笔记 — 基于 ORB-SLAM 的点+线特征单目 SLAM,线特征重投影误差、点线联合 BA、仅靠线特征的地图初始化 (3 帧小旋转假设)
- Paper:Pumarola, A., Vakhitov, A., Agudo, A., Sanfeliu, A., & Moreno-Noguer, F. (2017). PL-SLAM: Real-Time Monocular Visual SLAM with Points and Lines. ICRA.
- K2E-B ID:[K2E-B-L2-2]
- Max3 PDF:
[K2E] SLAM/[K2E-B-L] Localization/[K2E-B-L2] Line Features/[K2E-B-L2-2][2017] PL-SLAM Real-Time Monocular Visual SLAM with Points and Lines.pdf - Notion ID:(待创建)
- Created:2023-08-16
- Updated:2026-06-02
- License:转载欢迎 — 请署名 Yu Zhang 并链回 yuzhang.io 原文
Table of Contents
1. 概述与动机
PL-SLAM (Pumarola et al. 2017) — 在 ORB-SLAM 基础上加入线特征 (line features),提升低纹理 (low-textured) 场景性能而不牺牲效率。
为何要线特征:
- 特征点在运动模糊 / 低纹理时消失 (point features vanish out)
- 人造场景 (man-made) 富含直线
线特征的难点:
- 线检测器和参数化复杂
- 线位姿不如点可靠,对部分遮挡敏感
贡献:能处理点消失的情况;能只用 3 个连续帧的线特征初始化 (小旋转假设)。
线特征参数化 (Plücker 等) + 点线 SLAM 概览见 SLAM 学习资源 L 系列;点特征基础见 特征描述子。本笔记是 PL-SLAM 这篇论文的方法笔记。
2. 系统框架
基于 ORB-SLAM 三线程 (见 ORB-SLAM2 那篇),线特征处理:
- 检测 — LSD (Line Segment Detector)
- 匹配 — LBD (Line Band Descriptor) 局部外观 + 几何约束的关系图策略;得到 map-to-image 线对,投影到图像继续找匹配
- 关键帧 — 新信息足够则标记关键帧 → 线三角化
- 剔除 (culling) — < 3 视角,或 < 25% 预期可见帧
- 回环检测 — 只用特征点 (线特征不参与回环,全局线匹配太贵)
- 重定位 — 用 EPnPL (含线特征) 替换 ORB-SLAM 的 EPnP,最小化检测线重投影误差
- 优化 — local BA (点+线)
3. 线特征重投影误差
(基于文献 Vakhitov 的线参数化)
3D 线段端点 $P, Q$;图像上检测线段端点 $p_d, q_d$,齐次 $p_d^h, q_d^h$。图像线 (归一化法向量):
$$ \mathbf{l} = \frac{p_d^h \times q_d^h}{|p_d^h \times q_d^h|} $$
线重投影误差 = 点到线距离之和。投影端点 $P, Q$ 到图像,求到图像线 $\mathbf{l}$ 的距离:
$$ E_{\text{line}}(P, Q, \mathbf{l}, \theta, K) = E_{pl}^2(P, \mathbf{l}, \theta, K) + E_{pl}^2(Q, \mathbf{l}, \theta, K) $$
$$ E_{pl}(P, \mathbf{l}, \theta, K) = \mathbf{l}^T \pi(P, \theta, K) $$
($K$ 内参,$\theta = {R, t}$ 位姿,$\pi$ 投影方程)
考虑遮挡 → 实际用检测线重投影误差 (不直接用 $\pi$ 投影端点,而是用检测到的端点):
$$ E_{pl,d} = \mathbf{l}^T p_d $$
因为线遮挡/误检,检测端点 $p_d, q_d$ 往往不能和 $P, Q$ 匹配,所以分开定义。优化时对 $E_{line,d}$ 做递归,逼近 $E_{line}$。
4. 点线联合 BA
点到线误差向量 (BA 核心):
$$ e_{i,j}' = (\tilde{\mathbf{l}}{i,j})^T (K^{-1} p{i,j}^h), \quad e_{i,j}'' = (\tilde{\mathbf{l}}{i,j})^T (K^{-1} q{i,j}^h) $$
总代价 (点误差 + 线两端点误差,鲁棒核 $\rho$):
$$ C = \sum_{i,j} \rho\left( e_{i,j}^T \Omega_{i,j}^{-1} e_{i,j} + e_{i,j}'^T \Omega_{i,j}'^{-1} e_{i,j}' + e_{i,j}''^T \Omega_{i,j}''^{-1} e_{i,j}'' \right) $$
(点重投影 $e$ + 线两端 $e', e''$,各带协方差矩阵 $\Omega$ (公式中 $\Omega^{-1}$ 为信息矩阵);鲁棒核见 RANSAC 与鲁棒估计 §5)
全局重定位
和 ORB-SLAM 差不多,主要换成 EPnPL (EPnP + Line) 最小化检测线重投影误差。(EPnP 见 PnP §4)
5. 仅靠线特征的地图初始化
5 条线匹配即可。假设 3 连续帧 + 小旋转:
$R_1 = R^T, R_2 = I, R_3 = R$ (中间帧为参考,恒定小旋转)。利用 $\mathbf{l}_i$ 垂直于 $OPQ$ 平面的约束:
$$ \mathbf{l}_2^T ((R^T \mathbf{l}_1) \times (R \mathbf{l}_3)) = 0 $$
$R$ 是小量 → 只有 3 个变量。用 polynomial solver + trifocal tensor 方程求解 (假设 $t_2 = 0$),得 8 个解,取使误差最小的。所需最少线匹配 = 5。
6. 实验与结论
- TUM RGB-D 数据集
- 比较 ORB-SLAM / PTAM / LSD-SLAM / RGBD-SLAM,Absolute KeyFrame Trajectory RMSE
- 结论:低纹理场景受益于线特征;未来想结合平面特征,统一在类似特征点的框架里
References
- Pumarola, A., Vakhitov, A., Agudo, A., Sanfeliu, A., & Moreno-Noguer, F. (2017). PL-SLAM: Real-Time Monocular Visual SLAM with Points and Lines. ICRA. — 论文
- Mur-Artal, R., et al. (2015). ORB-SLAM. IEEE T-RO. — 基础框架 (见 ORB-SLAM2 那篇)
- Vakhitov, A., et al. (2016). Accurate and Linear Time Pose Estimation from Points and Lines (EPnPL). ECCV.
- Grompone von Gioi, R., et al. (2010). LSD: A Fast Line Segment Detector. IEEE T-PAMI.
- Zhang, L., & Koch, R. (2013). An Efficient and Robust Line Segment Matching (LBD). JVCIR.
- 点线 SLAM 相关 (PL-VIO/PL-VINS) 见 K2E-B-L2 Line Features 系列;BA 鲁棒核见 RANSAC 与鲁棒估计;EPnP 见 PnP