IMU模型和运动积分

$R_{\tiny{WB}} \left( t +\Delta{t} \right) = R_{\tiny{WB}} \left( t \right) Exp\left( \int_{t} ^{t+\Delta{t}} {}_{\tiny{B}} \omega_{\tiny{WB}} \left( \tau \right) d\tau   \right)$

${}_{\tiny{W}}V \left(t+\Delta{t} \right) = {}_{\tiny{W}}V\left( t \right) + \int _{t} ^{t+\Delta{t}} {}_{\tiny{W}}a \left( \tau \right)d\tau $

${}_{\tiny{W}}P \left(t+\Delta{t} \right) = {}_{\tiny{W}}P\left( t \right) + \int _{t} ^{t+\Delta{t}} {}_{\tiny{W}}V \left( \tau \right)d\tau \,+\int \int _{t} ^{t+\Delta{t}}{}_{\tiny{W}}a \left( \tau \right)d\tau^2$

其中IMU读数,即测量值(理论值在偏置和噪声的影响下得到的读数)为

${}_{\tiny{B}} \tilde{ \omega }_{\tiny{WB}} \left( t \right) = {}_{\tiny{B}} \omega_{\tiny{WB}} \left( t \right) + b^{g} \left( t \right) +\eta^{g}\left( t \right) $

${}_{\tiny{B}} \tilde{ a } \left( t \right) = R_{\tiny{WB}}^{T} \left( t \right)  \left( {}_{\tiny{W}}a\left( t \right) - {}_{\tiny{W}}g\right) + b^a\left( t \right) + \eta^a \left( t \right) $

假设在时间间隔$\left[ t,t+\Delta{t} \right]$中,${}_{\tiny{W}}a$和${}_{\tiny{B}} \omega_{\tiny{WB}}$为常数

$R_{\tiny{WB}} \left( t +\Delta{t} \right) = R_{\tiny{WB}}  \left( t \right)  Exp\left( {}_{\tiny{B}} \omega_{\tiny{WB}}  \left( t \right) \Delta{t} \right)$

${}_{\tiny{W}}V\left( t + \Delta{t} \right) ={}_{\tiny{W}}V\left( t \right) + {}_{\tiny{W}}a \left( t \right)\Delta{t} $

${}_{\tiny{W}}P \left(t+\Delta{t} \right) = {}_{\tiny{W}}P\left( t \right)+{}_{\tiny{W}}V \left( t \right) \Delta{t} + \frac{1}{2}{}_{\tiny{W}}a \left( t \right)\Delta{t}^2$

以上的公式用IMU测量值表示:

$R \left( t +\Delta{t} \right) = R \left( t \right) Exp\left( \left(  \tilde{ \omega } \left( t \right) - b^g\left( t \right) - \eta^{gd} \left( t \right) \right) \Delta{t}\right)$

$V \left( t +\Delta{t} \right) = V \left( t \right) +g\Delta{t}+R\left( t \right) \left(  \tilde{ a } \left( t \right) - b^{a}\left( t \right) - \eta^{ad}\left( t \right) \right) \Delta {t}$

$P \left(t+\Delta{t} \right) = P\left( t \right) + V \left( t \right)\Delta{t} + \frac{1}{2} g\Delta{t}^2 +\frac{1}{2}R\left( t \right) \left(  \tilde{ a } \left( t \right) - b^{a}\left( t \right) - \eta^{ad}\left( t \right) \right) \Delta {t}^2$

IMU预积分

给定初值,在i和j时刻对IMU的角速度和加速度进行积分,可以计算j时刻相对于i时刻的姿态:

$R_{j} = R_{i}\prod\limits_{k=i}\limits^{j-1}Exp\left( \left(  \tilde{ \omega }_{k}  - b^g_{k}- \eta^{gd}_{k}  \right) \Delta{t} \right)$

$V_{j} = V_{i}+ g\Delta{t_{ij}}+ \sum\limits_{k=i}\limits^{j-1}R_k\left( \tilde{ a }_{k}  - b^a_{k}- \eta^{ad}_{k}  \right) \Delta{t}$

$P_{j} = P_{i}+ \sum\limits_{k=i}\limits^{j-1}\left[V_k\Delta{t} + \frac{1}{2}g\Delta{t}^2 + \frac{1}{2}R_k\left( \tilde{ a }_{k}  - b^a_{k}- \eta^{ad}_{k}  \right) \Delta{t}^2 \right]$

在preintegration理论中需要初值($R_i$,$V_i$,$P_i$)和常数项(包含重力g的项)分离出来。

(1)

$\Delta{R_{ij}} = R_{i}^{T}R_j=\prod\limits_{k=i}\limits^{j-1}Exp\left( \left(  \tilde{ \omega }_{k}  - b^g_{k}- \eta^{gd}_{k}  \right) \Delta{t} \right)$

$\Delta{V_{ij}} = R_{i}^{T}\left( V_j - V_i - g\Delta{t_{ij}} \right)= \sum\limits_{k=i}\limits^{j-1}\Delta{R_{ik}}\left( \tilde{ a }_{k}  - b^a_{k}- \eta^{ad}_{k}  \right) \Delta{t}$

$\Delta{P_{ij}} = R_{i}^{T}\left( P_j - P_i -V_i\Delta{t_{ij}}-\frac{1}{2} g\Delta{t_{ij}^2} \right)=\sum\limits_{k=i}\limits^{j-1}\left[\Delta{V_{ik}}\Delta{t}+\frac{1}{2}\Delta{R_{ik}}\left( \tilde{ a }_{k}  - b^a_{k}- \eta^{ad}_{k}  \right) \Delta{t}^2\right]$

其中$\Delta{R_{ij}}$,$\Delta{V_{ij}}$,$\Delta{P_{ij}}$即为preintegration measurement,即不考虑初值以及重力加速度项的相对测量。注意到这项项包含有噪声$\eta$,我们也需要将它们分离出来,在分离的过程中发现preintegration measurement是近似服从高斯分布的,即

(2)

$\Delta\tilde{R}_{ij} \approx \Delta{R_{ij}}Exp\left( \delta \phi_{ij} \right) =\prod\limits_{k=i}\limits^{j-1}Exp\left( \left(  \tilde{ \omega }_{k}  - b^g_{k} \right) \Delta{t} \right)$

$\Delta\tilde{V}_{ij} \approx \Delta{V_{ij}}+\delta{V_{ij}} = \sum\limits_{k=i}\limits^{j-1}\Delta{\tilde{R}_{ik}}\left( \tilde{ a }_{k}  - b^a_{k}  \right) \Delta{t}$

$\Delta\tilde{P}_{ij} \approx \Delta{P_{ij}}+\delta{P_{ij}}=\sum\limits_{k=i}\limits^{j-1}\left[\Delta{\tilde{V}_{ik}}\Delta{t}+\frac{1}{2}\Delta{\tilde{R}_{ik}}\left( \tilde{ a }_{k}  - b^a_{k}  \right) \Delta{t}^2\right]$

最终可得预积分测量模型(其中$Exp\left(-\delta\phi_{ij}\right)^T = Exp\left(\delta\phi_{ij}\right)$)

(3)

$\Delta\tilde{R}_{ij} = R_{i}^{T}R_jExp\left( \delta \phi_{ij} \right)$

$\Delta\tilde{V}_{ij} = R_{i}^{T}\left( V_j - V_i - g\Delta{t_{ij}} \right)+\delta{V_{ij}}$

$\Delta\tilde{P}_{ij} = R_{i}^{T}\left( P_j - P_i -V_i\Delta{t_{ij}}-\frac{1}{2} g\Delta{t_{ij}^2} \right)+\delta{P_{ij}}$

偏差更新

(4)

$\Delta\tilde{R}_{ij}\left( b_i^g\right) =\prod\limits_{k=i}\limits^{j-1}Exp\left( \left(  \tilde{ \omega }_{k}  -\bar{b}^g_{i} -\delta{b_i^g}\right) \Delta{t} \right) \simeq \Delta\tilde{R}_{ij}\left( \bar{b}_i^g\right) Exp\left(\frac{\partial\Delta\bar{R}_{ij}} {\partial{b^g}} \delta{b^g_i} \right)$

$\Delta\tilde{V}_{ij}\left( b_i^g,b_i^a \right) =\sum\limits_{k=i}\limits^{j-1}\Delta{\tilde{R}_{ik}}\left(b_i^g\right)\left( \tilde{ a }_{k}  - \bar{b}^a_{i} -\delta{b}_i^a \right) \Delta{t}    \simeq \Delta\tilde{V}_{ij}\left( \bar{b}_i^g,\bar{b}_i^a\right) +\frac{\partial\Delta\bar{V}_{ij}} {\partial{b^g}} \delta{b^g_i} + \frac{\partial\Delta\bar{V}_{ij}} {\partial{b^a}} \delta{b^a_i}$

$\Delta\tilde{P}_{ij}\left( b_i^g,b_i^a \right)= \sum\limits_{k=i}\limits^{j-1}\left[\Delta{\tilde{V}_{ik}}\left( b_i^g,b_i^a \right)\Delta{t}+\frac{1}{2}\Delta{\tilde{R}_{ik}}\left( b_i^g\right)\left( \tilde{ a }_{k}  - \bar{b}^a_{i} -\delta{b}_i^a \right) \Delta{t}^2\right]    \simeq \Delta\tilde{P}_{ij}\left( \bar{b}_i^g,\bar{b}_i^a\right) +\frac{\partial\Delta\bar{P}_{ij}} {\partial{b^g}} \delta{b^g_i} + \frac{\partial\Delta\bar{P}_{ij}} {\partial{b^a}} \delta{b^a_i}$

$\Delta\tilde{R}_{ij}\left( \bar{b}_i^g\right)$,$\Delta\tilde{V}_{ij}\left( \bar{b}_i^g,\bar{b}_i^a\right)$,$\Delta\tilde{P}_{ij}\left( \bar{b}_i^g,\bar{b}_i^a\right)$为偏置未更新的时的值,后半部分为偏置更新后的影响。

在之前的预积分推导中我们假设i和j之间的偏置是不变的(即偏置的下标为i而不是会变化的k),但是在优化过程中偏置的估计会被一个小增量$\delta{b}$更新,将$b\gets\bar{b}+\delta{b}$代入(2)中得(4)的左半部分,对i和j之间的测量进行积分,但是这不是最高效的,所以我们采取用一阶泰勒展开的方式得(4)的右半部分,其中右半部分中的雅可比(在$\bar{b_i}$处计算所得)描述了由于估计的偏置的变化而引起的变化。

残差

$r_{\Delta{R_{ij}}} = Log\left( \left( \Delta\tilde{R}_{ij}\left( \bar{b}_i^g\right) Exp\left(\frac{\partial\Delta\bar{R}_{ij}} {\partial{b^g}} \delta{b^g} \right) \right) ^T R_i^T{R_j}\right)$

$r_{\Delta{V_{ij}}} = R_{i}^{T}\left( V_j - V_i - g\Delta{t_{ij}} \right) - \left[\Delta\tilde{V}_{ij}\left( \bar{b}_i^g,\bar{b}_i^a\right) +\frac{\partial\Delta\bar{V}_{ij}} {\partial{b^g}} \delta{b^g} + \frac{\partial\Delta\bar{V}_{ij}} {\partial{b^a}} \delta{b^a} \right]$

$r_{\Delta{P_{ij}}} = R_{i}^{T}\left( P_j - P_i -V_i\Delta{t_{ij}}-\frac{1}{2} g\Delta{t_{ij}^2} \right) - \left[ \Delta\tilde{P}_{ij}\left( \bar{b}_i^g,\bar{b}_i^a\right) +\frac{\partial\Delta\bar{P}_{ij}} {\partial{b^g}} \delta{b^g} + \frac{\partial\Delta\bar{P}_{ij}} {\partial{b^a}} \delta{b^a} \right]$

其中被减数为(1)的左半部分,减数为(4)的右半部分。

迭代噪声传播

噪声向量$\eta_{ij}^\Delta = \left[ \delta\phi^T_{ij}, \delta{V}^T_{ij},\delta{P}^T_{ij} \right]^T \sim \mathcal{N} \left( 0_{9X1},\sum_{ij} \right)$

给出递推结果:

$\delta\phi_{i,j} \backsimeq \Delta \tilde{R}_{j-1,j}^T\delta\phi_{i,j-1}+J_r^{j-1}\eta_{j-1}^{gd}\Delta{t}$

$\delta{V_{i,j}} \backsimeq \delta{V_{i,j-1}} - \Delta{\tilde{R}_{i,j-1}} \left( \tilde{a}_{j-1}-b^a_i \right)^{\wedge}\delta\phi_{i,j-1}\Delta{t}+\Delta\tilde{R}_{i,j-1}\eta_{j-1}^{ad}\Delta{t}$

$\delta{P_{i,j}} \backsimeq \delta{P_{i,j-1}} + \delta{V_{i,j-1}}\Delta{t} - \frac{1}{2}\Delta{\tilde{R}_{i,j-1}} \left( \tilde{a}_{j-1}-b^a_i \right)^{\wedge}\delta\phi_{i,j-1}\Delta{t}^2 + \frac{1}{2}\Delta\tilde{R}_{i,j-1}\eta_{j-1}^{ad}\Delta{t}^2$

写成矩阵形式:

$\begin{bmatrix}\delta\phi_{i,j} \\\delta{V}_{i,j} \\\delta{P}_{i,j}\end{bmatrix}= A_{j-1}\begin{bmatrix}\delta\phi_{i,j-1} \\\delta{V}_{i,j-1} \\\delta{P}_{i,j-1}\end{bmatrix}+B_{j-1}\eta_{j-1}^{gd}+C_{j-1}\eta_{j-1}^{ad}$这是线性模型

其中

$A_{j-1}=\begin{bmatrix} \Delta \tilde{R}_{j-1,j}^T & 0_{3X3} & 0_{3X3} \\ -\Delta{\tilde{R}_{i,j-1}} \left( \tilde{a}_{j-1}-b^a_i \right)^{\wedge}\Delta{t} & 0_{3X3} & I_{3X3} \\ - \frac{1}{2}\Delta{\tilde{R}_{i,j-1}} \left( \tilde{a}_{j-1}-b^a_i \right)^{\wedge}\Delta{t}^2 & I_{3X3} & I_{3X3}\Delta{t} \end{bmatrix}_{9X9}$

$B_{j-1} = \begin{bmatrix}J_r^{j-1}\Delta{t} \\ 0_{3X3} \\ 0_{3X3}\end{bmatrix}_{9X3}$

$C_{j-1}=\begin{bmatrix}0_{3X3} \\ \Delta\tilde{R}_{i,j-1}\Delta{t} \\ \frac{1}{2}\Delta\tilde{R}_{i,j-1} \Delta{t}^2\end{bmatrix}_{9X3}$

而写成协方差形式为:

$\sum_{ij}= A_{j-1}\sum_{i,j-1}A_{j-1}^T + B_{j-1}\eta_{j-1}^{gd}B_{j-1}^T + C_{j-1}\eta_{j-1}^{ad}C_{j-1}^T$

(4)的偏差更新中雅可比递推形式如下:

$\frac{\partial\Delta\bar{R}_{ij}}{\partial{b^g}} = -\sum^{j-1}_{k=i}\left[ \Delta\tilde{R}_{k+1,j}\left(\bar{b}_i\right)^T{J_r^k}\Delta{t}\right] $

$= -\sum^{j-1}_{k=i}\left[ \Delta\tilde{R}_{j,k+1}{J_r^k}\Delta{t}\right] $

推导:$\frac{\partial\Delta\bar{R}_{i,j+1}}{\partial{b^g}} = -\sum^{j}_{k=i}\left[ \Delta\tilde{R}_{j+1,k+1}{J_r^k}\Delta{t}\right]$

$=- \Delta{\tilde{R}_{j+1,j}}\left[ \sum_{k=i}^j \Delta{\tilde{R}_{j,k+1}}J_r^k \Delta{t}\right]$

$=- \Delta{\tilde{R}_{j+1,j}}\left[ \sum_{k=i}^{j-1} \Delta{\tilde{R}_{j,k+1}}J_r^k \Delta{t} + \Delta{\tilde{R}_{j,j+1}}J^j_r\Delta{t}\right]$

$= \Delta{\tilde{R}_{j+1,j}}\left[- \sum_{k=i}^{j-1} \Delta{\tilde{R}_{k+1,j}^T}J_r^k \Delta{t}\right]-J_r^j\Delta{t}$

$= \Delta\tilde{R}^T_{j,j+1}\frac{\partial\Delta\bar{R}_{ij}}{\partial{b^g}}-J_r^j\Delta{t}$

$\frac{\partial\Delta\bar{V}_{ij}}{\partial{b^a}} = -\sum^{j-1}_{k=i} \Delta\bar{R}_{ik}\Delta{t}$

推导:$\frac{\partial\Delta\bar{V}_{i,j+1}}{\partial{b^a}} = -\sum^{j}_{k=i} \Delta\bar{R}_{ik}\Delta{t}$

$=-\left(\Delta\bar{R}_{ij}\Delta{t} + \sum^{j-1}_{k=i} \Delta\bar{R}_{ik}\Delta{t}\right)$

$= \frac{\partial\Delta\bar{V}_{ij}}{\partial{b^a}}-\Delta\bar{R}_{ij}\Delta{t}$

$\frac{\partial\Delta\bar{V}_{ij}}{\partial{b^g}} = -\sum^{j-1}_{k=i} \Delta\bar{R}_{ik} \left(\tilde{a}_k - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ik}}{\partial{b^g}}\Delta{t}$

推导:$\frac{\partial\Delta\bar{V}_{i,j+1}}{\partial{b^g}} = -\sum^{j}_{k=i} \Delta\bar{R}_{ik} \left(\tilde{a}_k - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ik}}{\partial{b^g}}\Delta{t}$

$=-\Delta\bar{R}_{ij} \left(\tilde{a}_j - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ij}}{\partial{b^g}}\Delta{t}-\sum^{j-1}_{k=i} \Delta\bar{R}_{ik} \left(\tilde{a}_k - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ik}}{\partial{b^g}}\Delta{t}$

$= \frac{\partial\Delta\bar{V}_{ij}}{\partial{b^g}}-\Delta\bar{R}_{ij} \left(\tilde{a}_j - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ij}}{\partial{b^g}}\Delta{t}$

$\frac{\partial\Delta\bar{P}_{ij}}{\partial{b^a}} = \sum^{j-1}_{k=i} \frac{\partial\Delta\bar{V}_{ik}}{\partial{b^a}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ik}\Delta{t^2} $

推导:$\frac{\partial\Delta\bar{P}_{i,j+1}}{\partial{b^a}} = \sum^{j}_{k=i} \frac{\partial\Delta\bar{V}_{ik}}{\partial{b^a}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ik}\Delta{t^2}$

$=\frac{\partial\Delta\bar{V}_{ij}}{\partial{b^a}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ij}\Delta{t^2}+\sum^{j-1}_{k=i} \left(\frac{\partial\Delta\bar{V}_{ik}}{\partial{b^a}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ik}\Delta{t^2}\right)$

$= \frac{\partial\Delta\bar{P}_{ij}}{\partial{b^a}}+\left( \frac{\partial\Delta\bar{V}_{ij}}{\partial{b^a}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ij}\Delta{t^2} \right)$

$\frac{\partial\Delta\bar{P}_{ij}}{\partial{b^g}} = \sum^{j-1}_{k=i} \frac{\partial\Delta\bar{V}_{ik}}{\partial{b^g}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ik}\left(\tilde{a}_k - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ik}}{\partial{b^g}}\Delta{t}^2$

推导:$\frac{\partial\Delta\bar{P}_{i,j+1}}{\partial{b^g}} = \sum^{j}_{k=i} \left( \frac{\partial\Delta\bar{V}_{ik}}{\partial{b^g}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ik}\left(\tilde{a}_k - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ik}}{\partial{b^g}}\Delta{t}^2\right)$

$=\left(\frac{\partial\Delta\bar{V}_{ij}}{\partial{b^g}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ij}\left(\tilde{a}_j - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ij}}{\partial{b^g}}\Delta{t}^2\right) + \sum^{j-1}_{k=i} \left( \frac{\partial\Delta\bar{V}_{ik}}{\partial{b^g}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ik}\left(\tilde{a}_k - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ik}}{\partial{b^g}}\Delta{t}^2 \right)$

$=\frac{\partial\Delta\bar{P}_{ij}}{\partial{b^g}}+ \left( \frac{\partial\Delta\bar{V}_{ij}}{\partial{b^g}}\Delta{t}-\frac{1}{2}\Delta\bar{R}_{ij}\left(\tilde{a}_j - \bar{b}_i^a\right)^{\wedge}   \frac{\partial\Delta\bar{R}_{ij}}{\partial{b^g}}\Delta{t}^2 \right)$

不含噪声的递推公式

$\Delta\tilde{P}_{i,j+1} = \Delta\tilde{P}_{i,j} + \Delta\tilde{V}_{i,j}\Delta{t}+\frac{1}{2}\Delta\tilde{R}_{i,j}\left( \tilde{a}_j - \bar{b}^a_i\right)^{\wedge}\Delta{t^2}$

$\Delta\tilde{V}_{i,j+1} = \Delta\tilde{V}_{i,j}+\Delta\tilde{R}_{i,j}\left( \tilde{a}_j - \bar{b}^a_i\right)^{\wedge}\Delta{t} $

$\Delta\tilde{R}_{i,j+1} = \Delta\tilde{R}_{i,j}Exp\left[ \left( \tilde{\omega_j} - \bar{b_i^g}\right)^{\wedge}\Delta{t}\right]$

到此已经知道了delta measurements,jacobians,covariance matrix这三个部分的更新了。

  1. // incrementally update 1)delta measurements, 2)jacobians, 3)covariance matrix
  2. // acc: acc_measurement - bias_a, last measurement!! not current measurement
  3. // omega: gyro_measurement - bias_g, last measurement!! not current measurement
    {
  4. void IMUPreintegrator::update(const Vector3d &omega, const Vector3d &acc, const double &dt) {
  5. double dt2 = dt * dt;
  6.  
  7. Matrix3d dR = Expmap(omega * dt);//上一次的测试
  8. Matrix3d Jr = JacobianR(omega * dt);
  9. // noise covariance propagation of delta measurements
  10. // err_k+1 = A*err_k + B*err_gyro + C*err_acc
  11. Matrix3d I3x3 = Matrix3d::Identity();
  12. Matrix<double, , > A = Matrix<double, , >::Identity();
  13. A.block<, >(, ) = dR.transpose();
  14. A.block<, >(, ) = -_delta_R * skew(acc) * dt;
  15. A.block<, >(, ) = -0.5 * _delta_R * skew(acc) * dt2;
  16. A.block<, >(, ) = I3x3 * dt;
  17.  
  18. Matrix<double, , > Bg = Matrix<double, , >::Zero();
  19. Bg.block<, >(, ) = Jr * dt;
  20.  
  21. Matrix<double, , > Ca = Matrix<double, , >::Zero();
  22. Ca.block<, >(, ) = _delta_R * dt;
  23. Ca.block<, >(, ) = 0.5 * _delta_R * dt2;
  24. //协方差
  25. _cov_P_V_Phi = A * _cov_P_V_Phi * A.transpose() +
  26. Bg * IMUData::getGyrMeasCov() * Bg.transpose() +
  27. Ca * IMUData::getAccMeasCov() * Ca.transpose();
  28. // jacobian of delta measurements w.r.t bias of gyro/acc
  29. // update P first, then V, then R
  30. _J_P_Biasa += _J_V_Biasa * dt - 0.5 * _delta_R * dt2;
  31. _J_P_Biasg += _J_V_Biasg * dt - 0.5 * _delta_R * skew(acc) * _J_R_Biasg * dt2;
  32. _J_V_Biasa += -_delta_R * dt;
  33. _J_V_Biasg += -_delta_R * skew(acc) * _J_R_Biasg * dt;
  34. _J_R_Biasg = dR.transpose() * _J_R_Biasg - Jr * dt;
  35.  
  36. // delta measurements, position/velocity/rotation(matrix)
  37. // update P first, then V, then R. because P's update need V&R's previous state
  38.  
  39. _delta_P += _delta_V * dt + 0.5 * _delta_R * acc * dt2; // P_k+1 = P_k + V_k*dt + R_k*a_k*dt*dt/2
  40. _delta_V += _delta_R * acc * dt;
  41. _delta_R = normalizeRotationM(_delta_R * dR); // normalize rotation, in case of numerical error accumulation
  42. // // noise covariance propagation of delta measurements
  43. // // err_k+1 = A*err_k + B*err_gyro + C*err_acc
  44. // Matrix3d I3x3 = Matrix3d::Identity();
  45. // MatrixXd A = MatrixXd::Identity(9,9);
  46. // A.block<3,3>(6,6) = dR.transpose();
  47. // A.block<3,3>(3,6) = -_delta_R*skew(acc)*dt;
  48. // A.block<3,3>(0,6) = -0.5*_delta_R*skew(acc)*dt2;
  49. // A.block<3,3>(0,3) = I3x3*dt;
  50. // MatrixXd Bg = MatrixXd::Zero(9,3);
  51. // Bg.block<3,3>(6,0) = Jr*dt;
  52. // MatrixXd Ca = MatrixXd::Zero(9,3);
  53. // Ca.block<3,3>(3,0) = _delta_R*dt;
  54. // Ca.block<3,3>(0,0) = 0.5*_delta_R*dt2;
  55. // _cov_P_V_Phi = A*_cov_P_V_Phi*A.transpose() +
  56. // Bg*IMUData::getGyrMeasCov*Bg.transpose() +
  57. // Ca*IMUData::getAccMeasCov()*Ca.transpose();
  58.  
  59. // delta time
  60. _delta_time += dt;
  61.  
  62. }
    }

下面按照图优化的思路,建立VIO的图模型

图优化的模型如上图所示。

红色圆形节点中的量为$\delta{b^a}$,$\delta{b^g}$,因为$b\gets\bar{b}+\delta{b}$,所以$\delta{b}$被优化后相当于偏置也被更新了。

三角形黑色节点的量为IMU的状态,(R,P,V)。

四边形蓝色节点的量为世界坐标下的三维点坐标,(X,Y,Z)。

青色的五边形节点的量为(R,P,V,$\delta{b^a}$,$\delta{b^g}$)

黑色的圆形节点的量为世界坐标系下的重力加速度g。

紫色的圆形节点的量为陀螺仪的偏置$b^g$

各边的误差,及雅可比计算

参考ORB-YGZ-SLAM中设置节点与边的方式

误差函数为论文【1】中公式45

$r_{\Delta{R_{ij}}} = Log\left( \left( \Delta\tilde{R}_{ij}\left( \bar{b}_i^g\right) Exp\left(\frac{\partial\Delta\bar{R}_{ij}} {\partial{b^g}} \delta{b^g} \right) \right) ^T R_i^T{R_j}\right)$

$r_{\Delta{V_{ij}}} = R_{i}^{T}\left( V_j - V_i - g\Delta{t_{ij}} \right) - \left[\Delta\tilde{V}_{ij}\left( \bar{b}_i^g,\bar{b}_i^a\right) +\frac{\partial\Delta\bar{V}_{ij}} {\partial{b^g}} \delta{b^g} + \frac{\partial\Delta\bar{V}_{ij}} {\partial{b^a}} \delta{b^a} \right]$

$r_{\Delta{P_{ij}}} = R_{i}^{T}\left( P_j - P_i -V_i\Delta{t_{ij}}-\frac{1}{2} g\Delta{t_{ij}^2} \right) - \left[ \Delta\tilde{P}_{ij}\left( \bar{b}_i^g,\bar{b}_i^a\right) +\frac{\partial\Delta\bar{P}_{ij}} {\partial{b^g}} \delta{b^g} + \frac{\partial\Delta\bar{P}_{ij}} {\partial{b^a}} \delta{b^a} \right]$

误差程序实现

  1. void EdgeNavStatePVR::computeError() {
  2. //
  3. const VertexNavStatePVR *vPVRi = static_cast<const VertexNavStatePVR *>(_vertices[]);
  4. const VertexNavStatePVR *vPVRj = static_cast<const VertexNavStatePVR *>(_vertices[]);
  5. const VertexNavStateBias *vBiasi = static_cast<const VertexNavStateBias *>(_vertices[]);
  6.  
  7. // terms need to computer error in vertex i, except for bias error
  8. const NavState &NSPVRi = vPVRi->estimate();
  9. Vector3d Pi = NSPVRi.Get_P();
  10. Vector3d Vi = NSPVRi.Get_V();
  11. SO3d Ri = NSPVRi.Get_R();
  12. // Bias from the bias vertex
  13. const NavState &NSBiasi = vBiasi->estimate();
  14. Vector3d dBgi = NSBiasi.Get_dBias_Gyr();
  15. Vector3d dBai = NSBiasi.Get_dBias_Acc();
  16.  
  17. // terms need to computer error in vertex j, except for bias error
  18. const NavState &NSPVRj = vPVRj->estimate();
  19. Vector3d Pj = NSPVRj.Get_P();
  20. Vector3d Vj = NSPVRj.Get_V();
  21. SO3d Rj = NSPVRj.Get_R();
  22.  
  23. // IMU Preintegration measurement
  24. const IMUPreintegrator &M = _measurement; //预积分类,实际值
  25. double dTij = M.getDeltaTime(); // Delta Time
  26. double dT2 = dTij * dTij;
  27. Vector3d dPij = M.getDeltaP(); // Delta Position pre-integration measurement //测量出来的实际deltaP
  28. Vector3d dVij = M.getDeltaV(); // Delta Velocity pre-integration measurement
  29. Sophus::SO3d dRij = Sophus::SO3(M.getDeltaR()); // Delta Rotation pre-integration measurement
  30.  
  31. // tmp variable, transpose of Ri
  32. Sophus::SO3d RiT = Ri.inverse();
  33. // residual error of Delta Position measurement
  34. Vector3d rPij = RiT * (Pj - Pi - Vi * dTij - 0.5 * GravityVec * dT2)
  35. - (dPij + M.getJPBiasg() * dBgi +
  36. M.getJPBiasa() * dBai); // this line includes correction term of bias change.
  37. // residual error of Delta Velocity measurement
  38. Vector3d rVij = RiT * (Vj - Vi - GravityVec * dTij)
  39. - (dVij + M.getJVBiasg() * dBgi +
  40. M.getJVBiasa() * dBai); //this line includes correction term of bias change
  41. // residual error of Delta Rotation measurement
  42. Sophus::SO3d dR_dbg = Sophus::SO3d::exp(M.getJRBiasg() * dBgi);
  43. Sophus::SO3d rRij = (dRij * dR_dbg).inverse() * RiT * Rj;
  44. Vector3d rPhiij = rRij.log();
  45.  
  46. Vector9d err; // typedef Matrix<double, D, 1> ErrorVector; ErrorVector _error; D=9
  47. err.setZero();
  48.  
  49. // 9-Dim error vector order:
  50. // position-velocity-rotation
  51. // rPij - rVij - rPhiij
  52. err.segment<>() = rPij; // position error
  53. err.segment<>() = rVij; // velocity error
  54. err.segment<>() = rPhiij; // rotation phi error
  55.  
  56. _error = err;
  57. }

雅克比

对3个部分的误差$\left[r_{\Delta{P_{ij}}},r_{\Delta{V_{ij}}} ,  r_{\Delta{R_{ij}}}\right]$求8个部分的被优化项$\left[{P_i}, {V_i},{\phi_i},{P_j}, {V_j},{\phi_j},\tilde{\delta}b_i^g,\tilde{\delta}b_i^a\right]$的雅克比,总共24个部分。

i:

$\frac{\partial{r}_{\Delta{P_{ij}}}}{\partial\delta{P_i}} = -I_{3X1} $ , $ \frac{\partial{r}_{\Delta{V_{ij}}}}{\partial\delta{P_i}} = 0$, $ \frac{\partial{r}_{\Delta{R_{ij}}}}{\partial\delta{P_i}} = 0$

$\frac{\partial{r}_{\Delta{P_{ij}}}}{\partial\delta{V_i}} = -R_i^T\Delta{t}_{ij}$, $\frac{\partial{r}{_\Delta{V_{ij}}}}{\partial\delta{V_i}} = -R_i^T$, $\frac{\partial{r}_{\Delta{R_{ij}}}}{\partial\delta{V_i}} = 0$

$\frac{\partial{r}_{\Delta{P_{ij}}}}{\partial\delta{\phi_i}} = \left( R_i^T \left( P_j-P_i-V_i\Delta{t_{ij}}-\frac{1}{2}g\Delta{t_{ij}^2}\right)\right)^{\wedge}$, $\frac{\partial{r}_{\Delta{V_{ij}}}}{\partial\delta{\phi_i}}=\left(R_i^T\left( V_j- V_i-g\Delta{t_{ij}}\right)\right)^{\wedge}$, $\frac{\partial{r}_{\Delta{R_{ij}}}}{\partial\delta{\phi_i}} = -J_r^{-1}\left(r{}_{\Delta{R}}\left(R_i\right)\right)R^T_j{R_i}$

j:

$\frac{\partial{r}_{\Delta{P_{ij}}}}{\partial\delta{P_j}} = R_i^T{R_j}$, $\frac{\partial{r}_{\Delta{V_{ij}}}}{\partial\delta{P_j}} = 0$, $\frac{\partial{r}_{\Delta{R_{ij}}}}{\partial\delta{P_j}} = 0$

$\frac{\partial{r}_{\Delta{P_{ij}}}}{\partial\delta{V_j}} = 0$, $\frac{\partial{r}_{\Delta{V_{ij}}}}{\partial\delta{V_j}} = R_i^T$, $\frac{\partial{r}_{\Delta{R_{ij}}}}{\partial\delta{V_j}} = 0$

$\frac{\partial{r}_{\Delta{P_{ij}}}}{\partial\delta{\phi_j}} = 0$, $\frac{\partial{r}_{\Delta{V_{ij}}}}{\partial\delta{\phi_j}} = 0$, $\frac{\partial{r}_{\Delta{R_{ij}}}}{\partial\delta{\phi_j}} = J_r^{-1}\left(r{}_{\Delta{R}}\left(R_j\right)\right)$

$\tilde{\delta}{b^g_i}$,$\tilde{\delta}{b^a_i}$:

$\frac{\partial{r_{\Delta{P_{ij}}}}}{\partial\tilde{\delta}{b^g_i}}=-\frac{\partial\Delta\bar{P}_{ij}}{\partial{b_i^g}}$, $\frac{\partial{r_{\Delta{V_{ij}}}}}{\partial\tilde{\delta}{b^g_i}}=-\frac{\partial\Delta\bar{V}_{ij}}{\partial{b_i^g}}$,$\frac{\partial{r_{\Delta{R_{ij}}}}}{\partial\tilde{\delta}{b^g_i}}=\alpha$

$\frac{\partial{r_{\Delta{P_{ij}}}}}{\partial\tilde{\delta}{b^a_i}}=-\frac{\partial\Delta\bar{P}_{ij}}{\partial{b_i^a}}$, $\frac{\partial{r_{\Delta{V_{ij}}}}}{\partial\tilde{\delta}{b^a_i}}=-\frac{\partial\Delta\bar{V}_{ij}}{\partial{b_i^a}}$,$\frac{\partial{r_{\Delta{R_{ij}}}}}{\partial\tilde{\delta}{b^a_i}}=0$

其中$\alpha = -J_r^{-1}\left( r_{\Delta{R_{ij}}} \left( \delta{b}_i^g\right)\right) Exp\left( r_{\Delta{R}_{ij}}\left(\delta{b}_i^g\right)\right)^T {J}^b_r\frac{\partial\Delta\bar{R}_{ij}}{\partial{b^g}}$

雅克比程序实现

  1. void EdgeNavStatePVR::linearizeOplus() {
  2. //
  3. const VertexNavStatePVR *vPVRi = static_cast<const VertexNavStatePVR *>(_vertices[]);
  4. const VertexNavStatePVR *vPVRj = static_cast<const VertexNavStatePVR *>(_vertices[]);
  5. const VertexNavStateBias *vBiasi = static_cast<const VertexNavStateBias *>(_vertices[]);
  6.  
  7. // terms need to computer error in vertex i, except for bias error
  8. const NavState &NSPVRi = vPVRi->estimate();
  9. Vector3d Pi = NSPVRi.Get_P();
  10. Vector3d Vi = NSPVRi.Get_V();
  11. Matrix3d Ri = NSPVRi.Get_RotMatrix();
  12. // bias
  13. const NavState &NSBiasi = vBiasi->estimate();
  14. Vector3d dBgi = NSBiasi.Get_dBias_Gyr();//陀螺仪
  15. // Vector3d dBai = NSBiasi.Get_dBias_Acc();
  16.  
  17. // terms need to computer error in vertex j, except for bias error
  18. const NavState &NSPVRj = vPVRj->estimate();
  19. Vector3d Pj = NSPVRj.Get_P();
  20. Vector3d Vj = NSPVRj.Get_V();
  21. Matrix3d Rj = NSPVRj.Get_RotMatrix();
  22.  
  23. // IMU Preintegration measurement
  24. const IMUPreintegrator &M = _measurement;
  25. double dTij = M.getDeltaTime(); // Delta Time
  26. double dT2 = dTij * dTij;
  27.  
  28. // some temp variable
  29. Matrix3d I3x3 = Matrix3d::Identity(); // I_3x3
  30. Matrix3d O3x3 = Matrix3d::Zero(); // 0_3x3
  31. Matrix3d RiT = Ri.transpose(); // Ri^T
  32. Matrix3d RjT = Rj.transpose(); // Rj^T
  33. Vector3d rPhiij = _error.segment<>(); // residual of rotation, rPhiij
  34. Matrix3d JrInv_rPhi = Sophus::SO3::JacobianRInv(rPhiij); // inverse right jacobian of so3 term #rPhiij#
  35. Matrix3d J_rPhi_dbg = M.getJRBiasg(); // jacobian of preintegrated rotation-angle to gyro bias i
  36. // 1.
  37. // increment is the same as Forster 15'RSS
  38. // pi = pi + Ri*dpi, pj = pj + Rj*dpj
  39. // vi = vi + dvi, vj = vj + dvj
  40. // Ri = Ri*Exp(dphi_i), Rj = Rj*Exp(dphi_j)
  41. // Note: the optimized bias term is the 'delta bias'
  42. // dBgi = dBgi + dbgi_update, dBgj = dBgj + dbgj_update
  43. // dBai = dBai + dbai_update, dBaj = dBaj + dbaj_update
  44.  
  45. // 2.
  46. // 9-Dim error vector order in PVR:
  47. // position-velocity-rotation
  48. // rPij - rVij - rPhiij
  49. // Jacobian row order:
  50. // J_rPij_xxx
  51. // J_rVij_xxx
  52. // J_rPhiij_xxx
  53.  
  54. // 3.
  55. // order in 'update_' in PVR
  56. // Vertex_i : dPi, dVi, dPhi_i
  57. // Vertex_j : dPj, dVj, dPhi_j
  58. // 6-Dim error vector order in Bias:
  59. // dBiasg_i - dBiasa_i
  60.  
  61. // 4.
  62. // For Vertex_PVR_i
  63. Matrix<double, , > JPVRi;
  64. JPVRi.setZero();
  65.  
  66. // 4.1
  67. // J_rPij_xxx_i for Vertex_PVR_i
  68. JPVRi.block<, >(, ) = -I3x3; //J_rP_dpi
  69. JPVRi.block<, >(, ) = -RiT * dTij; //J_rP_dvi
  70. JPVRi.block<, >(, ) = Sophus::SO3::hat(
  71. RiT * (Pj - Pi - Vi * dTij - 0.5 * GravityVec * dT2)); //J_rP_dPhi_i
  72.  
  73. // 4.2
  74. // J_rVij_xxx_i for Vertex_PVR_i
  75. JPVRi.block<, >(, ) = O3x3; //dpi
  76. JPVRi.block<, >(, ) = -RiT; //dvi
  77. JPVRi.block<, >(, ) = Sophus::SO3::hat(RiT * (Vj - Vi - GravityVec * dTij)); //dphi_i
  78.  
  79. // 4.3
  80. // J_rPhiij_xxx_i for Vertex_PVR_i
  81. Matrix3d ExprPhiijTrans = Sophus::SO3::exp(rPhiij).inverse().matrix();
  82. Matrix3d JrBiasGCorr = Sophus::SO3::JacobianR(J_rPhi_dbg * dBgi);
  83. JPVRi.block<, >(, ) = O3x3; //dpi
  84. JPVRi.block<, >(, ) = O3x3; //dvi
  85. JPVRi.block<, >(, ) = -JrInv_rPhi * RjT * Ri; //dphi_i
  86. // 5.
  87. // For Vertex_PVR_j
  88. Matrix<double, , > JPVRj;
  89. JPVRj.setZero();
  90.  
  91. // 5.1
  92. // J_rPij_xxx_j for Vertex_PVR_j
  93. JPVRj.block<, >(, ) = RiT * Rj; //dpj
  94. JPVRj.block<, >(, ) = O3x3; //dvj
  95. JPVRj.block<, >(, ) = O3x3; //dphi_j
  96.  
  97. // 5.2
  98. // J_rVij_xxx_j for Vertex_PVR_j
  99. JPVRj.block<, >(, ) = O3x3; //dpj
  100. JPVRj.block<, >(, ) = RiT; //dvj
  101. JPVRj.block<, >(, ) = O3x3; //dphi_j
  102.  
  103. // 5.3
  104. // J_rPhiij_xxx_j for Vertex_PVR_j
  105. JPVRj.block<, >(, ) = O3x3; //dpj
  106. JPVRj.block<, >(, ) = O3x3; //dvj
  107. JPVRj.block<, >(, ) = JrInv_rPhi; //dphi_j
  108.  
  109. // 6.
  110. // For Vertex_Bias_i
  111. Matrix<double, , > JBiasi;
  112. JBiasi.setZero();
  113.  
  114. // 5.1
  115. // J_rPij_xxx_j for Vertex_Bias_i
  116. JBiasi.block<, >(, ) = -M.getJPBiasg(); //J_rP_dbgi
  117. JBiasi.block<, >(, ) = -M.getJPBiasa(); //J_rP_dbai
  118.  
  119. // J_rVij_xxx_j for Vertex_Bias_i
  120. JBiasi.block<, >(, ) = -M.getJVBiasg(); //dbg_i
  121. JBiasi.block<, >(, ) = -M.getJVBiasa(); //dba_i
  122.  
  123. // J_rPhiij_xxx_j for Vertex_Bias_i
  124. JBiasi.block<, >(, ) = -JrInv_rPhi * ExprPhiijTrans * JrBiasGCorr * J_rPhi_dbg; //dbg_i
  125. JBiasi.block<, >(, ) = O3x3; //dba_i
  126.  
  127. // Evaluate _jacobianOplus
  128. _jacobianOplus[] = JPVRi;
  129. _jacobianOplus[] = JPVRj;
  130. _jacobianOplus[] = JBiasi;
  131. }

偏置误差

$r = \begin{bmatrix} \left(b_j^g+\delta b_j^g\right) - \left( b_i^g+\delta b_i^g\right) \\ \left(b_j^a+\delta b_j^a\right) - \left( b_i^a+\delta b_i^a\right) \end{bmatrix}$

误差程序实现

  1. void EdgeNavStateBias::computeError() {
  2. const VertexNavStateBias *vBiasi = static_cast<const VertexNavStateBias *>(_vertices[]);
  3. const VertexNavStateBias *vBiasj = static_cast<const VertexNavStateBias *>(_vertices[]);
  4.  
  5. const NavState &NSi = vBiasi->estimate();
  6. const NavState &NSj = vBiasj->estimate();
  7.  
  8. // residual error of Gyroscope's bias, Forster 15'RSS
  9. Vector3d rBiasG = (NSj.Get_BiasGyr() + NSj.Get_dBias_Gyr())
  10. - (NSi.Get_BiasGyr() + NSi.Get_dBias_Gyr());
  11.  
  12. // residual error of Accelerometer's bias, Forster 15'RSS
  13. Vector3d rBiasA = (NSj.Get_BiasAcc() + NSj.Get_dBias_Acc()) //不是估计值与实际值之差,而是前后之差
  14. - (NSi.Get_BiasAcc() + NSi.Get_dBias_Acc());
  15.  
  16. Vector6d err; // typedef Matrix<double, D, 1> ErrorVector; ErrorVector _error; D=6
  17. err.setZero();
  18. // 6-Dim error vector order: //error是六维的
  19. // deltabiasGyr_i-deltabiasAcc_i
  20. // rBiasGi - rBiasAi
  21. err.segment<>() = rBiasG; // bias gyro error
  22. err.segment<>() = rBiasA; // bias acc error
  23.  
  24. _error = err;
  25. }

被优化项

节点i:  $\left[ \delta b_i^g,\delta b_i^a\right]$,节点j:  $\left[ \delta b_j^g, \delta b_j^a \right]$

偏置雅克比

$\frac{\partial r}{\partial \left[ \delta b_i^g,\delta b_i^a\right] } =  \begin{bmatrix} -I_3 & 0 \\ 0 & -I_3 \end{bmatrix}$,$\frac{\partial r}{\partial \left[ \delta b_j^g,\delta b_j^a\right] } =  \begin{bmatrix} I_3 & 0 \\ 0 & I_3 \end{bmatrix}$

雅克比代码实现

  1. void EdgeNavStateBias::linearizeOplus() {
  2. // 6-Dim error vector order:
  3. // deltabiasGyr_i-deltabiasAcc_i
  4. // rBiasGi - rBiasAi
  5.  
  6. _jacobianOplusXi = -Matrix<double, , >::Identity();
  7. _jacobianOplusXj = Matrix<double, , >::Identity();
  8. }

世界坐标系中空间点三维坐标经IMU坐标系转为像素二维坐标:

$P_b = \left(R_{bc}P_c + t_{bc}\right), P_w = \left( R_{wb}P_b + t_{wb}\right)$

$P_w = R_{wb}\left( R_{bc}P_c + t_{bc}\right) + t_{wb}$

$P_c = R_{cb}\left[ R_{wb}^T \left( P_w - t_{wb}\right) - t_{bc}\right]$

投影误差

_error = _measurement(测量值) - p(像素坐标估计值)

设$P_w = \left[ X, Y, Z\right]$,$P_c = \left[X^{'},Y^{'},Z^{'}\right]$

$p = \begin{bmatrix} u \\ v \end{bmatrix} = \begin{bmatrix} f_x\left( \frac{X^{'}}{Z^{'}}\right)+c_x \\ f_y\left( \frac{Y^{'}}{Z^{'}}\right)+c_y \end{bmatrix} $

投影误差代码实现

  1. void computeError() {
  2. Vector3d Pc = computePc();
  3. Vector2d obs(_measurement);//像素坐标,实际
  4. _error = obs - cam_project(Pc);//Pc为在相机坐标系下三维点,cam_project()将Pc转为像素坐标,误差为二维
  5. }
  6. bool isDepthPositive() {
  7. Vector3d Pc = computePc();
  8. return Pc() > 0.0;
  9. }
  10. Vector3d computePc() {
  11. const VertexSBAPointXYZ *vPoint = static_cast<const VertexSBAPointXYZ *>(_vertices[]);//三维点
  12. const VertexNavStatePVR *vNavState = static_cast<const VertexNavStatePVR *>(_vertices[]);//imu,p,v,r
  13.  
  14. const NavState &ns = vNavState->estimate();
  15. Matrix3d Rwb = ns.Get_RotMatrix(); //矩阵形式
  16. Vector3d Pwb = ns.Get_P();
  17. const Vector3d &Pw = vPoint->estimate();
  18.  
  19. Matrix3d Rcb = Rbc.transpose();//相机与imu之间的关系
  20. Vector3d Pc = Rcb * Rwb.transpose() * (Pw - Pwb) - Rcb * Pbc;
  21.  
  22. return Pc;
  23. }
  24.  
  25. inline Vector2d project2d(const Vector3d &v) const {//相机坐标系下三维点转为均一化坐标
  26. Vector2d res;
  27. res() = v() / v();
  28. res() = v() / v();
  29. return res;
  30. }

雅克比

优化项:$P_w$

$\frac{\partial{error}}{\partial{P_w}}=-\frac{\partial{p}}{\partial{P_w}} =-\frac{\partial{p}}{\partial{P_c}}\frac{\partial P_c}{\partial P_w} $

$\frac{\partial p}{\partial P_c} =  \begin{bmatrix} f_x\frac{1}{Z^{'}} & 0 & -f_x\frac{X^{'}}{Z^{'2}} \\ 0 & f_y\frac{1}{Z^{'}} & -f_y\frac{Y^{'}}{Z^{'2}} \end{bmatrix} $, $\frac{\partial P_c}{\partial P_w} = R_{cb}R_{wb}^T$

优化项:$\left[ \delta P , \delta V , \delta R \right]  = \left[ \delta P_{wb}, \delta V_{wb} , \delta R_{wb} \right] $

$ \frac{\partial{error}}{\partial{  \left[ \delta P_{wb}, \delta V_{wb} , \delta R_{wb} \right]  }}=-\frac{\partial{p}}{\partial{   \left[ \delta P_{wb}, \delta V_{wb} , \delta R_{wb} \right] }} = -\frac{\partial{p}}{\partial{P_c}}\frac{\partial P_c}{\partial \left[ \delta P_{wb}, \delta V_{wb} , \delta R_{wb} \right] }$

$\frac{\partial P_c}{\partial \delta P_{wb}} = \lim_\limits{\delta P_{wb}\to 0}\frac{           R_{cb}\left[ R_{wb}^T \left(     P_w - \left(  P_{wb}  + R_{wb}\delta P_{wb} \right)      \right) - P_{bc}\right]       -R_{cb}\left[ R_{wb}^T \left( P_w - P_{wb} \right) - P_{bc}\right] } {\delta P_{wb}}  = -R_{cb}$, $ P_w$为世界坐标系下三维点坐标。

$\frac{\partial P_c}{\partial \delta V_{wb}} = 0$

$\frac{\partial P_c}{\partial \delta \phi_{wb}} = \lim_\limits{\delta \phi_{wb}\to 0}\frac{         R_{cb}\left[    \left( R_{wb}Exp\left(   \delta \phi_{wb}^{\wedge}  \right) \right)^T \left( P_w - P_{wb} \right) - P_{bc}\right]              -R_{cb}\left[ R_{wb}^T \left( P_w - P_{wb} \right) - P_{bc}\right] } {\delta \phi_{wb}}  = \lim_\limits{\delta \phi_{wb}\to 0}\frac{         R_{cb}\left[          \left( Exp\left(  \delta \phi _{wb}^{\wedge} \right)\right)^T R_{wb}^T           \left( P_w - P_{wb} \right) - P_{bc}\right]      -R_{cb}\left[ R_{wb}^T \left( P_w - P_{wb} \right) - P_{bc}\right] } {\delta \phi_{wb}} $

$ = \lim_\limits{\delta \phi_{wb}\to 0}\frac{         R_{cb}\left[          \left(  I - \delta \phi_{wb} ^{\wedge}    \right)   R_{wb}^T           \left( P_w - P_{wb} \right) - P_{bc}\right]      -R_{cb}\left[ R_{wb}^T \left( P_w - P_{wb} \right) - P_{bc}\right] } {\delta \phi_{wb}} = \lim_\limits{\delta \phi_{wb}\to 0}\frac{         -R_{cb}\left[           \delta \phi_{wb} ^{\wedge}       R_{wb}^T           \left( P_w - P_{wb} \right) \right] } {\delta \phi_{wb}}=\lim_\limits{\delta \phi_{wb}\to 0}\frac{         -R_{cb}      R_{wb}^T   \left( R_{wb} \delta \phi_{wb}  \right)^{\wedge}        \left( P_w - P_{wb} \right) } {\delta \phi_{wb}}$

$= \lim_\limits{\delta \phi_{wb}\to 0}\frac{    R_{cb}      R_{wb}^T \left( P_w - P_{wb} \right) ^{\wedge} \left( R_{wb} \delta \phi_{wb}  \right) } {\delta \phi_{wb}} = \lim_\limits{\delta \phi_{wb}\to 0}\frac{    \left[ R_{cb} R_{wb}^T \left( P_w - P_{wb} \right) \right] ^{\wedge} R_{cb} R_{wb}^T\left( R_{wb} \delta \phi_{wb}  \right) } {\delta \phi_{wb}}$

$= \left[ R_{cb}R_{wb}^T \left(P_w-P_{wb}\right)\right]^{\wedge}R_{cb}$        推导用到伴随矩阵的性质,和论文公式(2)

雅克比程序实现:

  1. void EdgeNavStatePVRPointXYZ::linearizeOplus() {
  2. const VertexSBAPointXYZ *vPoint = static_cast<const VertexSBAPointXYZ *>(_vertices[0]);
  3. const VertexNavStatePVR *vNavState = static_cast<const VertexNavStatePVR *>(_vertices[1]);
  4.  
  5. const NavState &ns = vNavState->estimate();
  6. Matrix3d Rwb = ns.Get_RotMatrix();
  7. Vector3d Pwb = ns.Get_P();
  8. const Vector3d &Pw = vPoint->estimate();
  9.  
  10. Matrix3d Rcb = Rbc.transpose();
  11. Vector3d Pc = Rcb * Rwb.transpose() * (Pw - Pwb) - Rcb * Pbc;
  12.  
  13. double x = Pc[0];
  14. double y = Pc[1];
  15. double z = Pc[2];
  16.  
  17. // Jacobian of camera projection
  18. Matrix<double, 2, 3> Maux;
  19. Maux.setZero();
  20. Maux(0, 0) = fx;
  21. Maux(0, 1) = 0;
  22. Maux(0, 2) = -x / z * fx;
  23. Maux(1, 0) = 0;
  24. Maux(1, 1) = fy;
  25. Maux(1, 2) = -y / z * fy;
  26. Matrix<double, 2, 3> Jpi = Maux / z;
  27.  
  28. // error = obs - pi( Pc )
  29. // Pw <- Pw + dPw, for Point3D
  30. // Rwb <- Rwb*exp(dtheta), for NavState.R
  31. // Pwb <- Pwb + Rwb*dPwb, for NavState.P
  32.  
  33. // Jacobian of error w.r.t Pw
  34. _jacobianOplusXi = -Jpi * Rcb * Rwb.transpose();//空间三维点对误差函数求偏导
  35.  
  36. // Jacobian of Pc/error w.r.t dPwb
  37. Matrix<double, 2, 3> JdPwb = -Jpi * (-Rcb);//求NavState中P的偏导 ??
  38. // Jacobian of Pc/error w.r.t dRwb
  39. Vector3d Paux = Rcb * Rwb.transpose() * (Pw - Pwb);
  40. Matrix<double, 2, 3> JdRwb = -Jpi * (Sophus::SO3::hat(Paux) * Rcb); // ?????
  41.  
  42. // Jacobian of Pc w.r.t NavState
  43. // order in 'update_': dP, dV, dPhi
  44. Matrix<double, 2, 9> JNavState = Matrix<double, 2, 9>::Zero();
  45. JNavState.block<2, 3>(0, 0) = JdPwb;//跳过了(0.3),其实为对V求偏导,雅克比为0
  46. JNavState.block<2, 3>(0, 6) = JdRwb;
  47.  
  48. // Jacobian of error w.r.t NavState
  49. _jacobianOplusXj = JNavState;
  50. }

推导同上

误差程序实现:

  1. void computeError() {
  2. Vector3d Pc = computePc();
  3. Vector2d obs(_measurement);
  4.  
  5. _error = obs - cam_project(Pc);
  6. }
  7.  
  8. bool isDepthPositive() {//是否为正深度
  9. Vector3d Pc = computePc();
  10. return Pc() > 0.0;
  11. }
  12.  
  13. Vector3d computePc() {
  14. const VertexNavStatePVR *vNSPVR = static_cast<const VertexNavStatePVR *>(_vertices[]);
  15.  
  16. const NavState &ns = vNSPVR->estimate();
  17. Matrix3d Rwb = ns.Get_RotMatrix();
  18. Vector3d Pwb = ns.Get_P();
  19. //const Vector3d& Pw = vPoint->estimate();
  20.  
  21. Matrix3d Rcb = Rbc.transpose();
  22. Vector3d Pc = Rcb * Rwb.transpose() * (Pw - Pwb) - Rcb * Pbc;
  23.  
  24. return Pc;
  25. }
  26.  
  27. inline Vector2d project2d(const Vector3d &v) const {
  28. Vector2d res;
  29. res() = v() / v();
  30. res() = v() / v();
  31. return res;
  32. }
  33.  
  34. Vector2d cam_project(const Vector3d &trans_xyz) const {
  35. Vector2d proj = project2d(trans_xyz);
  36. Vector2d res;
  37. res[] = proj[] * fx + cx;
  38. res[] = proj[] * fy + cy;
  39. return res;
  40. }
  41.  
  42. virtual void linearizeOplus();
  43.  
  44. void SetParams(const double &fx_, const double &fy_, const double &cx_, const double &cy_,
  45. const Matrix3d &Rbc_, const Vector3d &Pbc_, const Vector3d &Pw_) {
  46. fx = fx_;
  47. fy = fy_;
  48. cx = cx_;
  49. cy = cy_;
  50. Rbc = Rbc_;
  51. Pbc = Pbc_;
  52. Pw = Pw_;
  53. }
  54.  
  55. void SetParams(const double &fx_, const double &fy_, const double &cx_, const double &cy_,
  56. const SO3d &Rbc_, const Vector3d &Pbc_, const Vector3d &Pw_) {
  57. fx = fx_;
  58. fy = fy_;
  59. cx = cx_;
  60. cy = cy_;
  61. Rbc = Rbc_.matrix();
  62. Pbc = Pbc_;
  63. Pw = Pw_; //Pw是参数?
  64. }
  65. protected:
  66. // Camera intrinsics
  67. double fx, fy, cx, cy;
  68. // Camera-IMU extrinsics
  69. Matrix3d Rbc;
  70. Vector3d Pbc;
  71. // Point position in world frame
  72. Vector3d Pw;
  73. };

雅克比程序实现:

  1. void EdgeNavStatePVRPointXYZOnlyPose::linearizeOplus() {
  2. const VertexNavStatePVR *vNSPVR = static_cast<const VertexNavStatePVR *>(_vertices[]);
  3.  
  4. const NavState &ns = vNSPVR->estimate();
  5. Matrix3d Rwb = ns.Get_RotMatrix();
  6. Vector3d Pwb = ns.Get_P();
  7.  
  8. Matrix3d Rcb = Rbc.transpose();
  9. Vector3d Pc = Rcb * Rwb.transpose() * (Pw - Pwb) - Rcb * Pbc;
  10.  
  11. double x = Pc[];
  12. double y = Pc[];
  13. double z = Pc[];
  14.  
  15. // Jacobian of camera projection
  16. Matrix<double, , > Maux;
  17. Maux.setZero();
  18. Maux(, ) = fx;
  19. Maux(, ) = ;
  20. Maux(, ) = -x / z * fx;
  21. Maux(, ) = ;
  22. Maux(, ) = fy;
  23. Maux(, ) = -y / z * fy;
  24. Matrix<double, , > Jpi = Maux / z;
  25.  
  26. // error = obs - pi( Pc )
  27. // Pw <- Pw + dPw, for Point3D
  28. // Rwb <- Rwb*exp(dtheta), for NavState.R
  29. // Pwb <- Pwb + Rwb*dPwb, for NavState.P
  30.  
  31. // Jacobian of Pc/error w.r.t dPwb
  32. //Matrix3d J_Pc_dPwb = -Rcb;
  33. Matrix<double, , > JdPwb = -Jpi * (-Rcb); //????????????
  34. // Jacobian of Pc/error w.r.t dRwb
  35. Vector3d Paux = Rcb * Rwb.transpose() * (Pw - Pwb);
  36. Matrix<double, , > JdRwb = -Jpi * (Sophus::SO3::hat(Paux) * Rcb); //??????????????
  37.  
  38. // Jacobian of Pc w.r.t NavStatePVR
  39. // order in 'update_': dP, dV, dPhi
  40. Matrix<double, , > JNavState = Matrix<double, , >::Zero();
  41. JNavState.block<, >(, ) = JdPwb;
  42. JNavState.block<, >(, ) = JdRwb;
  43.  
  44. // Jacobian of error w.r.t NavStatePVR
  45. _jacobianOplusXi = JNavState;
  46. }

不好意思,烂尾了,欢迎交流

参考论文

[1]Christian Forster, Luca Carlone, Frank Dellaert, Davide Scaramuzza,“On-Manifold Preintegration for Real-Time Visual-Inertial Odometry”,in IEEE Transactions on Robotics, 2016.

VIO的Bundle Adjustment推导的更多相关文章

  1. bundle adjustment 玩具程序

    结合 bundle adjustment原理(1) 和 Levenberg-Marquardt 的 MATLAB 代码 两篇博客的成果,调用MATLAB R2016a中 bundleAdjustmen ...

  2. bundle adjustment原理(1)

    那些光束平差的工具,比如SBA.SSBA之类的虽然好,然而例子和教程都不够多且不够详细,让初学者难以上手. 要传入的参数虽然有解释,然而却也不是十分清楚其含义,具体要怎么生成,生成为什么形式. 我在折 ...

  3. bundle adjustment原理(1)转载

    转自菠菜僵尸 http://www.cnblogs.com/shepherd2015/p/5848430.html bundle adjustment原理(1) 那些光束平差的工具,比如SBA.SSB ...

  4. 机器人学 —— 机器人视觉(Bundle Adjustment)

    今天完成了机器人视觉的所有课程以及作业,确实是受益匪浅啊! 最后一个话题是Bundle Adjustment. 机器人视觉学中,最顶尖的方法. 1.基于非线性优化的相机位姿估计 之前已经在拟合一篇中, ...

  5. Bundle Adjustment光束平差法概述

    http://blog.csdn.net/abcjennifer/article/details/7588865 http://blog.csdn.net/ximenchuixuezijin/arti ...

  6. Bundle Adjustment---即最小化重投影误差(高翔slam---第七讲)

    一.历史由来 Adjustment computation最早是由geodesy的人搞出来的.19世纪中期的时候,geodetics的学者就开始研究large scale triangulations ...

  7. 如何从零开始系统化学习视觉SLAM?

    由于显示格式问题,建议阅读原文:如何从零开始系统化学习视觉SLAM? 什么是SLAM? SLAM是 Simultaneous Localization And Mapping的 英文首字母组合,一般翻 ...

  8. 当前的开源SLAM方案

    开源方案 传感器形式 地址链接 MonoSLAM 单目 https://github.com/hanmekim/SceneLib2  PTAM 单目  http://www.robots.ox.ac. ...

  9. SLAM的现在与未来

    http://geek.csdn.net/news/detail/202128 作者:高翔,张涛,刘毅,颜沁睿. 编者按:本文节选自图书<视觉SLAM十四讲:从理论到实践>,系统介绍了视觉 ...

随机推荐

  1. log.error(msg)和log.error(msg,e)的显示区别

    log.error(msg): [2017-10-18 11:31:07,652] [Thread-7] (CmsCtlDataUploadFileExchange.java:50) ERROR co ...

  2. VML元素的相关资料

    虽然VML已经过气了,但有时我还不得不使用它,下面是我收集或研究得到的一些东西. 判定一个元素是否为VML元素 function isVML(el) { if (el && el.no ...

  3. 使用Visual Studio进行 Android开发的十大理由

    [原文发表地址]Top 10 reasons to use Visual Studio for C++ Android Development! Visual Studio: C++跨平台的移动解决方 ...

  4. Redis的强大之处

    [Redis的强大之处] 1.拥有对脚本的支持(此处是lua),脚本可选择性的缓存. 2.提供HyperLogLog计数器. 3.提供5种数据类型的全方位支持:List.Hash.Set.Ordere ...

  5. Axure 原型图 (转)

    Axure RP是很有名的一个界面原型设计工具,可以灵活快捷的对C/S.B/S程序设计原型. 近期我要开发一个Android客户端,也打算使用Axure RP设计原型. 下载地址:http://pan ...

  6. 二硫化铼(ReS2)的电子输运特性及逻辑器件研究进展

    南京大学物理学院.固体微结构物理国家重点实验室.微结构科学与技术协同创新中心的缪峰教授课题组和王伯根教授课题组在新型二维材料二硫化铼(ReS2)的电子输运特性及逻辑器件研究领域取得重要进展,相关论文于 ...

  7. 自己制作winhex的模板

    winhex有很多的官方模板,可以在网上下载(后缀tpl)并放至它的安装目录,即可使用.不过要是自己能自己制作,这才好玩,不是么?! 打开模板管理器,可以选中其中一个模板,下面有应用,有编辑,你点开编 ...

  8. 【Centos linux系统】命令行(静默)安装oracle 11gR2

    一.安装前准备 1.内存及swap要求 至于swap如何添加,后文将提到 1 2 grep MemTotal /proc/meminfo grep SwapTotal /proc/meminfo 2. ...

  9. 怎样才能做好SNS社区网站

    顺应历史潮流,大批的网络社区SNS(Social Networking Services)发展起来. SNS旨在构建一个网络上的人际关系网,让公众足不出户即可实现社交意愿.SNS满足了人的交流欲望,成 ...

  10. JScript 对象 <|> JSON

    <script type="text/javascript"> function test(){ var array = [{"id":1},{&q ...