本篇笔记我们简单记录一下ORB-SLAM3中使用到的传感器参数文件,主要是参考官方给出的这个文档。主要是一些个人觉得比较重点的地方的介绍,所以完备性可能稍差,如果想了解全部,建议看原文档。
1.参考系的建立
在传感器的标定和使用过程中,经常会涉及以下坐标系:
- 世界坐标系(W): 在应用场景中一般是固定的。坐标系的指向也是根据需求实际定义。尤其是在SLAM应用中,一旦被设定了,就一直fix住了。而且一般SLAM都是选择第一帧的坐标系作为世界坐标系。
- 本体坐标系(B): 一般应用中是和IMU绑定(或者说和移动平台固连,当然了把IMU放在云台上的那种不算)。同时一般认为IMU中的陀螺仪和加速度计共享同一个参考系。
- 相机坐标系(C): 以相机光心为中心的坐标系。Z轴平行于主光轴,指向外;Y轴指向下;X轴指向右。X、Y轴是和影像像素坐标系的u、v方向一致的。
2.传感器的外参
本质上来说,传感器的外参就是求解不同传感器坐标系之间的变换关系。比如,下图展示了一个典型的双目+IMU多传感器坐标系。 可以看到,在这里世界坐标系(W)的Z轴是重力方向的反方向。本体坐标系(B)恒等于IMU坐标系。各个坐标系之间的变换关系用\(T\)来表示。所以很容易就可以得到如下从相机坐标系变换到世界坐标系的式子:
\[\left\{\begin{matrix} \mathbf{T}_{WC_{1}}=\mathbf{T}_{WB}\mathbf{T}_{BC_{1}} \\ \mathbf{T}_{WC_{2}}=\mathbf{T}_{WB}T_{BC_{1}}\mathbf{T}_{C_{1}C_{2}} \end{matrix}\right.\]注意这里的变换顺序,\(\mathbf{T}_{WC_{1}}\)表示一个从C1相机坐标系变换到W世界坐标系的变换。有了这个变换,比如我们有一个C1相机坐标系下的坐标\(\mathbf{x}_{C_{1}}\),那么可以很容易求得它在世界坐标系W下的坐标\(\mathbf{x}_{W}\):
\[\mathbf{x}_{W} = \mathbf{T}_{WC_{1}}\mathbf{x}_{C_{1}}\]在上面我们说明了外参的实质之后。不同传感器的外参其实就是各种变换的组合:
- 双目+IMU: 我们关心的其实就是左相机和IMU之间的关系\(\mathbf{T}_{BC_{1}}\)以及左右相机之间的关系\(\mathbf{T}_{C_{1}C_{2}}\)
- 单目+IMU:只关心左相机和IMU之间的关系\(\mathbf{T}_{BC_{1}}\)
- 双目:只关心左右相机之间的关系\(\mathbf{T}_{C_{1}C_{2}}\)
- 单目:由于只有一个传感器,不存在外参
最后,贴一句文档中对于外参的很好的描述:Extrinsic calibration consists of the set of parameters which define how different sensors are geometrically related.
3.传感器的内参
所谓内参,自然就是指和传感器自身有关、和外界无关的参数。文档中也这样描述:Those are calibration parameters which only depend on each sensor itself.
3.1 相机内参
目前ORB-SLAM3支持三种相机或者说影像输入:
- 针孔模型(Pinhole)。典型针孔模型包含x、y方向上的焦距(\(f_{x}, f_{y}\))以及主点坐标(\(c_{x}, c_{y}\))。针孔模型一般和径向-切向畸变模型(radial-tangential distortion model)配合,一般使用三个径向畸变参数(\(k_{1}, k_{2}, k_{3}\))和两个切向畸变参数(\(p_{1}, p_{2}\))。
- KannalaBrandt8模型。可以支持广角以及鱼眼相机的成像模型。也包含x、y方向上的焦距(\(f_{x}, f_{y}\))以及主点坐标(\(c_{x}, c_{y}\))。一般配合使用的是等距畸变模型(equidistant distortion model),包含\(k_{1}, k_{2}, k_{3}, k_{4}\)参数。
- 已校正(Rectified)。对于已经校正的影像,只需提供x、y方向上的焦距(\(f_{x}, f_{y}\))以及主点坐标(\(c_{x}, c_{y}\))以及基线参数即可。
这里有个潜在的小问题需要注意一下。Pinhole模型和KannalaBrandt8模型他们使用的畸变模型是不同的,但是他们畸变参数的叫法类似,比如都有\(k_{1}, k_{2}, k_{3}\),但一定要记住他们只是名字相同,代表的意义完全不同。不能说我直接拿一个径向-切向畸变模型的k来给等距畸变模型,这样大概率会出问题(基于给定的参数越校正越奇怪)。
在ORB-SLAM3的示例中,分别使用了这三种相机内参(在Stereo-Inertial目录下),以供参考,分别是Euroc.yaml (Pinhole), TUM_VI_512.yaml (KannalaBrandt8) and Realsense_D435i.yaml (Rectified)。
另外需要注意的是,在ORB-SLAM3中,在内部使用OpenCV的stereorectify()
进行了双目校正,使得左右相机的像平面平行于基线。因此,在ORB-SLAM3的双目配置文件中,和ORB-SLAM2相比,去掉了双目校正有关参数。同时,如果相机使用的是KannalaBrandt8模型,为了避免损失分辨率和视场角,默认不做校正。
3.2 IMU内参
IMU是陀螺仪和加速度计的结合,所以一般观测的是在本体坐标系(B)下的三轴角速度\(\mathbf{\tilde{a}}\)和三轴线加速度\(\mathbf{\tilde{\omega}}\)。而这些观测的误差模型可以用下面这个通用的式子来表示。
\[\begin{align} \mathbf{\tilde{a}} = \mathbf{a}+\mathbf{\eta}^{a}+\mathbf{b}^{a}\\ \mathbf{\tilde{\omega}} = \mathbf{\omega}+\mathbf{\eta}^{g}+\mathbf{b}^{g}\\ \end{align}\]这里\(\mathbf{\tilde{a}},\mathbf{\tilde{\omega}}\)分别表示加速度计和陀螺仪的带误差观测值,\(\mathbf{a}, \mathbf{\omega}\)表示理论真值(永远无法得到)。而后面的\(\mathbf{\eta}\)和\(\mathbf{b}\)分别表示两种不同的误差来源:噪声与偏置。上标a和g分别表示加速度计和陀螺仪。也就是说,不管是加速度计还是陀螺仪,他们的真实观测都由三部分构成:真值、噪声、偏置。
3.2.1 IMU噪声
一般而言,上面提到的噪声\(\mathbf{\eta}\)我们假设服从零均值高斯分布,用如下的式子表示:
\[\begin{align} \mathbf{\eta}_{a} \sim \mathcal{N}(\mathbf{0}, \sigma_{a}^{2}\mathbf{I}_{3}) \\ \mathbf{\eta}_{g} \sim \mathcal{N}(\mathbf{0}, \sigma_{g}^{2}\mathbf{I}_{3}) \end{align}\]这里\(\mathbf{I}_{3}\)表示一个3×3的单位阵。为什么维度为3,是因为这里的观测值都是三个维度。我们把\(\sigma_{a},\sigma_{g}\)叫做噪声密度(noise density),一般由IMU的说明书上提供。在ORB-SLAM3的配置文件中,这两个参数要提供否则无法正确运行。并且加速度计的噪声密度\(\sigma_{a}\)的单位是\(m/s^{2}/\sqrt{Hz}\),陀螺仪的噪声密度\(\sigma_{g}\)单位是\(rad/s/\sqrt{Hz}\)。同时需要注意的是,当使用IMU的观测来进行积分推算位姿以及估计误差的时候,噪声密度取决于IMU的频率\(f\)。所以IMU的频率\(f\)也是必须要提供的参数。在实际使用的时候,ORB-SLAM3会根据频率利用公式\(\sigma_{a,f}=\sigma_{a}/\sqrt{f}\)在内部进行噪声密度的离散化,无需我们额外操心。比如下面给出了一个典型的IMU噪声密度和帧率的参数示意。
3.2.2 IMU偏置
除了零均值的高斯噪声,IMU的观测还受偏置影响。一般而言,对于IMU的偏置,认为它服从布朗运动(brownian motion),所以通常会用随机游走进行建模。对于i和i+1时刻,通过下式计算:
\[\begin{align} \mathbf{b}_{i+1}^{a} = \mathbf{b}_{i}^{a}+\mathbf{\eta}_{rw}^{a} \quad with\quad \mathbf{\eta}_{rw}^{a} \sim \mathcal{N}(\mathbf{0}, \sigma_{a,rw}^{2}\mathbf{I}_{3}) \\ \mathbf{b}_{i+1}^{g} = \mathbf{b}_{i}^{g}+\mathbf{\eta}_{rw}^{g} \quad with\quad \mathbf{\eta}_{rw}^{g} \sim \mathcal{N}(\mathbf{0}, \sigma_{g,rw}^{2}\mathbf{I}_{3}) \end{align}\]这里i+1时刻的偏置\(\mathbf{b}_{i+1}\)等于上一课时刻i的偏置\(b_{i}\)再加上一个随机变量。这个随机变量同样是一个服从零均值的高斯分布。其中\(\sigma_{a,rw},\sigma_{g,rw}\)分别是加速度计和陀螺仪的随机游走参数,也是由IMU设备规格书提供。在ORB-SLAM3中,这两个参数的单位分别是\(m/s^{2.5}\)和\(rad/s^{1.5}\)。
一般而言,为了增加随机游走模型对于一些难以建模的情况的鲁棒性,可以适当增大两个参数,比如乘以10等。换句话说就是,假如你跑SLAM的效果不好,那么千万不要再把这两个参数往小了调了,越调效果越差,应该适当增大。下面展示了加速度计和陀螺仪的随机游走参数。
4.其它零碎事项
-
根据这个文档的描述,如果说提供的是已经做过校正的双目数据,那么只需要基线参数就可以了,不需要提供完整的左右相机之间的变换\(\mathbf{T}_{C_{1}C_{2}}\)。
-
在ORB-SLAM3中,对于双目影像的校正是通过OpenCV的
stereorectify()
函数实现的。 -
对于使用Kalibr工具进行双目+IMU联合标定,一般都会分为两个步骤。第一步是先标好双目相机的内参以及相机间的外参。第二步才是标定双目相机和IMU之间的外参。为什么一定要这样呢?为什么不能够合二为一呢?其实这么做是有道理的。因为标定相机,我们需要相机的运动尽可能平缓、幅度不大,从而保证成像质量,不会出现运动模糊等问题。但是这个要求对于标定IMU却是无法接受的。IMU就是需要充分、幅度大的运动,才能在各个方向上都比较好的激活,标定结果才可靠。这两个步骤对于运动的要求是完全相反的,所以在Kalibr中把它们分开了。
5.双目校正
在ORB-SLAM的配置文件中,旧版和新版的最大区别就是新版去掉了一系列的双目校正参数(并不代表不做了,只是换了个方式,下面会介绍)。那么什么是双目校正?在ORB-SLAM中又是怎么做的。这一部分简单进行介绍。
5.1 什么是双目校正
双目校正英文是Stereo Rectification。我们之前在基于双目相机计算视差、深度等信息的时候画过一个原理图,如下。 看到这个图你可能并没有多想,觉得计算原理也挺简单。但其实这里隐含了一个条件,那么就是左右相机的像平面必须要平行于基线。但在现实使用双目相机的时候,两个相机的像平面可能并不一定平行,比如如下图所示。 左边是理想情况下,双目相机的成像情况。右边则是实际可能遇到的情况。双目相机之间的位姿差异、内参差异、畸变参数差异都会给最终的双目SLAM带来问题。比如实际情况1里左相机有向左旋转的趋势,导致像平面不再与基线平行,右相机则向右偏,也不再与基线平行。如果这种情况不加处理,那么可能就会给SLAM的结果带来比较大的影响。同时,左右相机之间内参的差异也会带来一些问题(情况2和3)。无论是左右相机的姿态不对齐还是内参不一致,最终都会导致像平面不与基线平行或者彼此不共面。当然,还有畸变参数的影响。如果两个相机的畸变参数不同,并且在做双目SLAM时没有进行校正,就可能会导致同一个目标在左右影像上的位置不满足成像规律。比如上图中的情况4,橙色点理论上在左右影像上的位置应该是浅黄色。但由于左相机存在没有消除的畸变,导致实际位置偏右下。在右相机中,由于不同畸变参数的存在,实际位置则偏右上。如果以这两个位置进行解算,就会给结果带来误差。 说到这里,你应该已经能够猜到双目校正的目的是什么了。没错,就是通过各种方法,根据给定的一些参数,对左右相机的影像进行校正,使得校正以后的双目影像可以像理想情况那样工作。而这些参数的确定是双目标定的工作,不在双目校正的范畴,这里不赘述。如果对双目校正算法比较感兴趣,可以查看这个CMU的pdf课件。
5.2 双目校正的输入和输出
明确了双目校正的目的,我们自然关心它的输入和输出了。显然,对于双目影像校正这个流程,输入当然是未校正的影像,然后我们根据某种变换关系对它进行校正,最后输出校正后的图像。那么进一步的问题是,“某种变换关系”如何获得?答案是可以根据实际状态和理想状态提前解算好。实际状态是指左右相机实际相对于基线的旋转变换关系、左右相机的内参以及畸变参数。而理想状态则是指我们希望各个参数的样子。比如我们希望左相机的姿态就应该是单位阵,主点为0,焦距为指定值等。输入这些变量,程序就可以计算像素级的变换关系。这里我们不讨论如何解算变换关系。而是直接告诉你实际情况是怎么做的。非常简单,利用OpenCV的函数即可完成。
比如我们看ORB-SLAM2双目stereo_euroc.cc
文件的63行,就是在分别读取左右相机的内参矩阵、畸变系数、旋转矩阵以及投影矩阵(也就是我们希望校正以后的理想状态),如下。
然后,直接调用OpenCV的initUndistortRectifyMap()
函数求解变换关系。关于这个函数的参数说明可以参见这个网页。简单来说,第一个参数是原始相机的内参矩阵,第二个参数是原始相机的畸变参数,第三个参数是原始相机的姿态矩阵,第四个参数是我们想要的变换以后的投影矩阵,第五个参数是无失真图像的像素尺寸,第六个参数是变换关系的数据类型,第七个参数输出的是X方向的变换,第八个参数是输出的Y方向的变换。这样,我们就一共可以得到四个映射变换关系:左影像X方向的变换、左影像Y方向的变换、右影像X方向的变换、右影像Y方向的变换。
5.3 实际执行双目校正
我们获取到变换关系以后,在ORB-SLAM2双目stereo_euroc.cc
文件的136、137行分别对左右影像执行了校正,如下。
简单来说,通过调用OpenCV的Remap()
函数实现了校正。它的参数也显而易见:第一个参数是未校正影像(原始影像),第二个参数是输出的校正后影像,第三个参数是X方向的变换关系,第四个参数是Y方向的变换关系,第五个参数是指定变换的算法。也可以看到,后续传给SLAM进行Tracking的,就是校正后的左右影像imLeftRect
和imRightRect
。
前面也提到,在最新版的ORB-SLAM3的代码中,已经把main()
函数中这个双目校正这个操作去掉了。比如还是双目的EuRoC,这个文件,如下。
可以看到,直接传入的就是读取的影像。当然,这并不代表ORB-SLAM3不做双目校正了。前面说了,它用的是OpenCV的stereorectify()
函数,在这个文件中,如下。
可以看到,这里ORB-SLAM3是自己根据我们给出的左右相机的各种参数,在内部拼接了一个校正的变换,然后用它去校正双目相机影像。当然,这里我们不深究。
6.EuRoC配置文件实例与解释
由于ORB-SLAM3更新了配置文件,所以这里我们分别介绍。
6.1 老版本配置文件
我们贴出来ORB-SLAM3中双目+IMU模式下的EuRoC配置文件,进行分析。注意这里贴出来的是和ORB-SLAM2格式保持一致的参数文件,不是最新的。
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
Camera.type: "PinHole"
# Camera calibration and distortion parameters (OpenCV) (equal for both cameras after stereo rectification)
Camera.fx: 435.2046959714599
Camera.fy: 435.2046959714599
Camera.cx: 367.4517211914062
Camera.cy: 252.2008514404297
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.width: 752
Camera.height: 480
# Camera frames per second
Camera.fps: 20.0
# stereo baseline times fx
Camera.bf: 47.90639384423901
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 60.0 # 35
# Transformation from camera 0 to body-frame (imu)
Tbc: !!opencv-matrix
rows: 4
cols: 4
dt: f
data: [0.0148655429818, -0.999880929698, 0.00414029679422, -0.0216401454975,
0.999557249008, 0.0149672133247, 0.025715529948, -0.064676986768,
-0.0257744366974, 0.00375618835797, 0.999660727178, 0.00981073058949,
0.0, 0.0, 0.0, 1.0]
# IMU noise
IMU.NoiseGyro: 1.7e-04 # 1.6968e-04
IMU.NoiseAcc: 2.0e-03 # 2.0000e-3
IMU.GyroWalk: 1.9393e-05
IMU.AccWalk: 3.e-03 # 3.0000e-3
IMU.Frequency: 200
#--------------------------------------------------------------------------------------------
# Stereo Rectification. Only if you need to pre-rectify the images.
# Camera.fx, .fy, etc must be the same as in LEFT.P
#--------------------------------------------------------------------------------------------
LEFT.height: 480
LEFT.width: 752
LEFT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data:[-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]
LEFT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0]
LEFT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176]
LEFT.Rf: !!opencv-matrix
rows: 3
cols: 3
dt: f
data: [0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176]
LEFT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [435.2046959714599, 0, 367.4517211914062, 0, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]
RIGHT.height: 480
RIGHT.width: 752
RIGHT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data:[-0.28368365, 0.07451284, -0.00010473, -3.555907e-05, 0.0]
RIGHT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [457.587, 0.0, 379.999, 0.0, 456.134, 255.238, 0.0, 0.0, 1]
RIGHT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644]
RIGHT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [435.2046959714599, 0, 367.4517211914062, -47.90639384423901, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1200
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500
下面就对ORB-SLAM双目EuRoC参数文件中一些容易迷惑的参数进行解释。
6.1.1 相机相关参数
Camera.fx
、Camera.fy
、Camera.cx
、Camera.cy
: 相机的焦距和主点,本身没什么好说的。但一定要注意的是,这里的内参并非是左或者右相机的。而是做过双目校正以后的理想参数,这在前面我们介绍双目校正的时候已经提到过了。如果你偷懒不做双目校正或者校正已经做好了,拿到的就是校正后的影像,那我姑且认为左右相机内参一样,这时候这个内参既可以指左相机也可以指右相机。Camera.k1
、Camera.k2
、Camera.p1
、Camera.p2
: 相机的畸变参数。这里都是0的原因是,我们在做双目校正的时候,其实已经对畸变参数进行处理了。换句话说,校正以后的影像畸变参数就是0。除非你不做双目校正,那么这些值就不为0。Camera.bf
: 这个表示的是和双目相机的基线有关的参数。但是需要注意的并非是直接的基线长度。而是以米为单位的基线长度乘以fx。这里的47.906就是这样算出来的。EuRoC的双目相机基线长度约为0.110073808米(来自这个网页)。因此0.110073808×435.2046959714599=47.904638145,也就是文件中的数值了。ThDepth
: 双目深度点的深度阈值,是基线长度的倍数。Tbc
: 相机和IMU之间的变换矩阵,包括旋转和平移。需要注意的是转换方向。根据EuRoC提供的传感器示意图如下。 可以看到,IMU和相机之间差了一个Z轴方向上的90度的旋转。进一步,根据前面的笔记,绕Z轴旋转的旋转矩阵为:
带入90度可以得到:
\[\mathbf{R}_{Z} = \begin{bmatrix} 0 & -1 & 0\\ 1 & 0 & 0\\ 0 & 0 & 1 \end{bmatrix}\]我们可以将理论的\(\mathbf{R}_{Z}\)与参数文件中的旋转部分对比,可以看到是一样的。这些数据都来自于EuRoC数据集自带的sensors.yaml
里,感兴趣可以查看。而平移部分则是在IMU坐标系(本体坐标系)下的平移。这里再简单多说两句平移部分。根据参数文件,平移为(-0.0216401454975, -0.064676986768, 0.00981073058949)。对照示意图,这个平移到底是相对于哪个坐标系的呢?答案是,它指的是相机坐标系的原点在IMU本体坐标系下的位置。所以这里x、y方向都为负值。需要注意的是,这个示意图中画的各个坐标系的位置不一定完全准确,仅供参考。真正可靠可以看跟随数据的sensors.yaml
文件。
6.1.2 IMU相关参数
IMU.NoiseGyro
: 陀螺仪的噪声密度单位是\(rad/s/\sqrt{Hz}\),非离散。在ORB-SLAM3内部自动使用\(\sigma_{g,f}=\sigma_{g}/\sqrt{f}\)公式进行噪声密度离散化。IMU.NoiseAcc
: 加速度计的噪声密度的单位是\(m/s^{2}/\sqrt{Hz}\),非离散。在ORB-SLAM3内部自动使用\(\sigma_{a,f}=\sigma_{a}/\sqrt{f}\)公式进行噪声密度离散化。IMU.GyroWalk
: 陀螺仪的随机游走参数单位是\(rad/s^{1.5}\),非离散。IMU.AccWalk
: 加速度计的随机游走参数单位是\(m/s^{2.5}\),非离散。
这些具体的数值都来自于EuRoC IMU的sensors.yaml
文件。
6.1.3 双目校正相关参数
前面说了,双目校正的输入应该包括左右相机实际相对于基线的旋转变换关系、左右相机的内参、畸变参数,以及期望校正以后的各个参数。
LEFT.D
、RIGHT.D
: 左、右相机的畸变参数矩阵,顺序是k1, k2, p1, p2, k3。如果没有畸变那就全为0。LEFT.K
、RIGHT.K
: 左、右相机的内参矩阵。还是那句话,这里的内参和前面提到的Camera.fx
不是一回事,那个可以看作是校正以后的、理想的相机内参。而这里的则是各个相机实际的内参。如果说你的相机完全相同,那么这里的内参矩阵可以和Camera.fx
一样。LEFT.R
、LEFT.Rf
、RIGHT.R
: 左、右相机相对于基线的姿态偏移矩阵。这里R
和Rf
是完全相同的。如果你的左右相机光轴完全平行,那么这里可以设为3×3的单位阵。LEFT.P
、RIGHT.P
: 左、右相机的理想投影矩阵。换句话说就是,经过双目校正以后,你希望各个参数应该是多少。根据前面的笔记,投影矩阵由相机内参、相机姿态和平移共同组成。因此我们利用平移分量来表达双目相机中和基线有关的变化。同时在双目的应用中,一般以左相机为参考,所以它的平移部分为0,而右相机相当于在x方向上有平移,所以这里填充的就是上面计算的Camera.bf
的负数。你可以把他理解为,在左相机的坐标系下,右相机要减少Camera.bf
长度才能和左相机重合。同时需要注意的是,投影矩阵中表达的相机内参就是理想的相机内参,也就对应了上面提到的以Camera.
开头的参数。因此,它们要保持完全一致,不然就没有意义了。
6.2 新版本
我们也可以贴出来ORB-SLAM3中最新格式的参数文件,如下。你会发现会简单了很多。
%YAML:1.0
#--------------------------------------------------------------------------------------------
# System config
#--------------------------------------------------------------------------------------------
# When the variables are commented, the system doesn't load a previous session or not store the current one
# If the LoadFile doesn't exist, the system give a message and create a new Atlas from scratch
#System.LoadAtlasFromFile: "Session_MH01_MH02_MH03_Stereo60_Pseudo"
# The store file is created from the current session, if a file with the same name exists it is deleted
#System.SaveAtlasToFile: "Session_MH01_MH02_MH03_Stereo60_Pseudo"
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
File.version: "1.0"
Camera.type: "PinHole"
# Camera calibration and distortion parameters (OpenCV)
Camera1.fx: 458.654
Camera1.fy: 457.296
Camera1.cx: 367.215
Camera1.cy: 248.375
Camera1.k1: -0.28340811
Camera1.k2: 0.07395907
Camera1.p1: 0.00019359
Camera1.p2: 1.76187114e-05
Camera2.fx: 457.587
Camera2.fy: 456.134
Camera2.cx: 379.999
Camera2.cy: 255.238
Camera2.k1: -0.28368365
Camera2.k2: 0.07451284
Camera2.p1: -0.00010473
Camera2.p2: -3.55590700e-05
Camera.width: 752
Camera.height: 480
# Camera frames per second
Camera.fps: 20
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
Stereo.ThDepth: 60.0
Stereo.T_c1_c2: !!opencv-matrix
rows: 4
cols: 4
dt: f
data: [0.999997256477797,-0.002317135723275,-0.000343393120620,0.110074137800478,
0.002312067192432,0.999898048507103,-0.014090668452683,-0.000156612054392,
0.000376008102320,0.014089835846691,0.999900662638081,0.000889382785432,
0,0,0,1.000000000000000]
# Transformation from camera 0 to body-frame (imu)
IMU.T_b_c1: !!opencv-matrix
rows: 4
cols: 4
dt: f
data: [0.0148655429818, -0.999880929698, 0.00414029679422, -0.0216401454975,
0.999557249008, 0.0149672133247, 0.025715529948, -0.064676986768,
-0.0257744366974, 0.00375618835797, 0.999660727178, 0.00981073058949,
0.0, 0.0, 0.0, 1.0]
# IMU noise
IMU.NoiseGyro: 1.7e-04 # 1.6968e-04
IMU.NoiseAcc: 2.0e-03 # 2.0000e-3
IMU.GyroWalk: 1.9393e-05
IMU.AccWalk: 3.e-03 # 3.0000e-3
IMU.Frequency: 200.0
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1200
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1.0
Viewer.GraphLineWidth: 0.9
Viewer.PointSize: 2.0
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3.0
Viewer.ViewpointX: 0.0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500.0
Viewer.imageViewScale: 1.0
没有了那些ORB-SLAM2格式中很难让人理解的参数,只有两个外参矩阵,十分方便。Camera1
表示左相机,Camera2
表示右相机。而左相机到IMU的变换和老版本是一样的,左相机到右相机的变换则是遵循一样的方法就可以求解。不清楚的参数查阅EuRoC的sensors.yaml
文件,里面有需要的参数。
7.参考资料
- [1] https://github.com/UZ-SLAMLab/ORB_SLAM3/blob/master/Calibration_Tutorial.pdf
- [2] https://blog.csdn.net/weixin_44279335/article/details/109448583
- [3] https://blog.csdn.net/weixin_37918890/article/details/95626004
本文作者原创,未经许可不得转载,谢谢配合