ORB_SLAM3_IMU预积分理论推导(预积分项)
误差
1.确定性误差
- Bias:偏置
- Scale:实际数值和传感器输出值之间的比值。
- Misalignment:非正交误差。
- 标定的方法:
六面法
标定加速度
。
2.随机误差
- Allan方差
- 随机游走
IMU器件测量模型
1.角标符号说明
b
:body坐标系a
:加速计(acc)g
:陀螺仪(gyro)w
:世界坐标系d
:离散(discrete)
2.假设
- 假设:地球是静止的,忽略自转,运行平面为水平面,重力指向固定,模值恒定。
- 运行场景小;
- 运行时间短;
- 精度低(mems);
3.测量模型(gyro/acc)
- 陀螺仪
ω~wbb(t)=ωwbb(t)+bg(t)+ηg(t)\\tilde{\\omega } ^{b}_{wb}\\left ( t \\right ) = \\omega ^{b}_{wb}\\left ( t \\right ) +b_g\\left ( t\\right ) +\\eta _g\\left ( t \\right ) ω~wbb(t)=ωwbb(t)+bg(t)+ηg(t) - 加速计
ab(t)=RbwT(aw−gw)+ba(t)+ηa(t)a^b\\left ( t \\right ) = {\\color{Red} R_{b}^{wT}} \\left ( a^{w}-g^{w} \\right ) +b_a\\left ( t\\right ) +\\eta _a \\left( t \\right ) ab(t)=RbwT(aw−gw)+ba(t)+ηa(t)
- ω~,ab(t)\\widetilde{\\omega}, a^b\\left ( t \\right )ω,ab(t):测量值
- ω,aw\\omega,a^{w}ω,aw:真实值
偏置项
和噪声项
都位于t时刻的载体坐标系(b)
- RbwR_{b}^{w}Rbw:从
载体坐标系(b)
到世界坐标系(w)
的旋转 - gwg^{w}gw:
世界坐标系下
的重力加速度
预积分
估计的状态:[Rbw(t),pw(t),vw(t)R_b^w(t), p^{w}(t), v^{w}(t)Rbw(t),pw(t),vw(t)]
- pw(t)p^{w}(t)pw(t)和vw(t)v^{w}(t)vw(t)为世界坐标系下IMU的位置和速度
- [Rbw(t),pw(t)R_b^w(t), p^{w}(t)Rbw(t),pw(t)]将帧从
B
映射到W
1.运动方程
使用欧拉积分,可以得到运动方程的离散形式为:
Rb(t+Δt)w=Rb(t)wExp(ωwbb(t)⋅Δt)vw(t+Δt)=vw(t)+aw(t)⋅Δtpw(t+Δt)=pw(t)+vw(t)⋅Δt+12aw(t)⋅Δt2\\begin{array}{l} \\mathbf{R}_{b(t+\\Delta t)}^{w}=\\mathbf{R}_{b(t)}^{w} {\\color{Red}\\operatorname{Exp} } \\left({\\color{Red} \\boldsymbol{\\omega}_{w b}^{b}(t)} \\cdot \\Delta t\\right) \\\\ \\mathbf{v}^{w}(t+\\Delta t)=\\mathbf{v}^{w}(t)+{\\color{Red} \\mathbf{a}^{w}(t)} \\cdot \\Delta t \\\\ \\mathbf{p}^{w}(t+\\Delta t)=\\mathbf{p}^{w}(t)+\\mathbf{v}^{w}(t) \\cdot \\Delta t+{\\color{Red} \\frac{1}{2} \\mathbf{a}^{w}(t)} \\cdot \\Delta t^{2} \\end{array} Rb(t+Δt)w=Rb(t)wExp(ωwbb(t)⋅Δt)vw(t+Δt)=vw(t)+aw(t)⋅Δtpw(t+Δt)=pw(t)+vw(t)⋅Δt+21aw(t)⋅Δt2
其中, wwbb(t)w_{wb}^b(t)wwbb(t)表示t时刻角速度矢量
在b系下的坐标,wwbb(t)⋅Δtw_{wb}^b(t)\\cdot \\Delta twwbb(t)⋅Δt表示旋转矢量
在b系下的坐标,Exp(ωwbb(t)⋅Δt){\\color{Red}\\operatorname{Exp} } \\left({\\color{Red} \\boldsymbol{\\omega}_{w b}^{b}(t)} \\cdot \\Delta t\\right)Exp(ωwbb(t)⋅Δt)表示在b系下从t+Δtt+\\Delta tt+Δt时刻到ttt时刻的旋转变换(Rb(t+Δt)b(t)R_{b \\left (t + \\Delta t \\right)}^{b \\left ( t \\right)}Rb(t+Δt)b(t))。
在采样频率不变,也就是Δt\\Delta tΔt不变,将测量模型代入离散运动方程为:
Rk+1=Rk⋅Exp((ω~k−bkg−ηkgd)⋅Δt)vk+1=vk+Rk⋅(f~k−bka−ηkad)⋅Δt+g⋅Δtpk+1=pk+vk⋅Δt+12g⋅Δt2+12Rk⋅(f~k−bka−ηkad)⋅Δt2\\begin{array}{l} \\mathbf{R}_{k+1}=\\mathbf{R}_{k} \\cdot \\operatorname{Exp}\\left(\\left(\\tilde{\\boldsymbol{\\omega}}_{k}-\\mathbf{b}_{k}^{g}-\\boldsymbol{\\eta}_{k}^{g d}\\right) \\cdot \\Delta t\\right) \\\\ \\mathbf{v}_{k+1}=\\mathbf{v}_{k}+\\mathbf{R}_{k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{k}^{a}-\\boldsymbol{\\eta}_{k}^{a d}\\right) \\cdot \\Delta t+{\\color{Red}\\mathbf{g} \\cdot \\Delta t} \\\\ \\mathbf{p}_{k+1}=\\mathbf{p}_{k}+\\mathbf{v}_{k} \\cdot \\Delta t+\\frac{1}{2} \\mathbf{g} \\cdot \\Delta t^{2}+\\frac{1}{2} \\mathbf{R}_{k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{k}^{a}-\\mathbf{\\eta}_{k}^{a d}\\right) \\cdot \\Delta t^{2} \\end{array} Rk+1=Rk⋅Exp((ω~k−bkg−ηkgd)⋅Δt)vk+1=vk+Rk⋅(f~k−bka−ηkad)⋅Δt+g⋅Δtpk+1=pk+vk⋅Δt+21g⋅Δt2+21Rk⋅(f~k−bka−ηkad)⋅Δt2
其中,
R(t)≐Rb(t)w;ω(t)≐ωwbb(t);f(t)=fb(t);v(t)≐vw(t);p(t)≐pw(t);g≐gw\\mathbf{R}(t) \\doteq \\mathbf{R}_{b(t)}^{w} ; \\boldsymbol{\\omega}(t) \\doteq \\boldsymbol{\\omega}_{w b}^{b}(t) ; \\mathbf{f}(t)=\\mathbf{f}^{b}(t) ; \\mathbf{v}(t) \\doteq \\mathbf{v}^{w}(t) ; \\mathbf{p}(t) \\doteq \\mathbf{p}^{w}(t) ; \\mathbf{g} \\doteq \\mathbf{g}^{w} R(t)≐Rb(t)w;ω(t)≐ωwbb(t);f(t)=fb(t);v(t)≐vw(t);p(t)≐pw(t);g≐gw
2.预积分
根据欧拉积分
,可以利用iii时刻到j−1j-1j−1时刻的所有IMU测量,其中jjj时刻的Rj,vj,pjR_j, v_j, p_jRj,vj,pj(世界坐标系
)可以直接由iii时刻的Ri,vi,piR_i, v_i,p_iRi,vi,pi(世界坐标系
)更新得到。
-
RjR_jRj
Rj=Ri∏k=ij−1Exp((ω~k−bkg−ηkgd)⋅△t)R_{j} =R_{i} \\prod_{k=i}^{j-1} Exp\\left ( \\left ( \\widetilde{\\omega}_{k} -b_k^g-\\eta _{k}^{gd} \\right ) \\cdot \\bigtriangleup t \\right ) Rj=Rik=i∏j−1Exp((ωk−bkg−ηkgd)⋅△t) -
vjv_jvj
vj=vi+g⋅Δtij+∑k=ij−1Rk⋅(fk~−bka−ηkad)⋅Δtv_{j} =v_{i} +{\\color{Purple} g\\cdot \\Delta t_{ij}} +\\sum_{k=i}^{j-1} {\\color{Red} R_k} \\cdot \\left ( \\widetilde{f_k}-b_k^a-\\eta _{k}^{ad} \\right )\\cdot \\Delta t vj=vi+g⋅Δtij+k=i∑j−1Rk⋅(fk−bka−ηkad)⋅Δt
其中,(fk~−bka−ηkad)⋅Δt\\left ( \\widetilde{f_k}-b_k^a-\\eta _{k}^{ad} \\right )\\cdot \\Delta t(fk−bka−ηkad)⋅Δt相对于的是IMU坐标系,需要转换到世界坐标系
。 -
pjp_jpj
pj=pi+∑k=ij−1vk⋅Δt+j−i2g⋅Δt2+12∑k=ij−1Rk⋅(fk~−bka−ηkad)⋅Δt2=pi+∑k=ij−1[vk⋅Δt+12g⋅Δt2+12Rk⋅(fk~−bka−ηkad)⋅Δt2]\\begin{align} p_j & = p_i+\\sum_{k = i}^{j-1} v_k\\cdot \\Delta t+{\\color{Purple} \\frac{j-i}{2} g\\cdot \\Delta t^2} +\\frac{1}{2} \\sum_{k = i}^{j-1}{\\color{Red} R_k} \\cdot \\left ( \\widetilde{f_k}-b_k^a-\\eta _k^{ad} \\right )\\cdot \\Delta t^2 \\\\ & = p_i+\\sum_{k=i}^{j-1}\\left [ v_k\\cdot \\Delta t+\\frac{1}{2} g\\cdot \\Delta t^2+\\frac{1}{2} {\\color{Red} R_k} \\cdot \\left ( \\widetilde{f_k}-b_k^a-\\eta _k^{ad} \\right )\\cdot \\Delta t^2 \\right ] \\end{align} pj=pi+k=i∑j−1vk⋅Δt+2j−ig⋅Δt2+21k=i∑j−1Rk⋅(fk−bka−ηkad)⋅Δt2=pi+k=i∑j−1[vk⋅Δt+21g⋅Δt2+21Rk⋅(fk−bka−ηkad)⋅Δt2]
其中,Δtij=∑k=ij−1Δt=(j−i)Δt\\Delta t_{ij}=\\sum_{k=i}^{j-1} \\Delta t=\\left ( j-i \\right ) \\Delta tΔtij=∑k=ij−1Δt=(j−i)Δt
为了避免每次更新初始的Ri,vi,piR_i, v_i, p_iRi,vi,pi都需要重新计算Rj,vj,pjR_j, v_j, p_jRj,vj,pj,引出预积分项:
ΔRij≜RiTRj=∏k=ij−1Exp((ω~k−bkg−ηkgd)⋅Δt)Δvij≜RiT(vj−vi−g⋅Δtij)=∑k=ij−1ΔRik⋅(f~k−bka−ηkad)⋅ΔtΔpij≜RiT(pj−pi−vi⋅Δtij−12g⋅Δtij2)=∑k=ij−1[Δvik⋅Δt+12ΔRik⋅(f~k−bka−ηkad)⋅Δt2]\\begin{aligned} \\Delta \\mathbf{R}_{i j} & \\triangleq \\mathbf{R}_{i}^{T} \\mathbf{R}_{j} \\\\ &=\\prod_{k=i}^{j-1} \\operatorname{Exp}\\left(\\left(\\tilde{\\mathbf{\\omega}}_{k}-\\mathbf{b}_{k}^{g}-\\eta_{k}^{g d}\\right) \\cdot \\Delta t\\right) \\\\ \\Delta \\mathbf{v}_{i j} & \\triangleq \\mathbf{R}_{i}^{T}\\left(\\mathbf{v}_{j}-\\mathbf{v}_{i}-\\mathbf{g} \\cdot \\Delta t_{i j}\\right) \\\\ &=\\sum_{k=i}^{j-1} \\Delta \\mathbf{R}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{k}^{a}-\\eta_{k}^{a d}\\right) \\cdot \\Delta t \\\\ \\Delta \\mathbf{p}_{i j} & \\triangleq \\mathbf{R}_{i}^{T}\\left(\\mathbf{p}_{j}-\\mathbf{p}_{i}-\\mathbf{v}_{i} \\cdot \\Delta t_{i j}-\\frac{1}{2} \\mathbf{g} \\cdot \\Delta t_{i j}^{2}\\right) \\\\ &=\\sum_{k=i}^{j-1}\\left[\\Delta \\mathbf{v}_{i k} \\cdot \\Delta t+\\frac{1}{2} \\Delta \\mathbf{R}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{k}^{a}-\\mathbf{\\eta}_{k}^{a d}\\right) \\cdot \\Delta t^{2}\\right] \\end{aligned} ΔRijΔvijΔpij≜RiTRj=k=i∏j−1Exp((ω~k−bkg−ηkgd)⋅Δt)≜RiT(vj−vi−g⋅Δtij)=k=i∑j−1ΔRik⋅(f~k−bka−ηkad)⋅Δt≜RiT(pj−pi−vi⋅Δtij−21g⋅Δtij2)=k=i∑j−1[Δvik⋅Δt+21ΔRik⋅(f~k−bka−ηkad)⋅Δt2]
预积分测量值和测量噪声
假设预积分计算区间内的bias
相等,即big=bi+1g=...=bjgb_i^g = b_{i+1}^g =...=b_j^{g}big=bi+1g=...=bjg以及bia=bi+1a=...=bjab_i^a = b_{i+1}^a =...=b_j^abia=bi+1a=...=bja
-
ΔRij\\Delta R_{ij}ΔRij项
根据性质“当δϕ→\\delta \\overrightarrow{\\phi }δϕ ”是小量
时,有
Exp(ϕ⃗+δϕ⃗)≈Exp(ϕ⃗)⋅Exp(Jr(ϕ⃗)⋅δϕ⃗)\\operatorname{Exp}(\\vec{\\phi}+\\delta \\vec{\\phi}) \\approx \\operatorname{Exp}(\\vec{\\phi}) \\cdot \\operatorname{Exp}\\left(\\mathbf{J}_{r}(\\vec{\\phi}) \\cdot \\delta \\vec{\\phi}\\right) Exp(ϕ+δϕ)≈Exp(ϕ)⋅Exp(Jr(ϕ)⋅δϕ)
指数映射的Adjoint性质:
R⋅Exp(ϕ⃗)⋅RT=exp(Rϕ⃗∧RT)=Exp(Rϕ⃗)⇔Exp(ϕ⃗)⋅R=R⋅Exp(RTϕ⃗)\\begin{array}{l} \\mathbf{R} \\cdot \\operatorname{Exp}(\\vec{\\phi}) \\cdot \\mathbf{R}^{T} = \\exp \\left(\\mathbf{R} \\vec{\\phi}^{\\wedge} \\mathbf{R}^{T}\\right) = \\operatorname{Exp}(\\mathbf{R} \\vec{\\phi}) \\\\ \\Leftrightarrow \\operatorname{Exp}(\\vec{\\phi}) \\cdot \\mathbf{R} = \\mathbf{R} \\cdot \\operatorname{Exp}\\left(\\mathbf{R}^{T} \\vec{\\phi}\\right) \\end{array} R⋅Exp(ϕ)⋅RT=exp(Rϕ∧RT)=Exp(Rϕ)⇔Exp(ϕ)⋅R=R⋅Exp(RTϕ)
ΔRij=∏k=ij−1Exp((ω~k−big)Δt⏟ϕ→−ηkgdΔt⏟δϕ→)≈(1)∏k=ij−1{Exp((ω~k−big)Δt)⋅Exp(−Jr((ω~k−big)Δt)⋅ηkgdΔt)}=(2)ΔR~ij⋅∏k=ij−1Exp(−ΔR~k+1jT⋅Jrk⋅ηkgdΔt)\\begin{aligned} \\Delta \\mathbf{R}_{i j} &=\\prod_{k=i}^{j-1} \\operatorname{Exp}\\left(\\underbrace{\\left(\\tilde{\\boldsymbol{\\omega}}_{k}-\\mathbf{b}_{i}^{g}\\right) \\Delta t}_{\\overrightarrow{\\phi } }\\underbrace{-\\boldsymbol{\\eta}_{k}^{g d} \\Delta t}_{\\delta \\overrightarrow{\\phi } } \\right) \\\\ & \\stackrel{(1)}{\\approx} \\prod_{k=i}^{j-1}\\left\\{\\operatorname{Exp}\\left(\\left(\\tilde{\\boldsymbol{\\omega}}_{k}-\\mathbf{b}_{i}^{g}\\right) \\Delta t\\right) \\cdot \\operatorname{Exp}\\left(-\\mathbf{J}_{r}\\left(\\left(\\tilde{\\boldsymbol{\\omega}}_{k}-\\mathbf{b}_{i}^{g}\\right) \\Delta t\\right) \\cdot \\boldsymbol{\\eta}_{k}^{g d} \\Delta t\\right)\\right\\} \\\\ & \\stackrel{(2)}{=} \\Delta \\tilde{\\mathbf{R}}_{i j} \\cdot \\prod_{k=i}^{j-1} \\operatorname{Exp}\\left(-\\Delta \\tilde{\\mathbf{R}}_{k+1 j}^{T} \\cdot \\mathbf{J}_{r}^{k} \\cdot \\boldsymbol{\\eta}_{k}^{g d} \\Delta t\\right) \\end{aligned} ΔRij=k=i∏j−1Expϕ(ω~k−big)Δtδϕ−ηkgdΔt≈(1)k=i∏j−1{Exp((ω~k−big)Δt)⋅Exp(−Jr((ω~k−big)Δt)⋅ηkgdΔt)}=(2)ΔR~ij⋅k=i∏j−1Exp(−ΔR~k+1jT⋅Jrk⋅ηkgdΔt)
其中,令:
Jrk=Jr((ω~k−big)Δt)ΔR~ij=∏k=ij−1Exp((ω~k−big)Δt)Exp(−δϕ⃗ij)=∏k=ij−1Exp(−ΔR~k+1jT⋅Jrk⋅ηkgdΔt)\\begin{array}{l} \\mathbf{J}_{r}^{k}=\\mathbf{J}_{r}\\left(\\left(\\tilde{\\boldsymbol{\\omega}}_{k}-\\mathbf{b}_{i}^{g}\\right) \\Delta t\\right)\\\\ \\Delta \\tilde{\\mathbf{R}}_{i j}=\\prod_{k=i}^{j-1} \\operatorname{Exp}\\left(\\left(\\tilde{\\boldsymbol{\\omega}}_{k}-\\mathbf{b}_{i}^{g}\\right) \\Delta t\\right) \\\\ \\operatorname{Exp}\\left(-\\delta \\vec{\\phi}_{i j}\\right)=\\prod_{k=i}^{j-1} \\operatorname{Exp}\\left(-\\Delta \\tilde{\\mathbf{R}}_{k+1 j}^{T} \\cdot \\mathbf{J}_{r}^{k} \\cdot \\boldsymbol{\\eta}_{k}^{g d} \\Delta t\\right) \\end{array} Jrk=Jr((ω~k−big)Δt)ΔR~ij=∏k=ij−1Exp((ω~k−big)Δt)Exp(−δϕij)=∏k=ij−1Exp(−ΔR~k+1jT⋅Jrk⋅ηkgdΔt)
其中,ΔR~jj=I\\Delta \\widetilde{R}_{jj}=IΔRjj=I,则可以得到:
ΔRij≜ΔR~ij⋅Exp(−δϕ⃗ij)\\Delta \\mathbf{R}_{i j} \\triangleq \\Delta \\tilde{\\mathbf{R}}_{i j} \\cdot \\operatorname{Exp}\\left(-\\delta \\vec{\\phi}_{i j}\\right) ΔRij≜ΔR~ij⋅Exp(−δϕij)
ΔR~ij\\Delta\\widetilde{R}_{ij}ΔRij即旋转量预积分测量值
,它由陀螺仪测量值
和对陀螺仪bias的估计
得到,δϕ→ij\\delta\\overrightarrow{\\phi }_{ij}δϕij为测量的噪声
。 -
Δvij\\Delta v_{ij}Δvij项:
将ΔRij≜ΔR~ij⋅Exp(−δϕ⃗ij)\\Delta \\mathbf{R}_{i j} \\triangleq \\Delta \\tilde{\\mathbf{R}}_{i j} \\cdot \\operatorname{Exp}\\left(-\\delta \\vec{\\phi}_{i j}\\right)ΔRij≜ΔR~ij⋅Exp(−δϕij)代入到Δvij\\Delta v_{ij}Δvij中
Δvij=∑k=ij−1ΔRik⋅(f~k−bia−ηkad)⋅Δt≈∑k=ij−1ΔR~ik⋅Exp(−δϕ⃗ik)⏟I−δϕ⃗ik∧⋅(f~k−bia−ηkad)⋅Δt≈(1)∑k=ij−1ΔR~ik⋅(I−δϕ⃗ik∧)⋅(f~k−bia−ηkad)⋅Δt≈(2)∑k=ij−1[ΔR~ik⋅(I−δϕ⃗ik∧)⋅(f~k−bia)⋅Δt⏟a∧⋅b=−b∧⋅a−ΔR~ikηkadΔt+ΔR~ikδϕ→ij∧ηkad‾]=(3)∑k=ij−1[ΔR~ik⋅(f~k−bia)⋅Δt+ΔR~ik⋅(f~k−bia)∧⋅δϕ⃗ik⋅Δt−ΔR~ikηkadΔt]=∑k=ij−1[ΔR~ik⋅(f~k−bia)⋅Δt]⏟Δv~ij+∑k=ij−1[ΔR~ik⋅(f~k−bia)∧⋅δϕ⃗ik⋅Δt−ΔR~ikηkadΔt]⏟−δvij\\begin{aligned} \\Delta \\mathbf{v}_{i j} &=\\sum_{k=i}^{j-1} \\Delta \\mathbf{R}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}-\\mathbf{\\eta}_{k}^{a d}\\right) \\cdot \\Delta t \\\\ & \\approx \\sum_{k=i}^{j-1} \\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot \\underbrace{{\\color{Red} \\operatorname{Exp}\\left(-\\delta \\vec{\\phi}_{i k}\\right)}}_{\\mathbf{I}-\\delta \\vec{\\phi}_{i k}^{\\wedge}} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}-\\boldsymbol{\\eta}_{k}^{a d}\\right) \\cdot \\Delta t \\\\ & \\stackrel{(1)}{\\approx} \\sum_{k=i}^{j-1} \\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\mathbf{I}-\\delta \\vec{\\phi}_{i k}^{\\wedge}\\right) \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}-\\boldsymbol{\\eta}_{k}^{a d}\\right) \\cdot \\Delta t \\\\ & \\stackrel{(2)}{\\approx} \\sum_{k=i}^{j-1}\\left[\\underbrace{\\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\mathbf{I}-\\delta \\vec{\\phi}_{i k}^{\\wedge}\\right) \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}\\right) \\cdot \\Delta t}_{{\\color{Red} a^{\\wedge } \\cdot b = -b^{\\wedge }\\cdot a} } -\\Delta \\tilde{\\mathbf{R}}_{i k} \\boldsymbol{\\eta}_{k}^{a d} \\Delta t +\\underline{\\Delta\\widetilde{R}_{ik}\\delta \\overrightarrow{\\phi} _{ij}^{\\wedge }\\eta _{k}^{ad}} \\right] \\\\ & \\stackrel{(3)}{=} \\sum_{k=i}^{j-1}\\left[\\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}\\right) \\cdot \\Delta t+\\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}\\right)^{\\wedge} \\cdot \\delta \\vec{\\phi}_{i k} \\cdot \\Delta t-\\Delta \\tilde{\\mathbf{R}}_{i k} \\boldsymbol{\\eta}_{k}^{a d} \\Delta t\\right] \\\\ &=\\underbrace{\\sum_{k=i}^{j-1}\\left[\\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}\\right) \\cdot \\Delta t\\right]}_{\\Delta \\widetilde{v}_{ij} } +\\underbrace{\\sum_{k=i}^{j-1}\\left[\\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}\\right)^{\\wedge} \\cdot \\delta \\vec{\\phi}_{i k} \\cdot \\Delta t-\\Delta \\tilde{\\mathbf{R}}_{i k} \\boldsymbol{\\eta}_{k}^{a d} \\Delta t\\right]}_{-\\delta v_{ij}} \\end{aligned} Δvij=k=i∑j−1ΔRik⋅(f~k−bia−ηkad)⋅Δt≈k=i∑j−1ΔR~ik⋅I−δϕik∧Exp(−δϕik)⋅(f~k−bia−ηkad)⋅Δt≈(1)k=i∑j−1ΔR~ik⋅(I−δϕik∧)⋅(f~k−bia−ηkad)⋅Δt≈(2)k=i∑j−1a∧⋅b=−b∧⋅aΔR~ik⋅(I−δϕik∧)⋅(f~k−bia)⋅Δt−ΔR~ikηkadΔt+ΔRikδϕij∧ηkad=(3)k=i∑j−1[ΔR~ik⋅(f~k−bia)⋅Δt+ΔR~ik⋅(f~k−bia)∧⋅δϕik⋅Δt−ΔR~ikηkadΔt]=Δvijk=i∑j−1[ΔR~ik⋅(f~k−bia)⋅Δt]+−δvijk=i∑j−1[ΔR~ik⋅(f~k−bia)∧⋅δϕik⋅Δt−ΔR~ikηkadΔt]
可以得到:
Δvij≜Δv~ij−δvij\\Delta v_{ij} \\triangleq \\Delta \\widetilde{v}_{ij}-\\delta v_{ij} Δvij≜Δvij−δvij
Δv~ij\\Delta \\widetilde{v}_{ij}Δvij为速度增量预积分测量值,它由IMU的测量值和对bias的估计得到,δvij\\delta v_{ij}δvij为测量噪声。 -
Δpij\\Delta p_{ij}Δpij项
将ΔRij≜ΔR~ij⋅Exp(−δϕ⃗ij)\\Delta \\mathbf{R}_{i j} \\triangleq \\Delta \\tilde{\\mathbf{R}}_{i j} \\cdot \\operatorname{Exp}\\left(-\\delta \\vec{\\phi}_{i j}\\right)ΔRij≜ΔR~ij⋅Exp(−δϕij)和Δvij≜Δv~ij−δvij\\Delta v_{ij} \\triangleq \\Delta \\widetilde{v}_{ij}-\\delta v_{ij}Δvij≜Δvij−δvij代入到Δpij\\Delta p_{ij}Δpij中
Δpij=∑k=ij−1[Δvik⋅Δt+12ΔRik⋅(f~k−bia−ηkad)⋅Δt2]≈∑k=ij−1[(Δv~ik−δvik)⋅Δt+12ΔR~ik⋅Exp(−δϕ⃗ik)⋅(f~k−bia−ηkad)⋅Δt2]≈(1)∑k=ij−1[(Δv~ik−δvik)⋅Δt+12ΔR~ik⋅(I−δϕ⃗ik∧)⏟Exp(ϕ⃗)=I+ϕ⃗∧⋅(f~k−bia−ηkad)⋅Δt2]≈(2)∑k=ij−1[(ΔV~ik−δvik)⋅Δt+12ΔR~ik⋅(I−δϕ⃗ik∧)⋅(f~k−bia)⋅Δt2−12ΔR~ikηkadΔt2+12ΔR~ikδϕ⃗ik∧ηkadΔt2‾]=(3)∑k=ij−1[ΔV~ikΔt+12ΔR~ik⋅(f~k−bia)Δt2⏟Δp~ij+12ΔR~ik⋅(f~k−bia)∧δϕ⃗ikΔt2⏟a∧⋅b=−b∧⋅a−12ΔR~ikηkadΔt2−δvikΔt⏟δpij]\\begin{array}{l} \\Delta \\mathbf{p}_{i j}=\\sum_{k=i}^{j-1}\\left[\\Delta \\mathbf{v}_{i k} \\cdot \\Delta t+\\frac{1}{2} \\Delta \\mathbf{R}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}-\\boldsymbol{\\eta}_{k}^{a d}\\right) \\cdot \\Delta t^{2}\\right] \\\\ \\approx \\sum_{k=i}^{j-1}\\left[{\\color{Red} \\left(\\Delta \\tilde{\\mathbf{v}}_{i k}-\\delta \\mathbf{v}_{i k}\\right)} \\cdot \\Delta t+\\frac{1}{2} {\\color{Red} \\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot \\operatorname{Exp}\\left(-\\delta \\vec{\\phi}_{i k}\\right)} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}-\\boldsymbol{\\eta}_{k}^{a d}\\right) \\cdot \\Delta t^{2}\\right] \\\\ \\stackrel{(1)}{\\approx} \\sum_{k=i}^{j-1}\\left[\\left(\\Delta \\tilde{\\mathbf{v}}_{i k}-\\delta \\mathbf{v}_{i k}\\right) \\cdot \\Delta t+\\frac{1}{2} \\underbrace{\\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\mathbf{I}-\\delta \\vec{\\phi}_{i k}^{\\wedge}\\right)}_{\\operatorname{Exp}\\left (\\vec{ \\phi} \\right)=I+\\vec{\\phi}^{\\wedge}} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}-\\mathbf{\\eta}_{k}^{a d}\\right) \\cdot \\Delta t^{2}\\right] \\\\ \\stackrel{(2)}{\\approx} \\sum_{k=i}^{j-1}\\left[\\left(\\Delta \\tilde{\\mathbf{V}}_{i k}-\\delta \\mathbf{v}_{i k}\\right) \\cdot \\Delta t+\\frac{1}{2} \\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\mathbf{I}-\\delta \\vec{\\phi}_{i k}^{\\wedge}\\right) \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}\\right) \\cdot \\Delta t^{2}-\\frac{1}{2} \\Delta \\tilde{\\mathbf{R}}_{i k} \\mathbf{\\eta}_{k}^{a d} \\Delta t^{2} + \\underline{\\frac{1}{2} \\Delta \\tilde{\\mathbf{R}}_{i k} \\delta \\vec{\\phi}_{i k}^{\\wedge} \\mathbf{\\eta}_{k}^{a d} \\Delta t^{2}} \\right] \\\\ \\stackrel{(3)}{=} \\sum_{k=i}^{j-1}\\left[\\underbrace{\\Delta \\tilde{\\mathbf{V}}_{i k} \\Delta t+\\frac{1}{2} \\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}\\right) \\Delta t^{2}}_{\\Delta \\widetilde{p} _{ij}} +\\underbrace{\\underbrace{\\frac{1}{2} \\Delta \\tilde{\\mathbf{R}}_{i k} \\cdot\\left(\\tilde{\\mathbf{f}}_{k}-\\mathbf{b}_{i}^{a}\\right)^{\\wedge} \\delta \\vec{\\phi}_{i k} \\Delta t^{2}}_{a^{\\wedge }\\cdot b=-b^{\\wedge }\\cdot a} -\\frac{1}{2} \\Delta \\tilde{\\mathbf{R}}_{i k} \\mathbf{\\eta}_{k}^{a d} \\Delta t^{2}-\\delta \\mathbf{v}_{i k} \\Delta t} _{\\delta p_{ij}}\\right] \\\\ \\end{array} Δpij=∑k=ij−1[Δvik⋅Δt+21ΔRik⋅(f~k−bia−ηkad)⋅Δt2]≈∑k=ij−1[(Δv~ik−δvik)⋅Δt+21ΔR~ik⋅Exp(−δϕik)⋅(f~k−bia−ηkad)⋅Δt2]≈(1)∑k=ij−1(Δv~ik−δvik)⋅Δt+21Exp(ϕ)=I+ϕ∧ΔR~ik⋅(I−δϕik∧)⋅(f~k−bia−ηkad)⋅Δt2≈(2)∑k=ij−1[(ΔV~ik−δvik)⋅Δt+21ΔR~ik⋅(I−δϕik∧)⋅(f~k−bia)⋅Δt2−21ΔR~ikηkadΔt2+21ΔR~ikδϕik∧ηkadΔt2]=(3)∑k=ij−1ΔpijΔV~ikΔt+21ΔR~ik⋅(f~k−bia)Δt2+δpija∧⋅b=−b∧⋅a21ΔR~ik⋅(f~k−bia)∧δϕikΔt2−21ΔR~ikηkadΔt2−δvikΔt
可以得到:
Δpij≜Δp~ij−δpij\\Delta p_{ij} \\triangleq \\Delta \\widetilde{p}_{ij}-\\delta p_{ij} Δpij≜Δpij−δpij
Δp~ij\\Delta \\widetilde{p}_{ij}Δpij为速度增量预积分测量值,它由IMU的测量值和对bias的估计得到,δpij\\delta p_{ij}δpij为测量噪声。
预积分理想值:
ΔRij≜RiTRjΔvij≜RiT(vj−vi−g⋅Δtij)Δpij≜RiT(pj−pi−vi⋅Δtij−12g⋅Δtij2)\\begin{array}{l} \\Delta \\mathbf{R}_{i j} \\triangleq \\mathbf{R}_{i}^{T} \\mathbf{R}_{j}\\\\ \\Delta \\mathbf{v}_{i j} \\triangleq \\mathbf{R}_{i}^{T}\\left(\\mathbf{v}_{j}-\\mathbf{v}_{i}-\\mathbf{g} \\cdot \\Delta t_{i j}\\right)\\\\ \\Delta \\mathbf{p}_{i j} \\triangleq \\mathbf{R}_{i}^{T}\\left(\\mathbf{p}_{j}-\\mathbf{p}_{i}-\\mathbf{v}_{i} \\cdot \\Delta t_{i j}-\\frac{1}{2} \\mathbf{g} \\cdot \\Delta t_{i j}^{2}\\right) \\end{array} ΔRij≜RiTRjΔvij≜RiT(vj−vi−g⋅Δtij)Δpij≜RiT(pj−pi−vi⋅Δtij−21g⋅Δtij2)
将预积分理想值代入:测量值 = 理想值 + 噪声
ΔR~ij≈ΔRijExp(δϕ⃗ij)=RiTRjExp(δϕ⃗ij)Δv~ij≈Δvij+δvij=RiT(vj−vi−g⋅Δtij)+δvijΔp~ij≈Δpij+δpij=RiT(pj−pi−vi⋅Δtij−12g⋅Δtij2)+δpij\\begin{array}{l} \\Delta \\tilde{\\mathbf{R}}_{i j} \\approx \\Delta \\mathbf{R}_{i j} \\operatorname{Exp}\\left(\\delta \\vec{\\phi}_{i j}\\right)=\\mathbf{R}_{i}^{T} \\mathbf{R}_{j} \\operatorname{Exp}\\left(\\delta \\vec{\\phi}_{i j}\\right) \\\\ \\Delta \\tilde{\\mathbf{v}}_{i j} \\approx \\Delta \\mathbf{v}_{i j}+\\delta \\mathbf{v}_{i j}=\\mathbf{R}_{i}^{T}\\left(\\mathbf{v}_{j}-\\mathbf{v}_{i}-\\mathbf{g} \\cdot \\Delta t_{i j}\\right)+\\delta \\mathbf{v}_{i j} \\\\ \\Delta \\tilde{\\mathbf{p}}_{i j} \\approx \\Delta \\mathbf{p}_{i j}+\\delta \\mathbf{p}_{i j}=\\mathbf{R}_{i}^{T}\\left(\\mathbf{p}_{j}-\\mathbf{p}_{i}-\\mathbf{v}_{i} \\cdot \\Delta t_{i j}-\\frac{1}{2} \\mathbf{g} \\cdot \\Delta t_{i j}^{2}\\right)+\\delta \\mathbf{p}_{i j} \\end{array} ΔR~ij≈ΔRijExp(δϕij)=RiTRjExp(δϕij)Δv~ij≈Δvij+δvij=RiT(vj−vi−g⋅Δtij)+δvijΔp~ij≈Δpij+δpij=RiT(pj−pi−vi⋅Δtij−21g⋅Δtij2)+δpij