IMU预积分
0 预备知识
-
SO(3)的指数映射:
exp ( ϕ ∧ ) = I + sin ( ∥ ϕ ∥ ) ∥ ϕ ∥ ϕ ∧ + 1 − cos ( ∥ ϕ ∥ ) ∥ ϕ ∥ 2 ( ϕ ∧ ) 2 \exp(\phi^\wedge)=\bold{I} + \frac{\sin(\|\phi \|)}{\| \phi \|}\phi^\wedge+\frac{1-\cos(\|\phi \|)}{\| \phi \|^2}(\phi^\wedge)^2 exp(ϕ∧)=I+∥ϕ∥sin(∥ϕ∥)ϕ∧+∥ϕ∥21−cos(∥ϕ∥)(ϕ∧)2exp ( ϕ ∧ ) ≈ I + ϕ ∧ \exp(\phi^\wedge)\approx \bold{I}+\phi^\wedge exp(ϕ∧)≈I+ϕ∧
-
SO(3)的对数映射:
log ( R ) ∨ = u θ log ( R ) = θ ⋅ ( R − R T ) 2 sin ( θ ) , θ = arccos ( t r ( R − 1 ) 2 ) \log(\bold{R})^\vee=\bold{u}\theta \\ \log(\bold{R})=\frac{\theta\cdot(\bold{R}-\bold{R}^T)}{2\sin(\theta)}, \quad \theta=\arccos(\frac{tr(\bold{R}-1)}{2}) log(R)∨=uθlog(R)=2sin(θ)θ⋅(R−RT),θ=arccos(2tr(R−1)) -
李代数的一阶近似:
Exp ( ϕ + δ ϕ ) ≈ Exp ( ϕ ) Exp ( J r ( ϕ ) δ ϕ ) Log ( Exp ( ϕ ) Exp ( δ ϕ ) ) ≈ ϕ + J r − 1 ( ϕ ) δ ϕ \text{Exp}(\phi+\delta\phi)\approx \text{Exp}(\phi)\text{Exp}(\bold{J}_r(\phi)\delta \phi) \\ \text{Log}(\text{Exp}(\phi)\text{Exp}(\delta\phi)) \approx \phi+\bold{J}_r^{-1}(\phi)\delta\phi Exp(ϕ+δϕ)≈Exp(ϕ)Exp(Jr(ϕ)δϕ)Log(Exp(ϕ)Exp(δϕ))≈ϕ+Jr−1(ϕ)δϕ
其中,
J r ( ϕ ) = I − 1 − cos ( ∥ ϕ ∥ ) ∥ ϕ ∥ 2 ϕ ∧ + ∥ ϕ ∥ − sin ( ∥ ϕ ∥ ) ∥ ϕ ∥ 3 ( ϕ ∧ ) 2 J r − 1 ( ϕ ) = I + 1 2 ϕ ∧ + ( 1 ∥ ϕ ∥ 2 + 1 + cos ( ∥ ϕ ∥ ) 2 ∥ ϕ ∥ sin ( ∥ ϕ ∥ ) ) ( ϕ ∧ ) 2 \bold{J}_r(\phi)=\bold{I}-\frac{1-\cos(\|\phi \|)}{\| \phi\|^2}\phi^\wedge+\frac{\|\phi\|-\sin(\|\phi\|)}{\| \phi\|^3}(\phi^\wedge)^2 \\ \bold{J}_r^{-1}(\phi)=\bold{I}+\frac{1}{2}\phi^\wedge+(\frac{1}{\| \phi\|^2}+\frac{1+\cos(\|\phi \|)}{2\|\phi \|\sin(\|\phi \|)})(\phi^\wedge)^2 Jr(ϕ)=I−∥ϕ∥21−cos(∥ϕ∥)ϕ∧+∥ϕ∥3∥ϕ∥−sin(∥ϕ∥)(ϕ∧)2Jr−1(ϕ)=I+21ϕ∧+(∥ϕ∥21+2∥ϕ∥sin(∥ϕ∥)1+cos(∥ϕ∥))(ϕ∧)2 -
伴随性质:
R Exp ( ϕ ) R T = exp ( R ϕ ∧ R T ) = Exp ( R ϕ ) Exp ( ϕ ) R = R Exp ( R T ϕ ) \bold{R}\text{Exp}(\phi)\bold{R}^T=\exp(\bold{R}\phi^\wedge \bold{R}^T)=\text{Exp}(\bold{R}\phi) \\ \text{Exp}(\phi)\bold{R}=\bold{R}\text{Exp}(\bold{R}^T\phi) RExp(ϕ)RT=exp(Rϕ∧RT)=Exp(Rϕ)Exp(ϕ)R=RExp(RTϕ)
1 Visual-Inertial State Estimation
-
系统状态
系统在时间 i i i的状态为 x i = [ R i , p i , v i , b i ] \mathbf x_i=[\bold{R}_i,\bold{p}_i,\bold{v}_i,\bold{b}_i] xi=[Ri,pi,vi,bi],其中 ( R i , p i ) ∈ S E ( 3 ) (\bold{R}_i,\bold{p}_i)\in SE(3) (Ri,pi)∈SE(3), b i = [ b i g , b i a ] ∈ R 6 \bold{b}_i=[\bold{b}_i^g,\bold{b}_i^a]\in\mathbb R^6 bi=[big,bia]∈R6。
令 K k \mathcal K_k Kk为到k时刻位置的关键帧集合,则我们估计所有关键帧的状态:
X k = { x i } i ∈ K k \mathcal X_k=\{\mathbf x_i\}_{i\in \mathcal K_k} Xk={xi}i∈Kk -
观测量
观测量包括视觉观测和IMU观测:
Z k = { C i , I i j } ( i , j ) ∈ K k \mathcal Z_k=\{C_i,I_{ij} \}_{(i,j)\in\mathcal K_k} Zk={Ci,Iij}(i,j)∈Kk -
因子图和MAP估计
p ( X k ∣ Z k ) ∝ p ( X 0 ) p ( Z k ∣ X k ) = p ( X 0 ) ∏ ( i , j ) ∈ K k p ( C i , I i j ∣ X k ) = p ( X 0 ) ∏ ( i , j ) ∈ K k p ( I i j ∣ x i , x j ) ∏ i ∈ K k ∏ l ∈ C i p ( z i l ∣ x i ) p(\mathcal X_k|\mathcal Z_k)\propto p(\mathcal X_0)p(\mathcal Z_k|\mathcal X_k) = p(\mathcal X_0) \prod_{(i,j)\in \mathcal K_k}p(\mathcal C_i,\mathcal I_{ij}|\mathcal X_k) \\= p(\mathcal X_0)\prod_{(i,j)\in\mathcal K_k} p(\mathcal I_{ij}|\mathbf x_i, \mathbf x_j)\prod_{i\in\mathcal K_k}\prod_{l\in\mathcal C_i}p(\mathbf z_{il}|\mathbf x_i) p(Xk∣Zk)∝p(X0)p(Zk∣Xk)=p(X0)(i,j)∈Kk∏p(Ci,Iij∣Xk)=p(X0)(i,j)∈Kk∏p(Iij∣xi,xj)i∈Kk∏l∈Ci∏p(zil∣xi)
2 IMU测量模型
- 测量模型
其中, B ω ~ W B _{B}{\tilde\omega}_{WB} Bω~WB为测量值, B ω W B _{B}{\omega}_{WB} BωWB为真实值。
- 动力学
R ˙ W B = R W B B ω W B ∧ , W v ˙ = W a , W p ˙ = W v \dot{\bold{R}}_{WB}=\bold{R}_{WB} ~_{B}{\omega}^\wedge_{WB}, ~ _W{\dot {\bold{v}}}=~_{W}{\bold{a}},\ _W{\dot {\bold{p}}}=~_W\bold{v} R˙WB=RWB BωWB∧, Wv˙= Wa, Wp˙= Wv
假设在 [ t , t + Δ t ] [t,t+\Delta t] [t,t+Δt]时间内, W a _{W}{\bold{a}} Wa和 B ω W B _{B}{\omega}_{WB} BωWB保持不变,则有:
将测量值代入,可以得到:
其中, Cov ( η g d ( t ) ) = 1 Δ t Cov ( η g ( t ) ) \text{Cov}(\eta^{gd}(t))=\frac{1}{\Delta t}\text{Cov}(\eta^{g}(t)) Cov(ηgd(t))=Δt1Cov(ηg(t))。
3 IMU预积分
根据动力学模型,我们可以得到两个连续关键帧的IMU积分:
为避免在时间 t i t_i ti线性化时需要重新积分,构造相对增量:
其中, Δ R i k = R i T R k , Δ v i k = R i T ( v k − v i − g Δ t i k ) \Delta \bold{R}_{ik}=\bold{R}_i^T\bold{R}_k,~\Delta\bold{v}_{ik}=\bold{R}^T_i(\bold{v}_k-\bold{v}_i-\bold{g}\Delta t_{ik}) ΔRik=RiTRk, Δvik=RiT(vk−vi−gΔtik)。然而,上述这种形式仍然是关于bias的函数,为此,提出了IMU预积分。
3.1 预积分测量模型
首先,假设两帧之间的bias不变:
b
i
g
=
b
i
+
1
g
=
⋯
=
b
j
−
1
g
,
b
i
a
=
b
i
+
1
a
=
⋯
=
b
j
−
1
a
\bold{b}^g_i=\bold{b}^g_{i+1}=\dots=\bold{b}^g_{j-1},~\bold{b}^a_i=\bold{b}^a_{i+1}=\dots=\bold{b}^a_{j-1}
big=bi+1g=⋯=bj−1g, bia=bi+1a=⋯=bj−1a
对
Δ
R
i
j
\Delta \bold{R}_{ij}
ΔRij做一阶近似,利用开始提到的BCH近似和伴随性质,可得:
其中, J r k = J r ( ( w ~ k − b i g ) Δ t ) \mathbf J^k_r=\mathbf J_r((\tilde{w}_k- \bold{b}^g_i)\Delta t) Jrk=Jr((w~k−big)Δt)。
对
Δ
v
i
j
\Delta \bold{v}_{ij}
Δvij做一阶近似,可得:
对 Δ p i j \Delta \bold{p}_{ij} Δpij做一阶近似,可得:
由此,将相对增量写成了“真实值+噪声”的测量模型:
[
Δ
R
~
i
j
Δ
v
~
i
j
Δ
p
~
i
j
0
0
]
=
[
R
i
T
R
j
Exp
(
δ
ϕ
i
j
)
R
i
T
(
v
j
−
v
i
−
g
Δ
t
i
j
)
+
δ
v
i
j
R
i
T
(
p
j
−
p
i
−
v
i
Δ
t
i
j
−
1
2
g
Δ
t
i
j
2
)
+
δ
p
i
j
b
j
a
−
b
i
a
+
δ
b
i
j
a
b
j
g
−
b
i
g
+
δ
b
i
j
g
]
\begin{bmatrix} \Delta \tilde{\bold{R}}_{ij} \\ \Delta \tilde{\bold{v}}_{ij} \\ \Delta \tilde{\bold{p}}_{ij} \\ \mathbf{0} \\ \mathbf{0} \end{bmatrix} = \begin{bmatrix} \bold{R}_i^T \mathbf{R}_{j}\text{Exp}(\delta\phi_{ij})\\ \bold{R}_i^T(\mathbf{v}_j-\mathbf{v}_i-\mathbf{g}\Delta t_{ij})+\delta \mathbf{v}_{ij} \\ \bold{R}_i^T(\bold{p}_j-\bold{p}_i-\bold{v}_i\Delta t_{ij}-\frac{1}{2}\bold{g}\Delta t_{ij}^2)+\delta \bold{p}_{ij} \\ \mathbf{b}^a_{j}-\mathbf{b}^a_{i}+\delta \mathbf{b}^a_{ij} \\ \mathbf{b}^g_{j}-\mathbf{b}^g_{i}+\delta \mathbf{b}^g_{ij} \end{bmatrix}
⎣
⎡ΔR~ijΔv~ijΔp~ij00⎦
⎤=⎣
⎡RiTRjExp(δϕij)RiT(vj−vi−gΔtij)+δvijRiT(pj−pi−viΔtij−21gΔtij2)+δpijbja−bia+δbijabjg−big+δbijg⎦
⎤
其中,预积分测量值为:
Δ
R
~
i
j
=
∏
k
=
i
j
−
1
Exp
(
(
ω
~
k
−
b
i
g
)
Δ
t
)
Δ
v
~
i
j
=
∑
k
=
i
j
−
1
Δ
R
~
i
k
(
a
~
k
−
b
i
a
)
Δ
t
Δ
p
~
i
j
=
∑
k
=
i
j
−
1
(
Δ
v
~
i
k
Δ
t
+
1
2
Δ
R
~
i
k
(
a
~
k
−
b
i
a
)
Δ
t
2
)
\begin{aligned} \Delta \tilde{\bold{R}}_{ij}&=\prod_{k=i}^{j-1}\text{Exp}((\tilde\omega_k-\bold{b}^g_i)\Delta t) \\ \Delta \tilde{\bold{v}}_{ij}&=\sum_{k=i}^{j-1} \Delta\tilde{\bold{R}}_{ik}(\tilde{\bold{a}}_{k}-\bold{b}^a_{i})\Delta t \\ \Delta \tilde{\bold{p}}_{ij}&=\sum_{k=i}^{j-1} (\Delta \tilde{\bold{v}}_{ik}\Delta t+\frac{1}{2}\Delta\tilde{\bold{R}}_{ik}(\tilde{\bold{a}}_{k}-\bold{b}^a_{i})\Delta t^2) \end{aligned}
ΔR~ijΔv~ijΔp~ij=k=i∏j−1Exp((ω~k−big)Δt)=k=i∑j−1ΔR~ik(a~k−bia)Δt=k=i∑j−1(Δv~ikΔt+21ΔR~ik(a~k−bia)Δt2)
其前向传播的形式为:
Δ
R
~
i
k
+
1
=
Δ
R
~
i
k
Exp
(
(
ω
~
k
−
b
i
g
)
Δ
t
)
Δ
v
~
i
k
+
1
=
Δ
v
~
i
k
+
Δ
R
~
i
k
(
a
~
k
−
b
i
a
)
Δ
t
Δ
p
~
i
k
+
1
=
Δ
p
~
i
k
+
Δ
v
~
i
k
Δ
t
+
1
2
Δ
R
~
i
k
(
a
~
k
−
b
i
a
)
Δ
t
2
\begin{aligned} \Delta \tilde{\bold{R}}_{ik+1}&=\Delta \tilde{\bold{R}}_{ik}\text{Exp}((\tilde\omega_k-\bold{b}^g_i)\Delta t) \\ \Delta \tilde{\bold{v}}_{ik+1}&=\Delta \tilde{\bold{v}}_{ik}+ \Delta\tilde{\bold{R}}_{ik}(\tilde{\bold{a}}_{k}-\bold{b}^a_{i})\Delta t \\ \Delta \tilde{\bold{p}}_{ik+1}&= \Delta \tilde{\bold{p}}_{ik}+\Delta \tilde{\bold{v}}_{ik}\Delta t+\frac{1}{2}\Delta\tilde{\bold{R}}_{ik}(\tilde{\bold{a}}_{k}-\bold{b}^a_{i})\Delta t^2 \end{aligned}
ΔR~ik+1Δv~ik+1Δp~ik+1=ΔR~ikExp((ω~k−big)Δt)=Δv~ik+ΔR~ik(a~k−bia)Δt=Δp~ik+Δv~ikΔt+21ΔR~ik(a~k−bia)Δt2
3.2 噪声传递
预积分噪声设定为零均值高斯分布:
η
i
j
Δ
=
[
δ
ϕ
i
j
,
δ
v
i
j
,
δ
p
i
j
]
∼
N
(
0
9
×
1
,
Σ
i
j
)
\eta^\Delta_{ij}=[\delta\phi_{ij},\delta\bold{v}_{ij},\delta\bold{p}_{ij}] \sim \mathcal N(0_{9\times1},\Sigma_{ij})
ηijΔ=[δϕij,δvij,δpij]∼N(09×1,Σij)
误差传递为:
η
i
k
+
1
Δ
=
A
η
i
k
Δ
+
B
η
k
d
[
δ
ϕ
i
k
+
1
δ
v
i
k
+
1
δ
p
i
k
+
1
]
=
[
Δ
R
~
k
k
+
1
T
0
3
×
3
0
3
×
3
−
Δ
R
~
i
k
(
a
~
k
−
b
i
a
)
∧
Δ
t
I
3
×
3
0
3
×
3
−
1
2
Δ
R
~
i
k
(
a
~
k
−
b
i
a
)
∧
Δ
t
2
I
3
×
3
Δ
t
I
3
×
3
]
[
δ
ϕ
i
k
δ
v
i
k
δ
p
i
k
]
+
[
J
r
k
Δ
t
0
3
×
3
0
3
×
3
Δ
R
~
i
k
Δ
t
0
3
×
3
1
2
Δ
R
~
i
k
Δ
t
2
]
[
η
k
g
d
η
k
a
d
]
\begin{aligned} \eta^\Delta_{ik+1} &= \mathbf{A}\eta^\Delta_{ik}+\mathbf{B}\eta^d_{k} \\ \begin{bmatrix} \delta \phi_{ik+1} \\ \delta \mathbf{v}_{ik+1} \\ \delta \mathbf{p}_{ik+1} \end{bmatrix} &= \begin{bmatrix} \Delta \tilde{\bold{R}}^T_{kk+1} & \mathbf{0}_{3\times3} & \mathbf{0}_{3\times3} \\ -\Delta \tilde{\bold{R}}_{ik}(\tilde{\mathbf{a}}_k-\mathbf{b}^a_i)^\wedge\Delta t & \mathbf{I}_{3\times3} & \mathbf{0}_{3\times3} \\ -\frac{1}{2}\Delta \tilde{\bold{R}}_{ik}(\tilde{\mathbf{a}}_k-\mathbf{b}^a_i)^\wedge\Delta t^2 & \mathbf{I}_{3\times3}\Delta t & \mathbf{I}_{3\times3} \end{bmatrix} \begin{bmatrix} \delta \phi_{ik} \\ \delta \mathbf{v}_{ik} \\ \delta \mathbf{p}_{ik} \end{bmatrix} + \begin{bmatrix} \mathbf{J}^k_r \Delta t & \mathbf{0}_{3\times3} \\ \mathbf{0}_{3\times3} & \Delta \tilde{\bold{R}}_{ik}\Delta t \\ \mathbf{0}_{3\times3} & \frac{1}{2}\Delta \tilde{\bold{R}}_{ik}\Delta t^2 \end{bmatrix} \begin{bmatrix} \eta^{gd}_k \\ \eta^{ad}_k \end{bmatrix} \end{aligned}
ηik+1Δ⎣
⎡δϕik+1δvik+1δpik+1⎦
⎤=AηikΔ+Bηkd=⎣
⎡ΔR~kk+1T−ΔR~ik(a~k−bia)∧Δt−21ΔR~ik(a~k−bia)∧Δt203×3I3×3I3×3Δt03×303×3I3×3⎦
⎤⎣
⎡δϕikδvikδpik⎦
⎤+⎣
⎡JrkΔt03×303×303×3ΔR~ikΔt21ΔR~ikΔt2⎦
⎤[ηkgdηkad]
其中,
η
k
d
=
[
η
k
g
d
,
η
k
a
d
]
\eta^d_{k}=[\eta^{gd}_{k},\eta^{ad}_{k}]
ηkd=[ηkgd,ηkad]。
协方差传递为:
Σ
i
k
+
1
=
A
Σ
i
k
A
T
+
B
Σ
η
B
T
\Sigma_{ik+1}=\bold{A}\Sigma_{ik}\bold{A}^T+\bold{B}\Sigma_\eta\bold{B}^T
Σik+1=AΣikAT+BΣηBT
其中,
Σ
i
i
=
0
9
×
9
\Sigma_{ii}=\mathbf{0}_{9\times9}
Σii=09×9,
Σ
η
∈
R
6
×
6
\Sigma_\eta\in\mathbb{R}^{6\times6}
Ση∈R6×6为IMU噪声协方差。
3.3 bias更新
之前的推导假设了bias不变,然而实际情况是bias会随时间发生微小变化,因此可以定义bias更新 b ← b ˉ + δ b \bold{b}\leftarrow \bar{\mathbf{b}}+\delta \bold{b} b←bˉ+δb,并对预积分测量值进行更新:
其中,雅可比项的递推形式为:
∂ Δ R ˉ i j ∂ b g = − ∑ k = i j − 1 [ Δ R ~ k + 1 j ( b i ˉ ) T J r k Δ t ] ∂ Δ v ˉ i j ∂ b a = − ∑ k = i j − 1 Δ R ˉ i k Δ t ∂ Δ v ˉ i j ∂ b g = − ∑ k = i j − 1 Δ R ˉ i k ( a ~ k − b ˉ i a ) × ∂ Δ R ˉ i k ∂ b g Δ t ∂ Δ p ˉ i j ∂ b a = ∑ k = i j − 1 ( ∂ Δ v ˉ i k ∂ b a Δ t − 1 2 Δ R ˉ i k Δ t 2 ) ∂ Δ p ˉ i j ∂ b g = ∑ k = i j − 1 ( ∂ Δ v ˉ i k ∂ b g Δ t − 1 2 Δ R ˉ i k ( a ~ k − b ˉ i a ) × ∂ Δ R ˉ i k ∂ b g Δ t 2 ) \begin{aligned} \frac{\partial\Delta\bar{\mathbf{R}}_{ij}}{\partial \mathbf{b}^g}&=-\sum_{k=i}^{j-1}[\Delta\tilde{\mathbf{R}}_{k+1j}(\bar{\mathbf{b}_i})^T\mathbf{J}_r^k \Delta t] \\ \frac{\partial\Delta\bar{\mathbf{v}}_{ij}}{\partial \mathbf{b}^a} &= -\sum_{k=i}^{j-1} \Delta\bar{\mathbf{R}}_{ik}\Delta t \\ \frac{\partial\Delta\bar{\mathbf{v}}_{ij}}{\partial \mathbf{b}^g} &= -\sum_{k=i}^{j-1} \Delta\bar{\mathbf{R}}_{ik} (\tilde{\mathbf{a}}_k-\bar{\mathbf{b}}^a_i)_\times \frac{\partial\Delta\bar{\mathbf{R}}_{ik}}{\partial \mathbf{b}^g} \Delta t \\ \frac{\partial\Delta\bar{\mathbf{p}}_{ij}}{\partial \mathbf{b}^a} &= \sum_{k=i}^{j-1} (\frac{\partial\Delta\bar{\mathbf{v}}_{ik}}{\partial \mathbf{b}^a}\Delta t-\frac{1}{2}\Delta\bar{\mathbf{R}}_{ik}\Delta t^2) \\ \frac{\partial\Delta\bar{\mathbf{p}}_{ij}}{\partial \mathbf{b}^g} &= \sum_{k=i}^{j-1} (\frac{\partial\Delta\bar{\mathbf{v}}_{ik}}{\partial \mathbf{b}^g}\Delta t - \frac{1}{2}\Delta\bar{\mathbf{R}}_{ik} (\tilde{\mathbf{a}}_k-\bar{\mathbf{b}}^a_i)_\times \frac{\partial\Delta\bar{\mathbf{R}}_{ik}}{\partial \mathbf{b}^g} \Delta t^2) \end{aligned} ∂bg∂ΔRˉij∂ba∂Δvˉij∂bg∂Δvˉij∂ba∂Δpˉij∂bg∂Δpˉij=−k=i∑j−1[ΔR~k+1j(biˉ)TJrkΔt]=−k=i∑j−1ΔRˉikΔt=−k=i∑j−1ΔRˉik(a~k−bˉia)×∂bg∂ΔRˉikΔt=k=i∑j−1(∂ba∂ΔvˉikΔt−21ΔRˉikΔt2)=k=i∑j−1(∂bg∂ΔvˉikΔt−21ΔRˉik(a~k−bˉia)×∂bg∂ΔRˉikΔt2)
3.4 IMU因子
预积分误差 r I i j = [ r Δ R i j , r Δ v i j , r Δ p i j ] ∈ R 9 \bold{r}_{\mathcal I_{ij}}=[\bold{r}_{\Delta\bold{R}_{ij}}, \bold{r}_{\Delta\bold{v}_{ij}},\bold{r}_{\Delta\bold{p}_{ij}}]\in \mathbb R^9 rIij=[rΔRij,rΔvij,rΔpij]∈R9,定义如下:
通常还包括bias项:
优化变量:
雅可比项:
1)
r
Δ
R
i
j
\bold{r}_{\Delta\bold{R}_{ij}}
rΔRij的雅可比:
2) r Δ v i j \bold{r}_{\Delta\bold{v}_{ij}} rΔvij的雅可比:
3)
r
Δ
p
i
j
\bold{r}_{\Delta\bold{p}_{ij}}
rΔpij的雅可比:
4 代码实现(VINS-Mono)
IntegrationBase类
IntegrationBase
类是VINS-Mono中用于处理IMU预积分的类,包含的成员变量如下:
double dt; // 每次预积分的时间周期长度[i,i+1]
Eigen::Vector3d acc_0, gyr_0; // k时刻对应的IMU测量值
Eigen::Vector3d acc_1, gyr_1; // k+1时刻对应的IMU测量值
const Eigen::Vector3d linearized_acc, linearized_gyr; // i时刻对应的IMU测量值
Eigen::Vector3d linearized_ba, linearized_bg; // 加速度计和陀螺仪零偏,在[i,j]区间上视为不变
Eigen::Matrix<double, 15, 15> jacobian, covariance; // 预积分误差的雅克比矩阵J_ij和协方差矩阵P_ij
Eigen::Matrix<double, 18, 18> noise; // 系统噪声矩阵Q
double sum_dt; //IMU预积分区间[i,j]的总时长
Eigen::Vector3d delta_p; // 位置预积分P_ij
Eigen::Quaterniond delta_q; // 旋转四元数预积分R_ij
Eigen::Vector3d delta_v; // 速度预积分V_ij
std::vector<double> dt_buf; // 用于存储每次预积分时间dt的寄存器
std::vector<Eigen::Vector3d> acc_buf; // 用于存储每次预积分加速度测量的寄存器
std::vector<Eigen::Vector3d> gyr_buf; // 用于存储每次预积分角速度测量的寄存器
预积分测量模型
预积分测量值通过中值积分计算,其前向传播函数为propagate
,该函数实现了
i
j
ij
ij的预积分递推。函数以当前IMU测量值和时间间隔为输入,首先调用midPointIntegration
计算预积分的一步递推,然后对预积分初值进行重置,用于下一步递推。
在VINS-Mono中,预积分测量值可以用中值积分进行前向传播计算(如VINS-Mono中),预积分测量值的前向传播可以写为:
Δ
R
~
i
j
=
∏
k
=
i
j
−
1
Exp
(
ω
^
k
Δ
t
)
Δ
v
~
i
j
=
∑
k
=
i
j
−
1
a
^
k
Δ
t
Δ
p
~
i
j
=
∑
k
=
i
j
−
1
(
Δ
v
~
i
k
Δ
t
+
1
2
a
^
k
Δ
t
2
)
\begin{aligned} \Delta \tilde{\bold{R}}_{ij} &= \prod_{k=i}^{j-1}\text{Exp}(\hat \omega_k\Delta t) \\ \Delta \tilde{\bold{v}}_{ij}&=\sum_{k=i}^{j-1} \hat{\mathbf{a}}_k \Delta t \\ \Delta \tilde{\bold{p}}_{ij}&=\sum_{k=i}^{j-1} (\Delta\tilde{\bold{v}}_{ik}\Delta t+\frac{1}{2}\hat{\mathbf{a}}_k \Delta t^2) \end{aligned}
ΔR~ijΔv~ijΔp~ij=k=i∏j−1Exp(ω^kΔt)=k=i∑j−1a^kΔt=k=i∑j−1(Δv~ikΔt+21a^kΔt2)
其中,加速度和角速度用中值积分表示:
ω
^
k
=
1
2
(
ω
~
k
+
ω
~
k
+
1
)
−
b
i
g
a
^
k
=
1
2
[
Δ
R
~
i
k
(
a
~
k
−
b
i
a
)
+
Δ
R
~
i
k
+
1
(
a
~
k
+
1
−
b
i
a
)
]
\hat \omega_k = \frac{1}{2}(\tilde\omega_k+\tilde\omega_{k+1})-\bold{b}^g_i \\ \hat{\mathbf{a}}_k = \frac{1}{2}[\Delta\tilde{\bold{R}}_{ik}(\tilde{\bold{a}}_{k}-\bold{b}^a_{i})+\Delta\tilde{\bold{R}}_{ik+1}(\tilde{\bold{a}}_{k+1}-\bold{b}^a_{i})]
ω^k=21(ω~k+ω~k+1)−biga^k=21[ΔR~ik(a~k−bia)+ΔR~ik+1(a~k+1−bia)]
void propagate(double _dt, const Eigen::Vector3d &_acc_1, const Eigen::Vector3d &_gyr_1)
{
dt = _dt;
acc_1 = _acc_1;
gyr_1 = _gyr_1;
Vector3d result_delta_p;
Quaterniond result_delta_q;
Vector3d result_delta_v;
Vector3d result_linearized_ba;
Vector3d result_linearized_bg;
midPointIntegration(_dt, acc_0, gyr_0, _acc_1, _gyr_1, delta_p, delta_q, delta_v,
linearized_ba, linearized_bg,
result_delta_p, result_delta_q, result_delta_v,
result_linearized_ba, result_linearized_bg, 1);
delta_p = result_delta_p;
delta_q = result_delta_q;
delta_v = result_delta_v;
linearized_ba = result_linearized_ba;
linearized_bg = result_linearized_bg;
delta_q.normalize(); // 四元数归一化
sum_dt += dt;
acc_0 = acc_1;
gyr_0 = gyr_1;
}
中值积分
midPointIntegration
函数用于计算预积分的一次递推,即
i
k
→
i
k
+
1
ik\rightarrow ik+1
ik→ik+1,并更新雅可比和协方差。
在VINS-Mono中,预积分噪声设定为零均值高斯分布:
η
i
j
Δ
=
[
δ
ϕ
i
j
,
δ
v
i
j
,
δ
p
i
j
,
δ
b
i
j
a
,
δ
b
i
j
g
]
∼
N
(
0
15
×
1
,
Σ
i
j
)
\eta^\Delta_{ij}=[\delta\phi_{ij},\delta\bold{v}_{ij},\delta\bold{p}_{ij},\delta \mathbf{b}^a_{ij}, \delta\mathbf{b}^g_{ij}] \sim \mathcal N(0_{15\times1},\Sigma_{ij})
ηijΔ=[δϕij,δvij,δpij,δbija,δbijg]∼N(015×1,Σij)
误差传递为:
η
i
k
+
1
Δ
=
F
k
η
i
k
Δ
+
V
k
η
k
d
\eta^\Delta_{ik+1}=\bold{F}_{k}\eta^\Delta_{ik}+\bold{V}_{k}\eta^d_{k}
ηik+1Δ=FkηikΔ+Vkηkd
使用中值积分得到离散化形式如下:
[
δ
p
i
k
+
1
δ
ϕ
i
k
+
1
δ
v
i
k
+
1
δ
b
i
k
+
1
a
δ
b
i
k
+
1
g
]
=
[
I
f
01
Δ
t
I
f
03
f
04
0
f
11
0
0
−
Δ
t
I
0
f
21
I
f
23
f
24
0
0
0
I
0
0
0
0
0
I
]
[
δ
p
i
k
δ
ϕ
i
k
δ
v
i
k
δ
b
i
k
a
δ
b
i
k
g
]
+
[
v
00
v
01
v
02
v
03
0
0
0
Δ
t
2
I
0
Δ
t
2
I
0
0
Δ
R
~
i
k
Δ
t
2
v
21
Δ
R
~
i
k
+
1
Δ
t
2
v
23
0
0
0
0
0
0
Δ
t
I
0
0
0
0
0
0
Δ
t
I
]
[
n
k
a
n
k
g
n
k
+
1
a
n
k
+
1
g
n
k
a
d
n
k
g
d
]
\begin{aligned} \begin{bmatrix} \delta \mathbf{p}_{ik+1} \\ \delta \mathbf{\phi}_{ik+1} \\ \delta\mathbf{v}_{ik+1} \\ \delta{\mathbf{b}}^a_{ik+1} \\ \delta{\mathbf{b}}^g_{ik+1} \end{bmatrix} &= \begin{bmatrix} \mathbf{I} & f_{01} & \Delta t\mathbf{I} & f_{03} & f_{04} \\ 0 & f_{11} & 0 & 0 & -\Delta t\mathbf{I} \\ 0 & f_{21} & \mathbf{I} & f_{23} & f_{24} \\ 0 & 0 & 0 & \mathbf{I} & 0 \\ 0 & 0 & 0 & 0 & \mathbf{I} \end{bmatrix} \begin{bmatrix} \delta \mathbf{p}_{ik} \\ \delta \mathbf{\phi}_{ik} \\ \delta\mathbf{v}_{ik} \\ \delta{\mathbf{b}}^a_{ik} \\ \delta{\mathbf{b}}^g_{ik} \end{bmatrix} \\ &+ \begin{bmatrix} v_{00} & v_{01} & v_{02} & v_{03} & 0 & 0 \\ 0 & \frac{\Delta t}{2}\mathbf{I} & 0 &\frac{\Delta t}{2}\mathbf{I} & 0 & 0 \\ \frac{\Delta \tilde{\bold{R}}_{ik} \Delta t}{2} & v_{21} & \frac{\Delta \tilde{\bold{R}}_{ik+1} \Delta t}{2} & v_{23} & 0 & 0 \\ 0 & 0 & 0 & 0 & \Delta t\mathbf{I} & 0 \\ 0 & 0 & 0 & 0 & 0 & \Delta t\mathbf{I} \end{bmatrix} \begin{bmatrix} \mathbf{n}^a_{k} \\ \mathbf{n}^g_{k} \\ \mathbf{n}^a_{k+1} \\ \mathbf{n}^g_{k+1} \\ \mathbf{n}^{ad}_{k} \\ \mathbf{n}^{gd}_{k} \end{bmatrix} \end{aligned}
⎣
⎡δpik+1δϕik+1δvik+1δbik+1aδbik+1g⎦
⎤=⎣
⎡I0000f01f11f2100ΔtI0I00f030f23I0f04−ΔtIf240I⎦
⎤⎣
⎡δpikδϕikδvikδbikaδbikg⎦
⎤+⎣
⎡v0002ΔR~ikΔt00v012ΔtIv2100v0202ΔR~ik+1Δt00v032ΔtIv2300000ΔtI00000ΔtI⎦
⎤⎣
⎡nkankgnk+1ank+1gnkadnkgd⎦
⎤
其中,矩阵
F
k
\bold{F}_{k}
Fk中的元素如下:
f
01
=
−
1
4
Δ
R
~
i
k
⌊
a
~
k
−
b
i
a
⌋
×
Δ
t
2
−
1
4
Δ
R
~
i
k
+
1
⌊
a
~
k
+
1
−
b
i
a
⌋
×
(
I
−
⌊
ω
^
k
⌋
×
Δ
t
)
Δ
t
2
f
03
=
−
1
4
(
Δ
R
~
i
k
+
Δ
R
~
i
k
+
1
)
Δ
t
2
f
04
=
1
4
Δ
R
~
i
k
+
1
⌊
a
~
k
+
1
−
b
i
a
⌋
×
Δ
t
3
f
11
=
I
−
⌊
ω
^
k
⌋
×
Δ
t
f
21
=
[
−
1
2
Δ
R
~
i
k
⌊
a
~
k
−
b
i
a
⌋
×
−
1
2
Δ
R
~
i
k
+
1
⌊
a
~
k
+
1
−
b
i
a
⌋
×
(
I
−
⌊
ω
^
k
⌋
×
Δ
t
)
]
Δ
t
f
23
=
−
1
2
(
Δ
R
~
i
k
+
Δ
R
~
i
k
+
1
)
Δ
t
f
24
=
1
2
Δ
R
~
i
k
+
1
⌊
a
~
k
+
1
−
b
i
a
⌋
×
Δ
t
2
\begin{aligned} f_{01} &= -\frac{1}{4} \Delta \tilde{\bold{R}}_{ik} \lfloor\tilde{\mathbf{a}}_k-\mathbf{b}^a_i\rfloor_\times \Delta t^2 - \frac{1}{4} \Delta \tilde{\bold{R}}_{ik+1} \lfloor\tilde{\mathbf{a}}_{k+1}-\mathbf{b}^a_i\rfloor_\times (\mathbf{I}-\lfloor \hat \omega_k\rfloor_\times\Delta t)\Delta t^2 \\ f_{03} &= -\frac{1}{4}(\Delta\tilde{\bold{R}}_{ik}+\Delta \tilde{\bold{R}}_{ik+1})\Delta t^2 \\ f_{04} &= \frac{1}{4} \Delta \tilde{\bold{R}}_{ik+1} \lfloor\tilde{\mathbf{a}}_{k+1}-\mathbf{b}^a_i\rfloor_\times \Delta t^3 \\ f_{11} &= \mathbf{I} - \lfloor \hat \omega_k \rfloor_\times \Delta t \\ f_{21} &= \begin{bmatrix} -\frac{1}{2} \Delta \tilde{\bold{R}}_{ik} \lfloor \tilde{\mathbf{a}}_k-\mathbf{b}^a_i \rfloor_\times - \frac{1}{2} \Delta \tilde{\bold{R}}_{ik+1} \lfloor\tilde{\mathbf{a}}_{k+1}-\mathbf{b}^a_i\rfloor_\times (\mathbf{I}-\lfloor \hat \omega_k\rfloor_\times\Delta t) \end{bmatrix} \Delta t \\ f_{23} &= -\frac{1}{2}(\Delta\tilde{\bold{R}}_{ik}+\Delta \tilde{\bold{R}}_{ik+1})\Delta t \\ f_{24} &= \frac{1}{2} \Delta \tilde{\bold{R}}_{ik+1} \lfloor\tilde{\mathbf{a}}_{k+1}-\mathbf{b}^a_i\rfloor_\times \Delta t^2 \end{aligned}
f01f03f04f11f21f23f24=−41ΔR~ik⌊a~k−bia⌋×Δt2−41ΔR~ik+1⌊a~k+1−bia⌋×(I−⌊ω^k⌋×Δt)Δt2=−41(ΔR~ik+ΔR~ik+1)Δt2=41ΔR~ik+1⌊a~k+1−bia⌋×Δt3=I−⌊ω^k⌋×Δt=[−21ΔR~ik⌊a~k−bia⌋×−21ΔR~ik+1⌊a~k+1−bia⌋×(I−⌊ω^k⌋×Δt)]Δt=−21(ΔR~ik+ΔR~ik+1)Δt=21ΔR~ik+1⌊a~k+1−bia⌋×Δt2
矩阵
V
j
−
1
\bold{V}_{j-1}
Vj−1中的元素如下:
v
00
=
1
4
Δ
R
~
i
k
Δ
t
2
v
01
=
−
1
8
Δ
R
~
i
k
+
1
⌊
a
~
k
+
1
−
b
i
a
⌋
×
Δ
t
3
v
02
=
1
4
Δ
R
~
i
k
+
1
Δ
t
2
v
03
=
v
01
v
21
=
−
1
4
Δ
R
~
i
k
+
1
⌊
a
~
k
+
1
−
b
i
a
⌋
×
Δ
t
2
v
23
=
v
21
\begin{aligned} v_{00} &= \frac{1}{4} \Delta\tilde{\bold{R}}_{ik} \Delta t^2 \\ v_{01} &= -\frac{1}{8} \Delta\tilde{\bold{R}}_{ik+1} \lfloor\tilde{\mathbf{a}}_{k+1}-\mathbf{b}^a_i\rfloor_\times \Delta t^3 \\ v_{02} &= \frac{1}{4} \Delta\tilde{\bold{R}}_{ik+1} \Delta t^2 \\ v_{03} &= v_{01} \\ v_{21} &= -\frac{1}{4} \Delta\tilde{\bold{R}}_{ik+1} \lfloor\tilde{\mathbf{a}}_{k+1}-\mathbf{b}^a_i\rfloor_\times \Delta t^2 \\ v_{23} &=v_{21} \end{aligned}
v00v01v02v03v21v23=41ΔR~ikΔt2=−81ΔR~ik+1⌊a~k+1−bia⌋×Δt3=41ΔR~ik+1Δt2=v01=−41ΔR~ik+1⌊a~k+1−bia⌋×Δt2=v21
根据误差传递,可以进一步得到雅可比传递为:
J
i
j
=
F
j
−
1
J
i
j
−
1
\mathbf{J}_{ij}=\mathbf{F}_{j-1} \mathbf{J}_{ij-1}
Jij=Fj−1Jij−1
其中,
J
i
i
=
I
15
×
15
\mathbf{J}_{ii}=\mathbf{I}_{15\times15}
Jii=I15×15。协方差传递为:
Σ
i
j
=
F
j
−
1
Σ
i
j
−
1
F
j
−
1
T
+
V
j
−
1
Σ
n
V
j
−
1
T
\Sigma_{ij}=\bold{F}_{j-1}\Sigma_{ij-1}\bold{F}_{j-1}^T+\bold{V}_{j-1}\Sigma_n\bold{V}_{j-1}^T
Σij=Fj−1Σij−1Fj−1T+Vj−1ΣnVj−1T
其中,
Σ
i
i
=
0
15
×
15
,
Σ
n
=
d
i
a
g
(
η
a
2
,
η
g
2
,
η
a
2
,
η
g
2
,
η
b
a
2
,
η
b
g
2
)
18
×
18
\Sigma_{ii}=\bold{0}_{15\times15},\Sigma_{n}=diag(\eta^2_a,\eta^2_g,\eta^2_a,\eta^2_g,\eta^2_{b_a},\eta^2_{b_g})_{18\times18}
Σii=015×15,Σn=diag(ηa2,ηg2,ηa2,ηg2,ηba2,ηbg2)18×18为IMU测量噪声的协方差。
void midPointIntegration(double _dt,
const Eigen::Vector3d &_acc_0, const Eigen::Vector3d &_gyr_0,
const Eigen::Vector3d &_acc_1, const Eigen::Vector3d &_gyr_1,
const Eigen::Vector3d &delta_p, const Eigen::Quaterniond &delta_q, const Eigen::Vector3d &delta_v,
const Eigen::Vector3d &linearized_ba, const Eigen::Vector3d &linearized_bg,
Eigen::Vector3d &result_delta_p, Eigen::Quaterniond &result_delta_q, Eigen::Vector3d &result_delta_v,
Eigen::Vector3d &result_linearized_ba, Eigen::Vector3d &result_linearized_bg, bool update_jacobian)
{
// 中值积分计算t+1时刻的PVQ预积分项,并认为bias不变
Vector3d un_acc_0 = delta_q * (_acc_0 - linearized_ba);
Vector3d un_gyr = 0.5 * (_gyr_0 + _gyr_1) - linearized_bg;
result_delta_q = delta_q * Quaterniond(1, un_gyr(0) * _dt / 2, un_gyr(1) * _dt / 2, un_gyr(2) * _dt / 2);
Vector3d un_acc_1 = result_delta_q * (_acc_1 - linearized_ba);
Vector3d un_acc = 0.5 * (un_acc_0 + un_acc_1);
result_delta_p = delta_p + delta_v * _dt + 0.5 * un_acc * _dt * _dt;
result_delta_v = delta_v + un_acc * _dt;
result_linearized_ba = linearized_ba;
result_linearized_bg = linearized_bg;
// 更新雅可比和协方差
if(update_jacobian)
{
Vector3d w_x = 0.5 * (_gyr_0 + _gyr_1) - linearized_bg;
Vector3d a_0_x = _acc_0 - linearized_ba;
Vector3d a_1_x = _acc_1 - linearized_ba;
Matrix3d R_w_x, R_a_0_x, R_a_1_x;
//反对称矩阵
R_w_x<<0, -w_x(2), w_x(1),
w_x(2), 0, -w_x(0),
-w_x(1), w_x(0), 0;
R_a_0_x<<0, -a_0_x(2), a_0_x(1),
a_0_x(2), 0, -a_0_x(0),
-a_0_x(1), a_0_x(0), 0;
R_a_1_x<<0, -a_1_x(2), a_1_x(1),
a_1_x(2), 0, -a_1_x(0),
-a_1_x(1), a_1_x(0), 0;
// 计算F矩阵
MatrixXd F = MatrixXd::Zero(15, 15);
F.block<3, 3>(0, 0) = Matrix3d::Identity();
F.block<3, 3>(0, 3) = -0.25 * delta_q.toRotationMatrix() * R_a_0_x * _dt * _dt +
-0.25 * result_delta_q.toRotationMatrix() * R_a_1_x *
(Matrix3d::Identity() - R_w_x * _dt) * _dt * _dt; // f_01
F.block<3, 3>(0, 6) = MatrixXd::Identity(3,3) * _dt;
F.block<3, 3>(0, 9) = -0.25 * (delta_q.toRotationMatrix() +
result_delta_q.toRotationMatrix()) * _dt * _dt; // f_03
F.block<3, 3>(0, 12) = -0.25 * result_delta_q.toRotationMatrix() * R_a_1_x * _dt * _dt * -_dt; // f_04
F.block<3, 3>(3, 3) = Matrix3d::Identity() - R_w_x * _dt; // f_11
F.block<3, 3>(3, 12) = -1.0 * MatrixXd::Identity(3,3) * _dt;
F.block<3, 3>(6, 3) = -0.5 * delta_q.toRotationMatrix() * R_a_0_x * _dt +
-0.5 * result_delta_q.toRotationMatrix() * R_a_1_x *
(Matrix3d::Identity() - R_w_x * _dt) * _dt; // f_21
F.block<3, 3>(6, 6) = Matrix3d::Identity();
F.block<3, 3>(6, 9) = -0.5 * (delta_q.toRotationMatrix() +
result_delta_q.toRotationMatrix()) * _dt; // f_23
F.block<3, 3>(6, 12) = -0.5 * result_delta_q.toRotationMatrix() * R_a_1_x * _dt * -_dt; // f_24
F.block<3, 3>(9, 9) = Matrix3d::Identity();
F.block<3, 3>(12, 12) = Matrix3d::Identity();
// 计算V矩阵
MatrixXd V = MatrixXd::Zero(15,18);
V.block<3, 3>(0, 0) = 0.25 * delta_q.toRotationMatrix() * _dt * _dt; // v_00
V.block<3, 3>(0, 3) = 0.25 * -result_delta_q.toRotationMatrix() * R_a_1_x * _dt * _dt * 0.5 * _dt; // v_01
V.block<3, 3>(0, 6) = 0.25 * result_delta_q.toRotationMatrix() * _dt * _dt; // v_02
V.block<3, 3>(0, 9) = V.block<3, 3>(0, 3); // v_03
V.block<3, 3>(3, 3) = 0.5 * MatrixXd::Identity(3,3) * _dt;
V.block<3, 3>(3, 9) = 0.5 * MatrixXd::Identity(3,3) * _dt;
V.block<3, 3>(6, 0) = 0.5 * delta_q.toRotationMatrix() * _dt;
V.block<3, 3>(6, 3) = 0.5 * -result_delta_q.toRotationMatrix() * R_a_1_x * _dt * 0.5 * _dt; // v_21
V.block<3, 3>(6, 6) = 0.5 * result_delta_q.toRotationMatrix() * _dt;
V.block<3, 3>(6, 9) = V.block<3, 3>(6, 3); // v_23
V.block<3, 3>(9, 12) = MatrixXd::Identity(3,3) * _dt;
V.block<3, 3>(12, 15) = MatrixXd::Identity(3,3) * _dt;
// 更新
jacobian = F * jacobian;
covariance = F * covariance * F.transpose() + V * noise * V.transpose();
}
}
bias更新
在优化过程中bias会更新,repropagate
函数实现了基于新的bias对已有的IMU预积分进行重新递推,函数的输入参数为优化后的bias值。
∂ Δ R ˉ i j ∂ b g = J i j ( 1 , 4 ) = − ∑ k = i j − 1 [ Δ R ~ k + 1 j ( b i ˉ ) T J r k Δ t ] ∂ Δ v ˉ i j ∂ b a = J i j ( 2 , 3 ) = − ∑ k = i j − 1 Δ R ˉ i k Δ t ∂ Δ v ˉ i j ∂ b g = J i j ( 2 , 4 ) = − ∑ k = i j − 1 Δ R ˉ i k ( a ~ k − b ˉ i a ) × ∂ Δ R ˉ i k ∂ b g Δ t ∂ Δ p ˉ i j ∂ b a = J i j ( 0 , 3 ) = ∑ k = i j − 1 ( ∂ Δ v ˉ i k ∂ b a Δ t − 1 2 Δ R ˉ i k Δ t 2 ) ∂ Δ p ˉ i j ∂ b g = J i j ( 0 , 4 ) = ∑ k = i j − 1 ( ∂ Δ v ˉ i k ∂ b g Δ t − 1 2 Δ R ˉ i k ( a ~ k − b ˉ i a ) × ∂ Δ R ˉ i k ∂ b g Δ t 2 ) \begin{aligned} \frac{\partial\Delta\bar{\mathbf{R}}_{ij}}{\partial \mathbf{b}^g}&=\mathbf{J}_{ij}^{(1,4)}=-\sum_{k=i}^{j-1}[\Delta\tilde{\mathbf{R}}_{k+1j}(\bar{\mathbf{b}_i})^T\mathbf{J}_r^k \Delta t] \\ \frac{\partial\Delta\bar{\mathbf{v}}_{ij}}{\partial \mathbf{b}^a} &= \mathbf{J}_{ij}^{(2,3)} = -\sum_{k=i}^{j-1} \Delta\bar{\mathbf{R}}_{ik}\Delta t \\ \frac{\partial\Delta\bar{\mathbf{v}}_{ij}}{\partial \mathbf{b}^g} &= \mathbf{J}_{ij}^{(2,4)} = -\sum_{k=i}^{j-1} \Delta\bar{\mathbf{R}}_{ik} (\tilde{\mathbf{a}}_k-\bar{\mathbf{b}}^a_i)_\times \frac{\partial\Delta\bar{\mathbf{R}}_{ik}}{\partial \mathbf{b}^g} \Delta t \\ \frac{\partial\Delta\bar{\mathbf{p}}_{ij}}{\partial \mathbf{b}^a} &= \mathbf{J}_{ij}^{(0,3)} = \sum_{k=i}^{j-1} (\frac{\partial\Delta\bar{\mathbf{v}}_{ik}}{\partial \mathbf{b}^a}\Delta t-\frac{1}{2}\Delta\bar{\mathbf{R}}_{ik}\Delta t^2) \\ \frac{\partial\Delta\bar{\mathbf{p}}_{ij}}{\partial \mathbf{b}^g} &= \mathbf{J}_{ij}^{(0,4)} = \sum_{k=i}^{j-1} (\frac{\partial\Delta\bar{\mathbf{v}}_{ik}}{\partial \mathbf{b}^g}\Delta t - \frac{1}{2}\Delta\bar{\mathbf{R}}_{ik} (\tilde{\mathbf{a}}_k-\bar{\mathbf{b}}^a_i)_\times \frac{\partial\Delta\bar{\mathbf{R}}_{ik}}{\partial \mathbf{b}^g} \Delta t^2) \end{aligned} ∂bg∂ΔRˉij∂ba∂Δvˉij∂bg∂Δvˉij∂ba∂Δpˉij∂bg∂Δpˉij=Jij(1,4)=−k=i∑j−1[ΔR~k+1j(biˉ)TJrkΔt]=Jij(2,3)=−k=i∑j−1ΔRˉikΔt=Jij(2,4)=−k=i∑j−1ΔRˉik(a~k−bˉia)×∂bg∂ΔRˉikΔt=Jij(0,3)=k=i∑j−1(∂ba∂ΔvˉikΔt−21ΔRˉikΔt2)=Jij(0,4)=k=i∑j−1(∂bg∂ΔvˉikΔt−21ΔRˉik(a~k−bˉia)×∂bg∂ΔRˉikΔt2)
void repropagate(const Eigen::Vector3d &_linearized_ba, const Eigen::Vector3d &_linearized_bg)
{
// 重置状态量
sum_dt = 0.0;
acc_0 = linearized_acc;
gyr_0 = linearized_gyr;
delta_p.setZero();
delta_q.setIdentity();
delta_v.setZero();
linearized_ba = _linearized_ba;
linearized_bg = _linearized_bg;
jacobian.setIdentity();
covariance.setZero();
// 对[i,j]两帧间的IMU预积分进行重新计算
for (int i = 0; i < static_cast<int>(dt_buf.size()); i++)
propagate(dt_buf[i], acc_buf[i], gyr_buf[i]);
}
void repropagate(const Eigen::Vector3d &_linearized_ba, const Eigen::Vector3d &_linearized_bg)
{
// 重置状态量
sum_dt = 0.0;
acc_0 = linearized_acc;
gyr_0 = linearized_gyr;
delta_p.setZero();
delta_q.setIdentity();
delta_v.setZero();
linearized_ba = _linearized_ba;
linearized_bg = _linearized_bg;
jacobian.setIdentity();
covariance.setZero();
// 对[i,j]两帧间的IMU预积分进行重新计算
for (int i = 0; i < static_cast<int>(dt_buf.size()); i++)
propagate(dt_buf[i], acc_buf[i], gyr_buf[i]);
}
IMU因子
evaluate
函数计算IMU预积分残差。
Eigen::Matrix<double, 15, 1> evaluate(const Eigen::Vector3d &Pi, const Eigen::Quaterniond &Qi, const Eigen::Vector3d &Vi, const Eigen::Vector3d &Bai, const Eigen::Vector3d &Bgi,
const Eigen::Vector3d &Pj, const Eigen::Quaterniond &Qj, const Eigen::Vector3d &Vj, const Eigen::Vector3d &Baj, const Eigen::Vector3d &Bgj)
{
Eigen::Matrix<double, 15, 1> residuals;
// 预积分项关于bias的雅可比
Eigen::Matrix3d dp_dba = jacobian.block<3, 3>(O_P, O_BA);
Eigen::Matrix3d dp_dbg = jacobian.block<3, 3>(O_P, O_BG);
Eigen::Matrix3d dq_dbg = jacobian.block<3, 3>(O_R, O_BG);
Eigen::Matrix3d dv_dba = jacobian.block<3, 3>(O_V, O_BA);
Eigen::Matrix3d dv_dbg = jacobian.block<3, 3>(O_V, O_BG);
// bias更新量
Eigen::Vector3d dba = Bai - linearized_ba;
Eigen::Vector3d dbg = Bgi - linearized_bg;
// 预积分关于bias的线性化修正(对应3.3节)
Eigen::Quaterniond corrected_delta_q = delta_q * Utility::deltaQ(dq_dbg * dbg);
Eigen::Vector3d corrected_delta_v = delta_v + dv_dba * dba + dv_dbg * dbg;
Eigen::Vector3d corrected_delta_p = delta_p + dp_dba * dba + dp_dbg * dbg;
// 计算优化残差(对应3.4节,注意使用修正后的预积分项)
residuals.block<3, 1>(O_P, 0) = Qi.inverse() * (0.5 * G * sum_dt * sum_dt + Pj - Pi - Vi * sum_dt) - corrected_delta_p;
residuals.block<3, 1>(O_R, 0) = 2 * (corrected_delta_q.inverse() * (Qi.inverse() * Qj)).vec();
residuals.block<3, 1>(O_V, 0) = Qi.inverse() * (G * sum_dt + Vj - Vi) - corrected_delta_v;
residuals.block<3, 1>(O_BA, 0) = Baj - Bai;
residuals.block<3, 1>(O_BG, 0) = Bgj - Bgi;
return residuals;
}
IMUFactor::Evaluate
函数计算优化变量的雅可比。
virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const
{
// 优化变量
Eigen::Vector3d Pi(parameters[0][0], parameters[0][1], parameters[0][2]);
Eigen::Quaterniond Qi(parameters[0][6], parameters[0][3], parameters[0][4], parameters[0][5]);
Eigen::Vector3d Vi(parameters[1][0], parameters[1][1], parameters[1][2]);
Eigen::Vector3d Bai(parameters[1][3], parameters[1][4], parameters[1][5]);
Eigen::Vector3d Bgi(parameters[1][6], parameters[1][7], parameters[1][8]);
Eigen::Vector3d Pj(parameters[2][0], parameters[2][1], parameters[2][2]);
Eigen::Quaterniond Qj(parameters[2][6], parameters[2][3], parameters[2][4], parameters[2][5]);
Eigen::Vector3d Vj(parameters[3][0], parameters[3][1], parameters[3][2]);
Eigen::Vector3d Baj(parameters[3][3], parameters[3][4], parameters[3][5]);
Eigen::Vector3d Bgj(parameters[3][6], parameters[3][7], parameters[3][8]);
#if 0
if ((Bai - pre_integration->linearized_ba).norm() > 0.10 ||
(Bgi - pre_integration->linearized_bg).norm() > 0.01)
{
pre_integration->repropagate(Bai, Bgi);
}
#endif
// 计算预积分残差
Eigen::Map<Eigen::Matrix<double, 15, 1>> residual(residuals);
residual = pre_integration->evaluate(Pi, Qi, Vi, Bai, Bgi,
Pj, Qj, Vj, Baj, Bgj);
Eigen::Matrix<double, 15, 15> sqrt_info = Eigen::LLT<Eigen::Matrix<double, 15, 15>>(pre_integration->covariance.inverse()).matrixL().transpose();
residual = sqrt_info * residual;
// 计算雅可比
if (jacobians)
{
double sum_dt = pre_integration->sum_dt;
Eigen::Matrix3d dp_dba = pre_integration->jacobian.template block<3, 3>(O_P, O_BA);
Eigen::Matrix3d dp_dbg = pre_integration->jacobian.template block<3, 3>(O_P, O_BG);
Eigen::Matrix3d dq_dbg = pre_integration->jacobian.template block<3, 3>(O_R, O_BG);
Eigen::Matrix3d dv_dba = pre_integration->jacobian.template block<3, 3>(O_V, O_BA);
Eigen::Matrix3d dv_dbg = pre_integration->jacobian.template block<3, 3>(O_V, O_BG);
if (pre_integration->jacobian.maxCoeff() > 1e8 || pre_integration->jacobian.minCoeff() < -1e8)
{
ROS_WARN("numerical unstable in preintegration");
}
if (jacobians[0])
{
Eigen::Map<Eigen::Matrix<double, 15, 7, Eigen::RowMajor>> jacobian_pose_i(jacobians[0]);
jacobian_pose_i.setZero();
jacobian_pose_i.block<3, 3>(O_P, O_P) = -Qi.inverse().toRotationMatrix();
jacobian_pose_i.block<3, 3>(O_P, O_R) = Utility::skewSymmetric(Qi.inverse() * (0.5 * G * sum_dt * sum_dt + Pj - Pi - Vi * sum_dt));
#if 0
jacobian_pose_i.block<3, 3>(O_R, O_R) = -(Qj.inverse() * Qi).toRotationMatrix();
#else
Eigen::Quaterniond corrected_delta_q = pre_integration->delta_q * Utility::deltaQ(dq_dbg * (Bgi - pre_integration->linearized_bg));
jacobian_pose_i.block<3, 3>(O_R, O_R) = -(Utility::Qleft(Qj.inverse() * Qi) * Utility::Qright(corrected_delta_q)).bottomRightCorner<3, 3>();
#endif
jacobian_pose_i.block<3, 3>(O_V, O_R) = Utility::skewSymmetric(Qi.inverse() * (G * sum_dt + Vj - Vi));
jacobian_pose_i = sqrt_info * jacobian_pose_i;
if (jacobian_pose_i.maxCoeff() > 1e8 || jacobian_pose_i.minCoeff() < -1e8)
{
ROS_WARN("numerical unstable in preintegration");
}
}
if (jacobians[1])
{
Eigen::Map<Eigen::Matrix<double, 15, 9, Eigen::RowMajor>> jacobian_speedbias_i(jacobians[1]);
jacobian_speedbias_i.setZero();
jacobian_speedbias_i.block<3, 3>(O_P, O_V - O_V) = -Qi.inverse().toRotationMatrix() * sum_dt;
jacobian_speedbias_i.block<3, 3>(O_P, O_BA - O_V) = -dp_dba;
jacobian_speedbias_i.block<3, 3>(O_P, O_BG - O_V) = -dp_dbg;
#if 0
jacobian_speedbias_i.block<3, 3>(O_R, O_BG - O_V) = -dq_dbg;
#else
jacobian_speedbias_i.block<3, 3>(O_R, O_BG - O_V) = -Utility::Qleft(Qj.inverse() * Qi * pre_integration->delta_q).bottomRightCorner<3, 3>() * dq_dbg;
#endif
jacobian_speedbias_i.block<3, 3>(O_V, O_V - O_V) = -Qi.inverse().toRotationMatrix();
jacobian_speedbias_i.block<3, 3>(O_V, O_BA - O_V) = -dv_dba;
jacobian_speedbias_i.block<3, 3>(O_V, O_BG - O_V) = -dv_dbg;
jacobian_speedbias_i.block<3, 3>(O_BA, O_BA - O_V) = -Eigen::Matrix3d::Identity();
jacobian_speedbias_i.block<3, 3>(O_BG, O_BG - O_V) = -Eigen::Matrix3d::Identity();
jacobian_speedbias_i = sqrt_info * jacobian_speedbias_i;
}
if (jacobians[2])
{
Eigen::Map<Eigen::Matrix<double, 15, 7, Eigen::RowMajor>> jacobian_pose_j(jacobians[2]);
jacobian_pose_j.setZero();
jacobian_pose_j.block<3, 3>(O_P, O_P) = Qi.inverse().toRotationMatrix();
#if 0
jacobian_pose_j.block<3, 3>(O_R, O_R) = Eigen::Matrix3d::Identity();
#else
Eigen::Quaterniond corrected_delta_q = pre_integration->delta_q * Utility::deltaQ(dq_dbg * (Bgi - pre_integration->linearized_bg));
jacobian_pose_j.block<3, 3>(O_R, O_R) = Utility::Qleft(corrected_delta_q.inverse() * Qi.inverse() * Qj).bottomRightCorner<3, 3>();
#endif
jacobian_pose_j = sqrt_info * jacobian_pose_j;
}
if (jacobians[3])
{
Eigen::Map<Eigen::Matrix<double, 15, 9, Eigen::RowMajor>> jacobian_speedbias_j(jacobians[3]);
jacobian_speedbias_j.setZero();
jacobian_speedbias_j.block<3, 3>(O_V, O_V - O_V) = Qi.inverse().toRotationMatrix();
jacobian_speedbias_j.block<3, 3>(O_BA, O_BA - O_V) = Eigen::Matrix3d::Identity();
jacobian_speedbias_j.block<3, 3>(O_BG, O_BG - O_V) = Eigen::Matrix3d::Identity();
jacobian_speedbias_j = sqrt_info * jacobian_speedbias_j;
}
}
return true;
}
5 代码实现(ORB_SLAM3)
Preintegrated类
Preintegrated
类是ORB_SLAM3中用于处理IMU预积分的类,包含的成员变量如下:
float dT; //预积分总时长\Delta t_{ij}
Eigen::Matrix<float,15,15> C; // 噪声协方差 \Sigma_{ij}, \Sigma_{\eta}
Eigen::Matrix<float,15,15> Info;
Eigen::DiagonalMatrix<float,6> Nga, NgaWalk;
// Values for the original bias (when integration was computed)
Bias b;
Eigen::Matrix3f dR;
Eigen::Vector3f dV, dP;
Eigen::Matrix3f JRg, JVg, JVa, JPg, JPa;
Eigen::Vector3f avgA, avgW;
预积分传递
在ORB_SLAM3中,预积分传递使用欧拉积分计算,由IntegrateNewMeasurement
函数实现。
void Preintegrated::IntegrateNewMeasurement(const Eigen::Vector3f &acceleration, const Eigen::Vector3f &angVel, const float &dt)
{
mvMeasurements.push_back(integrable(acceleration,angVel,dt));
// Position is updated firstly, as it depends on previously computed velocity and rotation.
// Velocity is updated secondly, as it depends on previously computed rotation.
// Rotation is the last to be updated.
//Matrices to compute covariance
Eigen::Matrix<float,9,9> A;
A.setIdentity();
Eigen::Matrix<float,9,6> B;
B.setZero();
Eigen::Vector3f acc, accW;
acc << acceleration(0)-b.bax, acceleration(1)-b.bay, acceleration(2)-b.baz;
accW << angVel(0)-b.bwx, angVel(1)-b.bwy, angVel(2)-b.bwz;
avgA = (dT*avgA + dR*acc*dt)/(dT+dt);
avgW = (dT*avgW + accW*dt)/(dT+dt);
// Update delta position dP and velocity dV (rely on no-updated delta rotation)
dP = dP + dV*dt + 0.5f*dR*acc*dt*dt;
dV = dV + dR*acc*dt;
// Compute velocity and position parts of matrices A and B (rely on non-updated delta rotation)
Eigen::Matrix<float,3,3> Wacc = Sophus::SO3f::hat(acc);
A.block<3,3>(3,0) = -dR*dt*Wacc;
A.block<3,3>(6,0) = -0.5f*dR*dt*dt*Wacc;
A.block<3,3>(6,3) = Eigen::DiagonalMatrix<float,3>(dt, dt, dt);
B.block<3,3>(3,3) = dR*dt;
B.block<3,3>(6,3) = 0.5f*dR*dt*dt;
// Update position and velocity jacobians wrt bias correction
JPa = JPa + JVa*dt -0.5f*dR*dt*dt;
JPg = JPg + JVg*dt -0.5f*dR*dt*dt*Wacc*JRg;
JVa = JVa - dR*dt;
JVg = JVg - dR*dt*Wacc*JRg;
// Update delta rotation
IntegratedRotation dRi(angVel,b,dt);
dR = NormalizeRotation(dR*dRi.deltaR);
// Compute rotation parts of matrices A and B
A.block<3,3>(0,0) = dRi.deltaR.transpose();
B.block<3,3>(0,0) = dRi.rightJ*dt;
// Update covariance
C.block<9,9>(0,0) = A * C.block<9,9>(0,0) * A.transpose() + B*Nga*B.transpose();
C.block<6,6>(9,9) += NgaWalk;
// Update rotation jacobian wrt bias correction
JRg = dRi.deltaR.transpose()*JRg - dRi.rightJ*dt;
// Total integrated time
dT += dt;
}
bias更新
GetDelta***
和 GetUpdatedDelta***
函数实现了bias更新。
Eigen::Vector3f Preintegrated::GetDeltaVelocity(const Bias &b_)
{
std::unique_lock<std::mutex> lock(mMutex);
Eigen::Vector3f dbg, dba;
dbg << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz;
dba << b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz;
return dV + JVg * dbg + JVa * dba;
}
Eigen::Vector3f Preintegrated::GetUpdatedDeltaVelocity()
{
std::unique_lock<std::mutex> lock(mMutex);
return dV + JVg * db.head(3) + JVa * db.tail(3);
}
IMU因子
ORB_SLAM3中的IMU因子及雅可比计算放在G2oType.cc中。其中,EdgeInertial::computeError
函数实现了IMU残差的计算。
r
I
i
j
=
[
r
Δ
R
i
j
,
r
Δ
v
i
j
,
r
Δ
p
i
j
]
∈
R
9
\bold{r}_{\mathcal I_{ij}}=[\bold{r}_{\Delta\bold{R}_{ij}}, \bold{r}_{\Delta\bold{v}_{ij}},\bold{r}_{\Delta\bold{p}_{ij}}]\in \mathbb R^9
rIij=[rΔRij,rΔvij,rΔpij]∈R9
void EdgeInertial::computeError()
{
// TODO Maybe Reintegrate inertial measurments when difference between linearization point and current estimate is too big
const VertexPose* VP1 = static_cast<const VertexPose*>(_vertices[0]);
const VertexVelocity* VV1= static_cast<const VertexVelocity*>(_vertices[1]);
const VertexGyroBias* VG1= static_cast<const VertexGyroBias*>(_vertices[2]);
const VertexAccBias* VA1= static_cast<const VertexAccBias*>(_vertices[3]);
const VertexPose* VP2 = static_cast<const VertexPose*>(_vertices[4]);
const VertexVelocity* VV2 = static_cast<const VertexVelocity*>(_vertices[5]);
const IMU::Bias b1(VA1->estimate()[0],VA1->estimate()[1],VA1->estimate()[2],VG1->estimate()[0],VG1->estimate()[1],VG1->estimate()[2]);
const Eigen::Matrix3d dR = mpInt->GetDeltaRotation(b1).cast<double>();
const Eigen::Vector3d dV = mpInt->GetDeltaVelocity(b1).cast<double>();
const Eigen::Vector3d dP = mpInt->GetDeltaPosition(b1).cast<double>();
const Eigen::Vector3d er = LogSO3(dR.transpose()*VP1->estimate().Rwb.transpose()*VP2->estimate().Rwb);
const Eigen::Vector3d ev = VP1->estimate().Rwb.transpose()*(VV2->estimate() - VV1->estimate() - g*dt) - dV;
const Eigen::Vector3d ep = VP1->estimate().Rwb.transpose()*(VP2->estimate().twb - VP1->estimate().twb
- VV1->estimate()*dt - g*dt*dt/2) - dP;
_error << er, ev, ep;
}
EdgeInertial::linearizeOplus
函数计算了残差关于优化变量的雅可比。
J
[
0
]
9
×
6
=
[
∂
r
I
i
j
∂
R
i
,
∂
r
I
i
j
∂
p
i
]
=
[
∂
r
Δ
R
i
j
∂
R
i
∂
r
Δ
R
i
j
∂
p
i
∂
r
Δ
v
i
j
∂
R
i
∂
r
Δ
v
i
j
∂
p
i
∂
r
Δ
p
i
j
∂
R
i
∂
r
Δ
p
i
j
∂
p
i
]
=
[
−
J
r
−
1
(
r
Δ
R
i
j
)
R
j
T
R
i
0
[
R
i
T
(
v
j
−
v
i
−
g
Δ
t
i
j
)
]
∧
0
[
R
i
T
(
p
j
−
p
i
−
v
i
Δ
t
i
j
−
1
2
g
Δ
t
i
j
2
)
]
∧
−
I
]
\begin{aligned} \mathbf{J}[0]_{9\times6}&=[\frac{\partial \bold{r}_{\mathcal I_{ij}}}{\partial \mathbf{R}_i},\frac{\partial \bold{r}_{\mathcal I_{ij}}}{\partial \mathbf{p}_i}] = \begin{bmatrix} \frac{\partial \bold{r}_{\Delta\bold{R}_{ij}}}{\partial \mathbf{R}_i} & \frac{\partial \bold{r}_{\Delta\bold{R}_{ij}}}{\partial \mathbf{p}_i} \\ \frac{\partial \bold{r}_{\Delta\bold{v}_{ij}}}{\partial \mathbf{R}_i} & \frac{\partial \bold{r}_{\Delta\bold{v}_{ij}}}{\partial \mathbf{p}_i} \\ \frac{\partial \bold{r}_{\Delta\bold{p}_{ij}}}{\partial \mathbf{R}_i} & \frac{\partial \bold{r}_{\Delta\bold{p}_{ij}}}{\partial \mathbf{p}_i} \end{bmatrix} \\ &= \begin{bmatrix} -\mathbf{J}^{-1}_{r}(\bold{r}_{\Delta\bold{R}_{ij}})\mathbf{R}^T_j\mathbf{R}_i & \mathbf{0} \\ [\mathbf{R}^T_i(\mathbf{v}_j-\mathbf{v}_i-\mathbf{g}\Delta t_{ij})]^\wedge & \mathbf{0} \\ [\mathbf{R}^T_i(\mathbf{p}_j-\mathbf{p}_i- \mathbf{v}_i\Delta t_{ij}-\frac{1}{2}\mathbf{g}\Delta t_{ij}^2)]^\wedge & -\mathbf{I} \end{bmatrix} \end{aligned}
J[0]9×6=[∂Ri∂rIij,∂pi∂rIij]=⎣
⎡∂Ri∂rΔRij∂Ri∂rΔvij∂Ri∂rΔpij∂pi∂rΔRij∂pi∂rΔvij∂pi∂rΔpij⎦
⎤=⎣
⎡−Jr−1(rΔRij)RjTRi[RiT(vj−vi−gΔtij)]∧[RiT(pj−pi−viΔtij−21gΔtij2)]∧00−I⎦
⎤
J [ 1 ] 9 × 3 = ∂ r I i j ∂ v i = [ ∂ r Δ R i j ∂ v i ∂ r Δ v i j ∂ v i ∂ r Δ p i j ∂ v i ] = [ 0 − R i T − R i T Δ t i j ] J [ 2 ] 9 × 3 = ∂ r I i j ∂ b i g = [ ∂ r Δ R i j ∂ b i g ∂ r Δ v i j ∂ b i g ∂ r Δ p i j ∂ b i g ] = [ − J r − 1 ( r Δ R i j ) Exp ( r Δ R i j ) T J r ( ∂ Δ R ˉ i j ∂ b g δ b g ) ∂ Δ R ˉ i j ∂ b g − ∂ Δ v ˉ i j ∂ b g − ∂ Δ p ˉ i j ∂ b g ] J [ 3 ] 9 × 3 = ∂ r I i j ∂ b i a = [ ∂ r Δ R i j ∂ b i a ∂ r Δ v i j ∂ b i a ∂ r Δ p i j ∂ b i a ] = [ 0 − ∂ Δ v ˉ i j ∂ b a − ∂ Δ p ˉ i j ∂ b a ] \begin{aligned} \mathbf{J}[1]_{9\times3}&=\frac{\partial \bold{r}_{\mathcal I_{ij}}}{\partial \mathbf{v}_i} = \begin{bmatrix} \frac{\partial \bold{r}_{\Delta\bold{R}_{ij}}}{\partial \mathbf{v}_i} \\ \frac{\partial \bold{r}_{\Delta\bold{v}_{ij}}}{\partial \mathbf{v}_i} \\ \frac{\partial \bold{r}_{\Delta\bold{p}_{ij}}}{\partial \mathbf{v}_i} \end{bmatrix} = \begin{bmatrix}\mathbf{0}\\ -\mathbf{R}^T_i \\ -\mathbf{R}^T_i\Delta t_{ij} \end{bmatrix} \\ \mathbf{J}[2]_{9\times3} &=\frac{\partial \bold{r}_{\mathcal I_{ij}}}{\partial \mathbf{b}^g_i} = \begin{bmatrix} \frac{\partial \bold{r}_{\Delta\bold{R}_{ij}}}{\partial \mathbf{b}^g_i} \\ \frac{\partial \bold{r}_{\Delta\bold{v}_{ij}}}{\partial \mathbf{b}^g_i} \\ \frac{\partial \bold{r}_{\Delta\bold{p}_{ij}}}{\partial \mathbf{b}^g_i} \end{bmatrix} = \begin{bmatrix} -\mathbf{J}^{-1}_{r}(\bold{r}_{\Delta\bold{R}_{ij}})\text{Exp}(\bold{r}_{\Delta\bold{R}_{ij}})^T\mathbf{J}_r(\frac{\partial \Delta\bar{\bold{R}}_{ij}}{\partial \mathbf{b}^g}\delta\mathbf{b}^g)\frac{\partial \Delta\bar{\bold{R}}_{ij}}{\partial \mathbf{b}^g} \\ -\frac{\partial \Delta\bar{\bold{v}}_{ij}}{\partial \mathbf{b}^g} \\ -\frac{\partial \Delta\bar{\bold{p}}_{ij}}{\partial \mathbf{b}^g} \end{bmatrix} \\ \mathbf{J}[3]_{9\times3} &=\frac{\partial \bold{r}_{\mathcal I_{ij}}}{\partial \mathbf{b}^a_i} = \begin{bmatrix}\frac{\partial \bold{r}_{\Delta\bold{R}_{ij}}}{\partial \mathbf{b}^a_i} \\\frac{\partial \bold{r}_{\Delta\bold{v}_{ij}}}{\partial \mathbf{b}^a_i} \\\frac{\partial \bold{r}_{\Delta\bold{p}_{ij}}}{\partial \mathbf{b}^a_i}\end{bmatrix} = \begin{bmatrix} \mathbf{0} \\ -\frac{\partial \Delta\bar{\bold{v}}_{ij}}{\partial \mathbf{b}^a} \\ -\frac{\partial \Delta\bar{\bold{p}}_{ij}}{\partial \mathbf{b}^a} \end{bmatrix} \end{aligned} J[1]9×3J[2]9×3J[3]9×3=∂vi∂rIij=⎣ ⎡∂vi∂rΔRij∂vi∂rΔvij∂vi∂rΔpij⎦ ⎤=⎣ ⎡0−RiT−RiTΔtij⎦ ⎤=∂big∂rIij=⎣ ⎡∂big∂rΔRij∂big∂rΔvij∂big∂rΔpij⎦ ⎤=⎣ ⎡−Jr−1(rΔRij)Exp(rΔRij)TJr(∂bg∂ΔRˉijδbg)∂bg∂ΔRˉij−∂bg∂Δvˉij−∂bg∂Δpˉij⎦ ⎤=∂bia∂rIij=⎣ ⎡∂bia∂rΔRij∂bia∂rΔvij∂bia∂rΔpij⎦ ⎤=⎣ ⎡0−∂ba∂Δvˉij−∂ba∂Δpˉij⎦ ⎤
J [ 4 ] 9 × 6 = [ ∂ r I i j ∂ R j , ∂ r I i j ∂ p j ] = [ ∂ r Δ R i j ∂ R j ∂ r Δ R i j ∂ p j ∂ r Δ v i j ∂ R j ∂ r Δ v i j ∂ p j ∂ r Δ p i j ∂ R j ∂ r Δ p i j ∂ p j ] = [ J r − 1 ( r Δ R i j ) 0 0 0 0 R i T R j ] J [ 5 ] 9 × 3 = ∂ r I i j ∂ v j = [ ∂ r Δ R i j ∂ v j ∂ r Δ v i j ∂ v j ∂ r Δ p i j ∂ v j ] = [ 0 R i T 0 ] \begin{aligned} \mathbf{J}[4]_{9\times6}&=[\frac{\partial \bold{r}_{\mathcal I_{ij}}}{\partial \mathbf{R}_j},\frac{\partial \bold{r}_{\mathcal I_{ij}}}{\partial \mathbf{p}_j}] = \begin{bmatrix} \frac{\partial \bold{r}_{\Delta\bold{R}_{ij}}}{\partial \mathbf{R}_j} & \frac{\partial \bold{r}_{\Delta\bold{R}_{ij}}}{\partial \mathbf{p}_j} \\ \frac{\partial \bold{r}_{\Delta\bold{v}_{ij}}}{\partial \mathbf{R}_j} & \frac{\partial \bold{r}_{\Delta\bold{v}_{ij}}}{\partial \mathbf{p}_j} \\ \frac{\partial \bold{r}_{\Delta\bold{p}_{ij}}}{\partial \mathbf{R}_j} & \frac{\partial \bold{r}_{\Delta\bold{p}_{ij}}}{\partial \mathbf{p}_j} \end{bmatrix} \\ &= \begin{bmatrix} \mathbf{J}^{-1}_r(\bold{r}_{\Delta\bold{R}_{ij}}) & \mathbf{0} \\ \mathbf{0} & \mathbf{0} \\ \mathbf{0} & \mathbf{R}^T_i\mathbf{R}_j \end{bmatrix} \\ \mathbf{J}[5]_{9\times3} &=\frac{\partial \bold{r}_{\mathcal I_{ij}}}{\partial \mathbf{v}_j} = \begin{bmatrix}\frac{\partial \bold{r}_{\Delta\bold{R}_{ij}}}{\partial \mathbf{v}_j} \\\frac{\partial \bold{r}_{\Delta\bold{v}_{ij}}}{\partial \mathbf{v}_j} \\\frac{\partial \bold{r}_{\Delta\bold{p}_{ij}}}{\partial \mathbf{v}_j}\end{bmatrix} = \begin{bmatrix} \mathbf{0} \\ \mathbf{R}^T_i \\ \mathbf{0} \end{bmatrix} \end{aligned} J[4]9×6J[5]9×3=[∂Rj∂rIij,∂pj∂rIij]=⎣ ⎡∂Rj∂rΔRij∂Rj∂rΔvij∂Rj∂rΔpij∂pj∂rΔRij∂pj∂rΔvij∂pj∂rΔpij⎦ ⎤=⎣ ⎡Jr−1(rΔRij)0000RiTRj⎦ ⎤=∂vj∂rIij=⎣ ⎡∂vj∂rΔRij∂vj∂rΔvij∂vj∂rΔpij⎦ ⎤=⎣ ⎡0RiT0⎦ ⎤
void EdgeInertial::linearizeOplus()
{
const VertexPose* VP1 = static_cast<const VertexPose*>(_vertices[0]);
const VertexVelocity* VV1= static_cast<const VertexVelocity*>(_vertices[1]);
const VertexGyroBias* VG1= static_cast<const VertexGyroBias*>(_vertices[2]);
const VertexAccBias* VA1= static_cast<const VertexAccBias*>(_vertices[3]);
const VertexPose* VP2 = static_cast<const VertexPose*>(_vertices[4]);
const VertexVelocity* VV2= static_cast<const VertexVelocity*>(_vertices[5]);
const IMU::Bias b1(VA1->estimate()[0],VA1->estimate()[1],VA1->estimate()[2],VG1->estimate()[0],VG1->estimate()[1],VG1->estimate()[2]);
const IMU::Bias db = mpInt->GetDeltaBias(b1);
Eigen::Vector3d dbg;
dbg << db.bwx, db.bwy, db.bwz;
const Eigen::Matrix3d Rwb1 = VP1->estimate().Rwb;
const Eigen::Matrix3d Rbw1 = Rwb1.transpose();
const Eigen::Matrix3d Rwb2 = VP2->estimate().Rwb;
const Eigen::Matrix3d dR = mpInt->GetDeltaRotation(b1).cast<double>();
const Eigen::Matrix3d eR = dR.transpose()*Rbw1*Rwb2;
const Eigen::Vector3d er = LogSO3(eR);
const Eigen::Matrix3d invJr = InverseRightJacobianSO3(er);
// Jacobians wrt Pose 1
_jacobianOplus[0].setZero();
// rotation
_jacobianOplus[0].block<3,3>(0,0) = -invJr*Rwb2.transpose()*Rwb1; // OK
_jacobianOplus[0].block<3,3>(3,0) = Sophus::SO3d::hat(Rbw1*(VV2->estimate() - VV1->estimate() - g*dt)); // OK
_jacobianOplus[0].block<3,3>(6,0) = Sophus::SO3d::hat(Rbw1*(VP2->estimate().twb - VP1->estimate().twb
- VV1->estimate()*dt - 0.5*g*dt*dt)); // OK
// translation
_jacobianOplus[0].block<3,3>(6,3) = -Eigen::Matrix3d::Identity(); // OK
// Jacobians wrt Velocity 1
_jacobianOplus[1].setZero();
_jacobianOplus[1].block<3,3>(3,0) = -Rbw1; // OK
_jacobianOplus[1].block<3,3>(6,0) = -Rbw1*dt; // OK
// Jacobians wrt Gyro 1
_jacobianOplus[2].setZero();
_jacobianOplus[2].block<3,3>(0,0) = -invJr*eR.transpose()*RightJacobianSO3(JRg*dbg)*JRg; // OK
_jacobianOplus[2].block<3,3>(3,0) = -JVg; // OK
_jacobianOplus[2].block<3,3>(6,0) = -JPg; // OK
// Jacobians wrt Accelerometer 1
_jacobianOplus[3].setZero();
_jacobianOplus[3].block<3,3>(3,0) = -JVa; // OK
_jacobianOplus[3].block<3,3>(6,0) = -JPa; // OK
// Jacobians wrt Pose 2
_jacobianOplus[4].setZero();
// rotation
_jacobianOplus[4].block<3,3>(0,0) = invJr; // OK
// translation
_jacobianOplus[4].block<3,3>(6,3) = Rbw1*Rwb2; // OK
// Jacobians wrt Velocity 2
_jacobianOplus[5].setZero();
_jacobianOplus[5].block<3,3>(3,0) = Rbw1; // OK
}
[参考文献]
[1] IMU Preintegration on Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation
[2] VINS-Mono: A Robust and Versatile Monocular Visual-Inertial State Estimator
[3] ORB-SLAM3: An Accurate Open-Source Library for Visual, Visual-Inertial and Multi-Map SLAM