Photometric Calibration
居于特征点法的 vSLAM 通常不太考虑光度标定1的问题,这是由于这些特征描述一般都会具备光照不变性,对图像的亮度值并不敏感。然而在基于光度不变假设的直接法(Direct Method)的 vSLAM 中,由于姿态估计以图像的亮度值为出发点,亮度值的准确度会直接影响算法的精度和稳定性。因此 DSO (Direct Sparse Odometry 2) 的作者引入光度标定的概念,利用精细的相机成像模型,标定成像过程中的光度参数,并用这些参数矫正图像亮度值。
1. 相机成像原理
考虑基于物理的光照模型,相机主要采集的是来自外界环境的辐射度(Radiance,辐射度是给定表面每单位投影面积发射、反射、透射或接收的辐射通量,和方向有关),经过光学镜头(Optics Lens)后转化为感光器件(Sensor)表面所接受到的辐照度(Irradiance,辐照度是单位面积表面接收的辐射通量,和方向无关),然后受到快门(Shutter)控制负责调整曝光时长来使得感光器件积累能量,最后对每个单位积累的能量量化为图像像素光度值(Image Intensity)。整个相机成像过程如下图所示34:
1.1 透镜衰减
光学镜头除了原本熟悉的像素成像位置模型(焦距、光心、畸变),还会有对灰度值影响的晕影现象(Vignetting,原文作者叫做衰减因子(Attenuation Factors)),大致来说是因为光学元件(透镜之类)边缘的非线性以及遮挡等,导致光入射强度随着离主轴的距离拉大而减小。比如想象一下拍摄一面白墙,所得画面边缘会暗一些罢,就这种感觉。所以这个过程有点像给实际图像套了一个核函数,使远离主光轴的像素亮度“衰减”了,因此得名。
1.2 快门影响
快门影响的是曝光时间。自动曝光模式下,不同场景曝光时间并不一样,会导致同一物体在不同场景下的灰度值产生差异。举个例子,根据成像流程图可知,假设同一物体在感器件的辐照度是相同的,那么快门曝光类似一个积分过程,当对相同单位面积的相同辐照度进行不同时间长度的累积能量,那么曝光能量值将不同进而影响图像灰度值。
1.3 感光响应
作者将输入的曝光量和输出的亮度值之间的关系称为响应函数。然而,响应函数一般来说是非线性的,甚至包含人为调整的成分,比如伽马校正、白平衡、色调、饱和度等。
因此作者希望通过光度标定来补偿它们的影响,目的是去除相机成像过程对观测的影响,最好能做到直接取得场景光辐射(或者说传感器表面接收到的辐照度)的真实观测值
2. 相机光度模型
为了决绝成像过程中上述因素的影响,作者将所得的图像数据与我们所需要的真实图像数据通过下式进行建模(注意的是,论文中,使用的是非参数化(non-parametric)的求解方式,也就是说我们不是求出函数的表达式,而是得到对应的映射表): $$ I_i({\bf x}) = G( t_i V({\bf x}) B_i({\bf x}) ) \tag{2.1} \label{2.1} $$ 其中,
- $I_i({\bf x})$ 是通过相机获得的第 i 帧图像(像素灰度矩阵),从公式中看出,数值由相机曝光时间和相机传感器的输入的曝光量和输出的亮度值之间响应函数决定
- $\bf x$ 是自变量为像素坐标
- $G$ 为感光响应函数,是一个标量到标量的映射,为相机固有属性,故与 i 无关。考虑到实际的图像处理,一般设定它的输入输出是离散的,数值取从 0 到 255 的整数(图像灰度值),这样也方便我们使用一个长度 256 的向量来表示它。同时记它的反函数为 $U \doteq G^{-1}$
- $t_i$ 是曝光时间
- $V({\bf x})$ 为描述晕影的透镜衰减因子,固有属性与 i 无关。作者将其表示为一个权重矩阵,描述图像中每像素点的衰减情况。其值为标量,定义在 $[0, 1]$ 上
- $B_i({\bf x})$ 表示不受光学影响的第 i 帧辐照度图像(irradiance image),即我们所求的满足光度不变假设的图像像素灰度矩阵
根据式 $\eqref{2.1}$ 的定义就明显的知道了光度标定的目标是求得 $G$ 和 $V$ 函数。由此,对于相机拍摄的图片我们就可以直接获得光度校准之后的图像: $$ I’_i({\bf x}) \doteq t_i B_i({\bf x}) = \frac{G^{-1} \big( I_i({\bf x}) \big)}{V({\bf x})} = \frac{U \big( I_i({\bf x}) \big)}{V({\bf x})} \tag{2.2} \label{2.2} $$ 对于已知曝光时间的相机图像系列,使用 $B$ 去做直接法当然要比 $I$ 准确得多。当然,场景的亮度在不同视角下有差异这是无法避免的。而对于无法获取曝光时间的相机图像系列,DSO 作者的后续处理以及在线光度标定等方式可以去看原文。
3. 感光相应函数标定
在标定感光相应函数的时候,作者是将相机固定,逐渐变换相机曝光时间,对一个静止的场景进行采集(如下图),以获取标定感光相应函数的数据 $\lbrace I_i, t_i \rbrace$ ,作为已知量。
在这个过程中,相机的辐照度图像 $B$ 是不变的。由于相机的渐晕是相机固有的属性,为了简单起见,定义 $B’({\bf x}) \doteq V({\bf x}) B({\bf x})$。因此,在标定相机响应函数的时候,把相机的光度模型简化成: $$ I({\bf x}) = G(t B’({\bf x})) \tag{3.1} \label{3.1} $$ 给定一个图像 $I_i$ ,其对应的曝光时间为 $t_i$ ,假设在 $U(I({\bf x}))$ 上有一个零均值的高斯噪声,则模型有如下形式: $$ U(I_i({\bf x})) = t_i B’({\bf x}) + \eta_i \ \ , \quad \eta_i \sim {\cal N}(0, \sigma_i^2) \tag{3.2} \label{3.2} $$ 通过最大似然估计,我们近似给出如下最小二乘的形式 $$ E(U, B’) = \sum_i \sum_{{\bf x} \in \Omega} ( U(I_i({\bf x})) - t_i B’({\bf x}))^2 \tag{3.3} \label{3.3} $$ 上式中,第一个求和是对所有(不同曝光时间的)图像,第二个求和是对图像平面上所有的像素点。作者采用迭代轮流最小化上式求解: $$ \begin{align*} U(k)^* &= \underset{U(k)}{\arg\min} \ E(U, B’) = \frac{\sum_{\Omega_k}t_i B’({\bf x})}{|\Omega_k|} \tag{3.4.a} \label{3.4.a} \newline B’({\bf x})^* &= \underset{B’({\bf x})}{\arg\min} \ E(U, B’) = \frac{\sum_i t_i U(I_i({\bf x}))}{\sum_i t_i^2} \tag{3.4.b} \label{3.4.b} \end{align*} $$ 先看 $U(k)$ 的求解,由于论文中使用的是非参数方式,$U(k)$ 对应与一个大小为 256 的一维数组映射表,对于固定的 $k$ 值, $U(k)$ 也是常量。因此在求 $U(k)$ 时,相当于对式 $\eqref{3.3}$ 中的一个变量求偏导,并令偏导为 0: $$ \sum_i \sum_{{\bf x} \in \Omega’}( U(k) - t_i B’({\bf x}) ) = \sum_i \sum_{{\bf x} \in \Omega’} U(k) - \sum_i \sum_{{\bf x} \in \Omega’} t_i B’({\bf x}) = \sum_{{\bf x} \in \Omega_k} U(k) - \sum_{{\bf x} \in \Omega_k} t_i B’({\bf x}) = 0 \tag{3.5} \label{3.5} $$ 其中,$\Omega’ \doteq \lbrace {\bf x} | I_i({\bf x} = k) \rbrace$ 是对于第 i 帧图像的所有图像值为 k 的像素点的结合,而 $\Omega_k \doteq \lbrace i, {\bf x} | I_i({\bf x} = k) \rbrace$ 是在所有图像中,像素值等于 k 的像素点的结合。从而我们可以得到式 $\eqref{3.4.a}$ 。
对于 $B’({\bf x})$ 同理,由于是只对某一位置像素点求,因此可以把每一个 $B’({\bf x})$ 分开,求得每个像素上其对应的最优。转换得到: $$ E(U, B’) = \sum_{{\bf x} \in \Omega} \underbrace{ \sum_i ( U(I_i({\bf x})) - t_i B’({\bf x}))^2 }_{E(U, B’, {\bf x})} \tag{3.6} \label{3.6} $$ 则对式 $\eqref{3.3}$ 中分别每一个 $B’({\bf x})$ 求偏导,也就是对 $E(U, B’, {\bf x})$ 中的 $B’({\bf x})$ 求偏导,并令偏导为 0: $$ \sum_i t_i ( U(I_i({\bf x})) - t_i B’({\bf x})) = \sum_i t_i U(I_i({\bf x})) - \sum_i t_i^2 B’({\bf x}) = 0 \tag{3.7} \label{3.7} $$ 整理之后可得式 $\eqref{3.4.b}$ 。
源码中作者将数据中所有图像的均值作为 $B’$ 的初值,然后根据式 $\eqref{3.4.a}$ 求解 $U$ ,然后在通过求解的 $U$ 根据式 $\eqref{3.4.b}$ 求解 $B’$ ,反复迭代多次以求得合适的结果 $U$ ,源码中默认迭代次数为 10 次。在源码中 main_responseCalib.cpp ,作者还添加了一些工程化的考虑:首先,对灰度值达到 255 的过曝像素进行了向外延伸 leakPadding (默认值为两个像素) 距离的区域,将之都修改为 255 ,这是因为过曝像素周围的像素因为过度也大概率不可靠,因此过滤掉这不边缘像素;其次,实现中考虑如果所有图像中没有某一些光度值的点,那么就无法获取到对应的响应函数值,刚好因为响应函数是个单调函数,因此程序中直接用前两个函数值进行插值获取保证映射的完整性;最后,为了除去尺度的多义性,令 $U(255) = 255$,并把其他 $U(k)$ 值按照该尺度进行缩放。
4. 渐晕标定
同样,对于渐晕标定也使用非参数的形式,使用一个晕影映射表 $V: \Omega \to [0, 1]$ 。标定过程是对一块白墙进行多角度拍摄图像。假设白墙是理想的朗伯反射面(Lambertian Suface),即在固定光照下,从任意视角上观测都有相同的亮度的平面。其目的是要采集的图像数据包涵墙面上某个三维点出现在图像不同位置时的灰度变化信息,以求得衰减因子。因此需要让所取表面上的点尽量在图像的各个角落都坐落一遍。
由于要从不同角度拍摄,因此涉及到相机的位姿估计的问题。作者通过 AR Marker 获取相机相对于平面的位姿。定义从 3D 空间到图像平面的映射 $\pi: {\cal P} \to \Omega$ 。为了方便起见,记 $C({\bf x}) = B_i(\pi_i({\bf x}))$ ,即 $C: {\cal P} \to {\mathbb R}$ 是平面上的点到相机的辐射度。这里的 $C$ 与 $i$ 无关,是因为针对某一空间三维点,从不同角度拍摄,它符合假设的光度不变原则。 注意:这部分中的 $\bf x$ 与前面的不一样,这里的 $\bf x$ 指的是空间中的三维点坐标,而之前指的是图像上的像素坐标。 实际操作上作者把平面表示为正方形区域,且分成 $1000 \times 1000$ 个离散点,如下图,
同样假设在 $U(I_i(\pi_i({\bf x})))$ 上有高斯白噪声,通过最大似然,构建最小二乘: $$ E(C, V) = \sum_{i, {\bf x} \in {\cal P}} \Big( t_i V \big( [ \pi_i ({\bf x}) ] \big) C ({\bf x}) - U \big( I_i (\pi_i ({\bf x})) \big) \Big)^2 \tag{4.1} \label{4.1} $$ 其中,$[\cdot]$ 表示取整运算。之后同样进行交替迭代最小化 $C$ 和 $V$ , $$ \begin{align*} C^* ({\bf x}) = \underset{C({\bf x})}{\arg\min} \ E(C, V) &= \frac{\sum_i t_i V \big( [\pi_i ({\bf x})] \big) U \big( I_i (\pi_i ({\bf x})) \big)}{\sum_i \big( t_i V \big( [\pi_i ({\bf x})] \big) \big)^2} \tag{4.2.a} \label{4.2.a} \newline V^* ({\bf x}) = \underset{V({\bf x})}{\arg\min} \ E(C, V) &= \frac{\sum_i t_i C({\bf x}) U \big( I_i (\pi_i ({\bf x})) \big)}{\sum_i \big( t_i C({\bf x}) \big)^2} \tag{4.2.b} \label{4.2.b} \end{align*} $$ 首先估计一个 $V$ (代码中初始化全 1 矩阵),然后求解 $C$ ,之后反复通过上式进行迭代求解。最后缩放调整至 $\max(V) = 1$ 即可。源码在 main_vignetteCalib.cpp ,其中针对工程化中的优化细节可以清晰的从代码中看出,这里不在赘述。
Reference
A Photometrically Calibrated Benchmark For Monocular Visual Odometry , J. Engel, V. Usenko, D. Cremers, In arXiv:1607.02555, 2016 ↩︎
Direct Sparse Odometry , J. Engel, V. Koltun, D. Cremers, In arXiv:1607.02565, 2016 ↩︎
Recovering High Dynamic Range Radiance Maps from Photographs, Paul E. Debevec, Jitendra Malik ↩︎