单目/双目与imu的融合(一)

目前单目slam存在初始化的尺度问题和追踪的尺度漂移问题,而双目也存在精度不高和鲁棒性不好的问题。针对这些问题,提出了融合imu的想法。

那么imu的作用是什么呢?

单目

(1)解决初始化尺度问题

(2)追踪中提供较好的初始位姿。

(3)提供重力方向

(4)提供一个时间误差项以供优化

双目

(1)追踪中提供较好的初始位姿。

(2)提供重力方向

(3)提供一个时间误差项以供优化

目前做这方面融合论文很多,但开源的比较少,这里给出几个比较好的开源code和论文

开源code:

(1)imu和单目的数据融合开源代码(EKF)

https://github.com/ethz-asl/rovio

(2)imu和单目的数据融合开源代码

https://github.com/ethz-asl/okvis_ros(非线性优化)

(3)orbslam+imu(立体相机)

https://github.com/JzHuai0108/ORB_SLAM

论文:

(1)Keyframe-based visual–inertial odometry(okvis的论文)

(2) IMU Preintegration on Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation(预积分)

(3)Visual-Inertial Monocular SLAM with Map Reuse (orb+imu)

(4)Robust Visual Inertial Odometry Using a Direct EKF-Based Approach(eth的rovio)

(5)On-Manifold Preintegration for Real-Time Visual-Inertial Odometry(gtsam)

由于是初学比较详细看得就是以上5篇,而且自认为还不错的论文。

本人研究的是基于非线性优化的视觉和imu融合的算法研究,那么这里先引出融合的方式:

滤波方法:

(1)紧耦合

(2)松耦合

非线性优化:

(1)紧耦合(本人研究方向)

(2)松耦合

imu'和视觉是怎样融合的呢?

仅仅视觉的时候我们优化的只是重投影误差项:

以上的公式我就不解释了。

而imu+视觉优化的是重投影误差项+imu的时间误差项:

其中imu时间误差项:

其中为:


这里:imu时间误差项要求的主要有5个变量:eR,ev,ep,eb,W。即求(R ,v,p,b,W)

这里先给出一张非线性优化视觉+imu融合的图:

下面我们就开始用与积分的方式求以上的6个变量,下面给出预积分的code

  1. Eigen::Matrix4d Tracking::propagate(const double time_frame)  
  2. {  
  3.     bool is_meas_good=getObservation(time_frame);  
  4.     assert(is_meas_good);  
  5.     time_pair[0]=time_pair[1];  
  6.     time_pair[1]=time_frame;  
  7.     Eigen::Vector3d tempVs0inw;  
  8.     Eigen::Matrix<double, 15,15>* holder=NULL;  
  9.     if(bPredictCov)  
  10.         holder= &P_;  
  11.     predictStates(T_s1_to_w, speed_bias_1, time_pair,  
  12.                                  measurement, imu_.gwomegaw, imu_.q_n_aw_babw,  
  13.                                  &pred_T_s2_to_w, &tempVs0inw);  
  14.     pred_speed_bias_2.head<3>()=tempVs0inw;//速度偏差  
  15.     pred_speed_bias_2.tail<6>()=speed_bias_1.tail<6>();     //biases do not change in propagation  
  16.    Eigen::Matrix4d pred_Tr_delta=pred_T_s2_to_w*imu_.T_imu_from_cam;//camera-imu-world(矩阵的乘法从左开始)  
  17.    cam_to_w=pred_Tr_delta;  
  18.    pred_Tr_delta=pred_Tr_delta.inverse()*(T_s1_to_w*imu_.T_imu_from_cam);//由imu计算(预测)上一帧-》当前帧的变换关  
  19.   // T_s1_to_w=pred_T_s2_to_w;  
  20.    speed_bias_1=pred_speed_bias_2;  
  21.    return pred_Tr_delta;  
  22. }  
  1. void Tracking::predictStates(const Eigen::Matrix4d  &T_sk_to_w, const Eigen::Matrix<double, 9,1>& speed_bias_k,  
  2.                    const double * time_pair,  
  3.                    std::vector<Eigen::Matrix<double, 7,1> >& measurements, const Eigen::Matrix<double, 6,1> & gwomegaw,  
  4.                    const Eigen::Matrix<double, 12, 1>& q_n_aw_babw,  
  5.                    Eigen::Matrix4d  * pred_T_skp1_to_w, Eigen::Matrix<double, 3,1>* pred_speed_kp1,  
  6.                    Eigen::Matrix<double, 15,15> *covariance,  
  7.                    Eigen::Matrix<double, 15,15>  *jacobian)  
  8. {  
  9.     double time=time_pair[0],end = time_pair[1];  
  10.     // the eventual covariance has little to do with this param as long as it remains small  
  11.     Eigen::Matrix<double, 3,1>  r_0(T_sk_to_w.topRightCorner<3, 1>());  
  12.     Eigen::Matrix<double,3,3> C_WS_0(T_sk_to_w.topLeftCorner<3, 3>());  
  13.     Eigen::Quaternion<double>  q_WS_0(C_WS_0);  
  14.   
  15.     Eigen::Quaterniond Delta_q(1,0,0,0);  
  16.     Eigen::Matrix3d C_integral = Eigen::Matrix3d::Zero();  
  17.     Eigen::Matrix3d C_doubleintegral = Eigen::Matrix3d::Zero();  
  18.     Eigen::Vector3d acc_integral = Eigen::Vector3d::Zero();  
  19.     Eigen::Vector3d acc_doubleintegral = Eigen::Vector3d::Zero();  
  20.   
  21.     Eigen::Matrix3d cross = Eigen::Matrix3d::Zero();  
  22.   
  23.     // sub-Jacobians  
  24.     Eigen::Matrix3d dalpha_db_g = Eigen::Matrix3d::Zero();  
  25.     Eigen::Matrix3d dv_db_g = Eigen::Matrix3d::Zero();  
  26.     Eigen::Matrix3d dp_db_g = Eigen::Matrix3d::Zero();  
  27.   
  28.     // the Jacobian of the increment (w/o biases)  
  29.     Eigen::Matrix<double,15,15> P_delta = Eigen::Matrix<double,15,15>::Zero();  
  30.     double Delta_t = 0;  
  31.     bool hasStarted = false;  
  32.     int i = 0;  
  33.     for (int it=0;it<measurements.size();it++)  
  34.     {  
  35.         Eigen::Vector3d omega_S_0 =measurements[it].block<3,1>(4,0);//角速度  
  36.         Eigen::Vector3d acc_S_0 = measurements[it].block<3,1>(1,0);//线加速度  
  37.         Eigen::Vector3d omega_S_1 = measurements[it+1].block<3,1>(4,0);  
  38.         Eigen::Vector3d acc_S_1 = measurements[it+1].block<3,1>(1,0);  
  39.         ave_omega_S=ave_omega_S+omega_S_0;  
  40.         ave_omega_S=ave_omega_S/(it+1);  
  41.         // time delta  
  42.         double nexttime;  
  43.        if ((it + 1) == (measurements.size()-1)) {  
  44.           nexttime = end;  
  45.         }  
  46.         else  
  47.           nexttime =measurements [it + 1][0];  
  48.         double dt = (nexttime - time);  
  49.   
  50.         if ( end < nexttime) {  
  51.           double interval = (nexttime - measurements[it][0]);  
  52.           nexttime = end;  
  53.           dt = (nexttime - time);  
  54.           const double r = dt / interval;  
  55.           omega_S_1 = ((1.0 - r) * omega_S_0 + r * omega_S_1).eval();  
  56.           acc_S_1 = ((1.0 - r) * acc_S_0 + r * acc_S_1).eval();  
  57.         }  
  58.       /* if ( it+1==measurements.size()) { 
  59.           double interval = last_dt; 
  60.           nexttime = end; 
  61.           double dt = (nexttime - time); 
  62.           const double r = dt / interval; 
  63.           omega_S_1 = ((1.0 - r) * omega_S_0 + r * omega_S_1).eval(); 
  64.           acc_S_1 = ((1.0 - r) * acc_S_0 + r * acc_S_1).eval(); 
  65.         } 
  66.         else 
  67.         nexttime =measurements [it + 1][0]; 
  68.           double dt = (nexttime - time);*/  
  69.       if (dt <= 0.0) {  
  70.           continue;  
  71.         }  
  72.         Delta_t += dt;  
  73.   
  74.     if (!hasStarted) {  
  75.       hasStarted = true;  
  76.       const double r = dt / (nexttime -measurements[it][0]);  
  77.       omega_S_0 = (r * omega_S_0 + (1.0 - r) * omega_S_1).eval();//求开始是加权的角速度和线加速度  
  78.       acc_S_0 = (r * acc_S_0 + (1.0 - r) * acc_S_1).eval();  
  79.     }  
  80.     // ensure integrity  
  81.     double sigma_g_c = q_n_aw_babw(3);//Gyroscope noise density.  
  82.     double sigma_a_c = q_n_aw_babw(1);  
  83.     // actual propagation  
  84.     // orientation:  
  85.     Eigen::Quaterniond dq;  
  86.     const Eigen::Vector3d omega_S_true = (0.5*(omega_S_0+omega_S_1) - speed_bias_k.segment<3>(3));//w  
  87.     const double theta_half = omega_S_true.norm() * 0.5 * dt;  
  88.     const double sinc_theta_half = ode(theta_half);  
  89.     const double cos_theta_half = cos(theta_half);  
  90.     dq.vec() = sinc_theta_half * omega_S_true * 0.5 * dt;  
  91.     dq.w() = cos_theta_half;  
  92.     Eigen::Quaterniond Delta_q_1 = Delta_q * dq;  
  93.     // rotation matrix integral:  
  94.     const Eigen::Matrix3d C = Delta_q.toRotationMatrix();  
  95.     const Eigen::Matrix3d C_1 = Delta_q_1.toRotationMatrix();  
  96.     const Eigen::Vector3d acc_S_true = (0.5*(acc_S_0+acc_S_1) - speed_bias_k.segment<3>(6));  
  97.     const Eigen::Matrix3d C_integral_1 = C_integral + 0.5*(C + C_1)*dt;  
  98.     const Eigen::Vector3d acc_integral_1 = acc_integral + 0.5*(C + C_1)*acc_S_true*dt;  
  99.     // rotation matrix double integral:  
  100.     C_doubleintegral += C_integral*dt + 0.25*(C + C_1)*dt*dt;  
  101.     acc_doubleintegral += acc_integral*dt + 0.25*(C + C_1)*acc_S_true*dt*dt;  
  102.     // Jacobian parts  
  103.     dalpha_db_g += dt*C_1;  
  104.     const Eigen::Matrix3d cross_1 = dq.inverse().toRotationMatrix()*cross +  
  105.     okvis::kinematics::rightJacobian(omega_S_true*dt)*dt;  
  106.     const Eigen::Matrix3d acc_S_x = crossMx(acc_S_true);  
  107.     Eigen::Matrix3d dv_db_g_1 = dv_db_g + 0.5*dt*(C*acc_S_x*cross + C_1*acc_S_x*cross_1);  
  108.     dp_db_g += dt*dv_db_g + 0.25*dt*dt*(C*acc_S_x*cross + C_1*acc_S_x*cross_1);  
  109.   
  110.     // covariance propagation  
  111.     if (covariance) {  
  112.       Eigen::Matrix<double,15,15> F_delta = Eigen::Matrix<double,15,15>::Identity();  
  113.       // transform  
  114.       F_delta.block<3,3>(0,3) = -crossMx(acc_integral*dt + 0.25*(C + C_1)*acc_S_true*dt*dt);  
  115.       F_delta.block<3,3>(0,6) = Eigen::Matrix3d::Identity()*dt;  
  116.       F_delta.block<3,3>(0,9) = dt*dv_db_g + 0.25*dt*dt*(C*acc_S_x*cross + C_1*acc_S_x*cross_1);  
  117.       F_delta.block<3,3>(0,12) = -C_integral*dt + 0.25*(C + C_1)*dt*dt;  
  118.       F_delta.block<3,3>(3,9) = -dt*C_1;  
  119.       F_delta.block<3,3>(6,3) = -crossMx(0.5*(C + C_1)*acc_S_true*dt);  
  120.       F_delta.block<3,3>(6,9) = 0.5*dt*(C*acc_S_x*cross + C_1*acc_S_x*cross_1);  
  121.       F_delta.block<3,3>(6,12) = -0.5*(C + C_1)*dt;  
  122.       P_delta = F_delta*P_delta*F_delta.transpose();  
  123.       // add noise. Note that transformations with rotation matrices can be ignored, since the noise is isotropic.  
  124.       //F_tot = F_delta*F_tot;  
  125.       const double sigma2_dalpha = dt * sigma_g_c * sigma_g_c;  
  126.       P_delta(3,3) += sigma2_dalpha;  
  127.       P_delta(4,4) += sigma2_dalpha;  
  128.       P_delta(5,5) += sigma2_dalpha;  
  129.       const double sigma2_v = dt * sigma_a_c * q_n_aw_babw(1);  
  130.       P_delta(6,6) += sigma2_v;  
  131.       P_delta(7,7) += sigma2_v;  
  132.       P_delta(8,8) += sigma2_v;  
  133.       const double sigma2_p = 0.5*dt*dt*sigma2_v;  
  134.       P_delta(0,0) += sigma2_p;  
  135.       P_delta(1,1) += sigma2_p;  
  136.       P_delta(2,2) += sigma2_p;  
  137.       const double sigma2_b_g = dt * q_n_aw_babw(9) * q_n_aw_babw(9);  
  138.       P_delta(9,9)   += sigma2_b_g;  
  139.       P_delta(10,10) += sigma2_b_g;  
  140.       P_delta(11,11) += sigma2_b_g;  
  141.       const double sigma2_b_a = dt * q_n_aw_babw(6) * q_n_aw_babw(6);  
  142.       P_delta(12,12) += sigma2_b_a;  
  143.       P_delta(13,13) += sigma2_b_a;  
  144.       P_delta(14,14) += sigma2_b_a;  
  145.     }  
  146.   
  147.     // memory shift  
  148.     Delta_q = Delta_q_1;  
  149.     C_integral = C_integral_1;  
  150.     acc_integral = acc_integral_1;  
  151.     cross = cross_1;  
  152.     dv_db_g = dv_db_g_1;  
  153.     time = nexttime;  
  154.     interval_time=Delta_t;  
  155.      last_dt=dt;  
  156.   
  157.     ++i;  
  158.   
  159.     if (nexttime == end)  
  160.       break;  
  161.   
  162.   }  
  163. // actual propagation output:  
  164. const Eigen::Vector3d g_W = gwomegaw.head<3>();  
  165. const Eigen::Vector3d  t=r_0+speed_bias_k.head<3>()*Delta_t+ C_WS_0*(acc_doubleintegral)+0.5*g_W*Delta_t*Delta_t;  
  166. const  Eigen::Quaterniond q=q_WS_0*Delta_q;  
  167. (*pred_T_skp1_to_w)=rt_to_T(t,q.toRotationMatrix());  
  168.   
  169. (*pred_speed_kp1)=speed_bias_k.head<3>() + C_WS_0*(acc_integral)+g_W*Delta_t;//???语法曾有错误  
  170. if (jacobian) {  
  171.   Eigen::Matrix<double,15,15> & F = *jacobian;  
  172.   F.setIdentity(); // holds for all states, including d/dalpha, d/db_g, d/db_a  
  173.   F.block<3,3>(0,3) = -okvis::kinematics::crossMx(C_WS_0*acc_doubleintegral);  
  174.   F.block<3,3>(0,6) = Eigen::Matrix3d::Identity()*Delta_t;  
  175.   F.block<3,3>(0,9) = C_WS_0*dp_db_g;  
  176.   F.block<3,3>(0,12) = -C_WS_0*C_doubleintegral;  
  177.   F.block<3,3>(3,9) = -C_WS_0*dalpha_db_g;  
  178.   F.block<3,3>(6,3) = -okvis::kinematics::crossMx(C_WS_0*acc_integral);  
  179.   F.block<3,3>(6,9) = C_WS_0*dv_db_g;  
  180.   F.block<3,3>(6,12) = -C_WS_0*C_integral;  
  181. }  
  182.   
  183. // overall covariance, if requested  
  184. if (covariance) {  
  185.   Eigen::Matrix<double,15,15> & P = *covariance;  
  186.   // transform from local increments to actual states  
  187.   Eigen::Matrix<double,15,15> T = Eigen::Matrix<double,15,15>::Identity();  
  188.   T.topLeftCorner<3,3>() = C_WS_0;  
  189.   T.block<3,3>(3,3) = C_WS_0;  
  190.   T.block<3,3>(6,6) = C_WS_0;  
  191.   P = T * P_delta * T.transpose();  
  192. }  
  193. }  

以上code来自以下公式:

其中认为角速度w和加速度a在连续两次imu测量之间是匀速的,因此上式可写成:


其中上式的角速度和加速度:

因此最终公式:


上面公式给出5个变量(R,V,P,b,W)中的3个最重要的变量:R,V,P。

而偏差变量b我们可以初始化的时候可以设为0(其实最好是要求出来的,这里就不给出推倒公式了)。

下面的们就是有关W(权重)的公式了。


其中

是有关R,P,V,b的协方差矩阵

到此为止已经把imu时间误差项求完。

下一篇将是怎样把时间误差项融合到目标函数里(主要是局部地图的优化)


  • 1
    点赞
  • 15
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值