问题背景
阈值 δ\deltaδ 是 Huber 鲁棒核函数的重要参数。首先给出结论,在ORB-SLAM系列中,该阈值选取的原则为:
- 单目情况下,根据95%置信水平下两自由度卡方检验的临界值, δ\deltaδ 设置为5.991\sqrt{5.991}5.991;
- 双目情况下,根据95%置信水平下三自由度卡方检验的临界值, δ\deltaδ 设置为7.815\sqrt{7.815}7.815;
下面详细描述了以这种方式设置Huber损失函数的原因。
Huber鲁棒核函数
使用的Huber鲁棒核函数定义如下:

当误差 eee 超过阈值 δ\deltaδ 时,函数的增长从二次型变为线性型。在构建视觉重投影误差的背景下,我们假设当重投影误差超过某个阈值时,有95%的置信度认为是由于错误匹配导致的离群点,从而以线性的方式添加到代价函数中;否则,以二次函数方式计算误差。通过这样的方式,限制了错误匹配对优化算法的影响。
单目相机分析
接下来,我们首先分析单目相机配置中的重投影误差。令 u∈R2\mathbf{u} \in \mathbb{R}^2u∈R2 表示图像特征点的二维(2D)像素位置,并令 u‾∈R2\overline{\mathbf{u}} \in \mathbb{R}^2u∈R2 表示从三维点 P∈R3\bm{P} \in \mathbb{R}^3P∈R3 重投影到图像上的2D像素位置,则重投影误差 ev\bm{e}_vev 为:


其中 (fx,fy)(f_x, f_y)(fx,fy) 是相机焦距,(cx,cy)(c_x, c_y)(cx,cy)是主点,均从标定过程已知。Πm(⋅)\Pi_m(\cdot)Πm(⋅) 是单目相机投影模型。我们假设重投影误差遵循高斯分布:

然后利用协方差对重投影误差进行归一化,得到:

这意味着它遵循二维标准正态分布,因此由其各分量的平方和相加得到的统计量服从自由度为2的卡方分布。
双目相机分析
对于双目配置的情况,我们令观测量为 3 维,即由左相机图像的特征点横纵坐标 + 右相机特征点的横坐标组成(在双目立体相机配置下,左右图像特征点的纵坐标就是相同的)。令 uz∈R3\mathbf{u}_z \in \mathbb{R}^3uz∈R3 为双目立体相机的特征点观测量,u‾z∈R3\overline{\mathbf{u}}_z \in \mathbb{R}^3uz∈R3 表示从三维地图点 P∈R3\bm{P} \in \mathbb{R}^3P∈R3 重投影到图像上的像素位置,则重投影误差 ev\bm{e}_vev 为:

其中 Πs(⋅)\Pi_s(\cdot)Πs(⋅) 为双目相机投影模型。(fx,fy)(f_x, f_y)(fx,fy) 是相机焦距,(cx,cy)(c_x, c_y)(cx,cy)是主点,bbb 是基线长度,均从内参标定中已知。与单目配置情况类似,利用协方差对双目重投影误差进行归一化,其服从三维标准正态分布,因此由其各分量的平方和相加得到的统计量服从自由度为3的卡方分布。
3392

被折叠的 条评论
为什么被折叠?



