DSO — Direct Sparse Odometry


  • Description:DSO 论文与系统详解 — 直接稀疏里程计,光度误差 + 稀疏点的滑窗光度 BA、无匹配点的数据关联、光度标定、未成熟点与 trace、FEJ、关键帧与点选择策略、雅可比三分解
  • Paper:Engel, J., Koltun, V., & Cremers, D. (2018). Direct Sparse Odometry. IEEE T-PAMI, 40(3). (arXiv:1607.02565, 2016)
  • K2E-B ID:[K2E-B-S15-1]
  • Max3 PDF[K2E] SLAM/[K2E-B-S] SLAM Systems/[K2E-B-S15] DSO/[K2E-B-S15-1][2016] Direct Sparse Odometry.pdf (同目录另有 S15-2~5: Stereo/Rolling-Shutter/VI/Omnidirectional DSO)
  • Notion ID:(待创建)
  • Created:2023-04-10
  • Updated:2026-06-02
  • License转载欢迎 — 请署名 Yu Zhang 并链回 yuzhang.io 原文

Table of Contents


1. DSO 概述

DSO (Direct Sparse Odometry) — Engel, Koltun, Cremers 2016/2018 (TUM + Intel:Engel/Cremers @ TUM,Koltun @ Intel Labs)。直接法视觉里程计的成熟之作,精度与鲁棒性优于 ORB-SLAM2 (高翔实测),远比 LSD-SLAM 成熟。

核心:把 VO 表述成稀疏点上的光度误差滑窗 BA — 不提特征不匹配,直接用像素灰度。

本笔记整理自高翔 (半闲居士) 的 DSO 详解 + 任乾 DSO 源码解读 (见 References)。直接法/光流的灰度不变假设见 光流;FEJ/可观性见 VIO 系列 ch03

2. 直接法的数据关联

DSO 甚至没有"匹配点"概念。每个 3D 点从某个主导帧 (host frame) 出发,乘深度后投影到目标帧 (target frame),建立一个投影残差 (residual)。只要残差在合理范围,就认为是同一个点投影的。

  • 没有 a1-b1, a2-b2 这样的一对一关系
  • 可能 a1-b1, a2-b1, a3-b1 (多个投到一个)
  • DSO 不在意,残差不大就当同一点

这是直接法的关键 — 用整体光度一致性代替显式特征匹配。

3. 光度标定与光度参数

DSO 提出光度标定 (photometric calibration) — 对相机的曝光时间、暗角 (vignetting)、伽马响应等参数标定后,直接法更鲁棒。

未做光度标定的相机,DSO 为每帧估计一对仿射光度参数 $(a_i, b_i)$;host 帧 $i$ → target 帧 $j$ 的亮度传递为:

$$ I_j(x) = e^{a_j - a_i},\big(I_i(x) - b_i\big) + b_j $$

(即残差中以 $(a_i,b_i)$、$(a_j,b_j)$ 成对出现;代码里的 affLL[0]affLL[1] 是由两帧参数 (并含曝光比 $t_j/t_i$) 导出的相对系数affLL[0] 乘性作用于 host 灰度、affLL[1] 为加性偏移,非单帧的 $e^{a}$)

每个关键帧状态 = 6 自由度位姿 + 2 个光度参数 $(a, b)$ = 8 维

梯度依赖权重 (gradient-dependent weighting):

$$ w_p = \frac{c^2}{c^2 + |\nabla I_i(p)|^2} $$

4. 框架与代码结构

DSO 代码四部分:

  • src/FullSystem — 系统与各算法集成
  • src/OptimizationBackend — 后端优化
  • src/utils + src/IOWrapper — 去畸变 / 数据集读写 / 可视化

(前两者是核心)

每帧存于 FrameHessian (带状态变量 + Hessian 信息)。每帧携带地图点信息:

  • pointHessians — 活跃点 (在视野内、残差仍参与优化)
  • pointHessiansMarginalized — 已边缘化地图点
  • pointHessiansOut — 判为外点的地图点
  • immaturePoints — 未成熟地图点

整体行为

  • 非关键帧 — 仅计算位姿,并用该帧更新每个未成熟点的深度估计
  • 后端 (关键帧) — 增加新残差项、去除错误残差项、提取新未成熟点

5. 滑窗光度 BA

DSO 后端 = 若干关键帧的滑动窗口上的非线性最小二乘 (光度 BA)。

  • 每关键帧状态:6 DOF 位姿 + 2 光度参数 = 8 维
  • 每地图点状态:1 维 — 在主导帧的逆深度
  • 每个残差项 (能量项 $E$) 关联两个关键帧 + 一个逆深度 (host → target 投影)
  • 还有一个全局相机内参也参与优化

后端维护优化结构:GN/LM 的 Hessian 矩阵 + b 向量 (含先验部分)。

(逆深度参数化见 三角化 D4;滑窗 BA 见 VIO 系列 ch03)

6. 点选择与未成熟点

候选点选择 (Step 1)

  • well-distributed (分布均匀)
  • 高图像梯度幅值:图像分 32×32 block,取 median absolute gradient + 全局常数为阈值;弱纹理区用 block-size 2d/4d 重复

候选点跟踪 (Step 2) — trace

随相机运动,DSO 在每张图上追踪未成熟点 — 称为 trace,沿极线搜索 (类似 SVO 的 depth filter),最小化光度误差。确定每个 immature point 的逆深度 + 变化范围。

(灵感来自 LSD-SLAM 的极线搜索)

候选点激活 (Step 3)

  • 把所有活跃点投影到关键帧
  • 取到已有点最大距离的候选 (保持稀疏均匀)

外点与遮挡

  • 极线搜索不 distinct 的点丢弃
  • 光度误差大的观测丢弃

7. 关键帧边缘化策略

DSO 的关键帧边缘化 (Keyframe Marginalization Strategy):

  • 总保留最新两个关键帧 $I_1, I_2$
  • 可见点比例 < 5% 的帧 (points_visible(I) to I_1 < 5%) 边缘化
  • 帧数 $> N_f$ 时,按距离分数选边缘化对象:

$$ s(I_i) = \sqrt{d(i,1)} \sum_{j \in [3,n], j \neq i} (d(i,j) + \epsilon)^{-1} $$

(保留时间/空间分散的关键帧,边缘化冗余的)

边缘化用 Schur 补 (见 边缘化 那篇)。

8. 雅可比与 FEJ

DSO 的雅可比三部分:

  • 图像雅可比 — 图像梯度
  • 几何雅可比 — 各量对几何量 (旋转/平移) 的变化率
  • 光度雅可比 — 各量对光度参数的雅可比

关键技巧:几何和光度雅可比对自变量通常是光滑函数,图像雅可比依赖图像数据不光滑。所以:

  • 几何 + 光度雅可比 仅在线性化点算一次后固定,只重算依赖图像数据的那部分 (残差 + 图像梯度) → 是一种光滑雅可比近似,省计算
  • 图像雅可比随迭代更新

注意:这个“冻结光滑雅可比”的技巧 不等于 FEJ。DSO 里的 FEJ (First Estimate Jacobian) 专指对已线性化/待边缘化的残差固定其线性化点 (evalPT,isLinearized 门控),用于保证边缘化后的一致性 — 而活跃 (未线性化) 残差的雅可比在每次 GN 迭代仍按当前状态重算。

FEJ 的作用 (也用于 VIO,见 VIO 系列 ch03 §7):减小计算量、防止优化往错误方向走太多、边缘化时保证零空间维度不降低 (维持可观性一致)。

不一致 (inconsistency) 的根源:$H_k / \Phi_k$ 计算时用了不同的线性化状态点。FEJ = 用相同状态点线性化 (位姿用 propagated 值而非 updated 值,landmark 用第一次估计值)。

9. 直接法 vs 特征点法

DSO (直接法) 的优劣 (高翔评述):

优点

  • 数据关联更整体、优雅 (光度一致性代替显式匹配)
  • 弱纹理 / 重复纹理 / 边缘多的场景更好 (特征点法易错配,如车道线/栏杆)
  • 精度鲁棒性优于 ORB-SLAM2 (实测)
  • 卷帘快门相机只要运动不快也能工作

缺点

  • 要求全局曝光相机 (rolling shutter 需慢运动)
  • 明显模糊/失真会丢失
  • 地图重用难 — 没有描述子,无法像特征点法那样存特征+匹配做全局回环
  • 所以直接法擅长连续图像定位,特征点法擅长全局匹配与回环

工程细节

  • 8 个点 (而非完整 $3\times3$ pattern) 是为了配合 SSE C++ optimizer (MatrixAccumulators.h):8 点 = 2 个 SSE 寄存器 (每寄存器 4 float),整齐展开;具体坐标是一个自定义的对称散布 pattern (settings.cpp staticPattern[8],注释仅写 8 for SSE efficiency),并非 3×3 去掉某个角
  • 未成熟点方差估计:见 traceOnerrorInPixel 计算

References

  • Engel, J., Koltun, V., & Cremers, D. (2018). Direct Sparse Odometry. IEEE T-PAMI, 40(3). (arXiv:1607.02565) — 论文
  • DSO 代码: github.com/JakobEngel/dso
  • 高翔 (半闲居士): DSO 详解 — 本笔记主要参考
  • 任乾: DSO 之求导篇 p/77002568;源码解读 / /
  • Engel, J., Schöps, T., & Cremers, D. (2014). LSD-SLAM: Large-Scale Direct Monocular SLAM. ECCV. — 半稠密直接法前作
  • OpenVINS FEJ 文档: docs.openvins.com/fej.html;可观性 知乎讨论
  • 光度标定: cnblogs.com/luyb/p/6077478
  • 直接法灰度不变假设见 光流;FEJ/可观性见 VIO 系列 ch03;逆深度见 三角化 D4