VINS-Mono-相机与IMU外参标定原理及源码解析

前言

相机与IMU的标定方法很多,有在线和离线两种方式.其中通过Kalibr工具箱进行标定的方法属于离线标定,并且还依赖场景中的标定板,是很麻烦的一种标定方法.而在线标定方法操作简便,不需要特定的场景布置,直接多角度移动设备即可实现标定,因此是极力推崇的方法,本文将介绍VINS-Mono中在线标定相机与IMU外参的方法.

旋转部分标定

  • 原理推导
    说明: q b k + 1 b k \mathbf{q}_{b_{k+1}}^{b_{k}} qbk+1bk是从时刻 b k b_{k} bk到时刻 b k + 1 b_{k+1} bk+1过程中IMU测量值姿态预积分结果
              q c k + 1 c k \mathbf{q}_{c_{k+1}}^{c_{k}} qck+1ck b k + 1 b_{k+1} bk+1时刻图像帧相对于 b k b_{k} bk时刻图像帧的姿态变化(通过本质矩阵求解)
              q c b \mathbf{q}_{c}^{b} qcb 是相机相对于IMU的旋转变换
    根据旋转矩阵性质可得:
    q b k + 1 b k = q c k b k ⊗ q c k + 1 c k ⊗ q b k + 1 c k + 1 (1) \mathbf{q}_{b_{k+1}}^{b_{k}} = \mathbf{q}_{c_{k}}^{b_{k}} \otimes \mathbf{q}_{c_{k+1}}^{c_{k}} \otimes \mathbf{q}_{b_{k+1}}^{c_{k+1}} \tag{1} qbk+1bk=qckbkqck+1ckqbk+1ck+1(1)
    由于 q c k b k = q c k + 1 b k + 1 = q c b \mathbf{q}_{c_{k}}^{b_{k}} = \mathbf{q}_{c_{k+1}}^{b_{k+1}} = \mathbf{q}_{c}^{b} qckbk=qck+1bk+1=qcb,所以有:
    q b k + 1 b k = q c b ⊗ q c k + 1 c k ⊗ q b c (2) \mathbf{q}_{b_{k+1}}^{b_{k}} = \mathbf{q}_{c}^{b} \otimes \mathbf{q}_{c_{k+1}}^{c_{k}} \otimes \mathbf{q}_{b}^{c} \tag{2} qbk+1bk=qcbqck+1ckqbc(2)
    q b c \mathbf{q}_{b}^{c} qbc 移到等式左边有:
    q b k + 1 b k ⊗ q c b = q c b ⊗ q c k + 1 c k (3) \mathbf{q}_{b_{k+1}}^{b_{k}} \otimes \mathbf{q}_{c}^{b} = \mathbf{q}_{c}^{b} \otimes \mathbf{q}_{c_{k+1}}^{c_{k}} \tag{3} qbk+1bkqcb=qcbqck+1ck(3)
    根据文章 Quaternion kinematics for the error-state KF 中的"一些四元素的性质"章节中提到两四元素的乘法可以转换成矩阵与四元素的乘法,转换方法如下:
    q 1 ⊗ q 2 = Q 1 + q 2 → Q 1 + = q w I + [ 0 − q v T q v [ q v ] × ] q 1 ⊗ q 2 = Q 2 − q 1 → Q 2 − = q w I + [ 0 − q v T q v − [ q v ] × ] [ q v ] × = [ 0 − q z q y q z 0 − q x − q y q x 0 ] q = [ q w q v ] \begin{aligned} \mathbf{q}_{1}\otimes \mathbf{q}_{2} &=\mathbf{Q}_{1}^{+}\mathbf{q}_{2}\rightarrow \mathbf{Q}_{1}^{+} =q_{w}\mathbf{I}+\begin{bmatrix} 0 & -\mathbf{q}_{v}^{T}\\ \mathbf{q}_{v} & \begin{bmatrix} \mathbf{q}_{v} \end{bmatrix}_{\times } \end{bmatrix} \\ \mathbf{q}_{1}\otimes \mathbf{q}_{2}&=\mathbf{Q}_{2}^{-}\mathbf{q}_{1}\rightarrow \mathbf{Q}_{2}^{-}=q_{w}\mathbf{I}+\begin{bmatrix} 0 & -\mathbf{q}_{v}^{T}\\ \mathbf{q}_{v} & -\begin{bmatrix} \mathbf{q}_{v} \end{bmatrix}_{\times } \end{bmatrix} \\ \begin{bmatrix} \mathbf{q}_{v} \end{bmatrix}_{\times }&=\begin{bmatrix} 0 & -q_{z} & q_{y} \\ q_{z} & 0 & -q_{x} \\ -q_{y} & q_{x} & 0 \end{bmatrix} \\ \mathbf{q} &= \begin{bmatrix} q_{w} & \mathbf{q}_{v} \end{bmatrix} \end{aligned} q1q2q1q2[qv]×q=Q1+q2Q1+=qwI+[0qvqvT[qv]×]=Q2q1Q2=qwI+[0qvqvT[qv]×]=0qzqyqz0qxqyqx0=[qwqv]
    其中 Q + , Q − \mathbf{Q}^{+},\mathbf{Q}^{-} Q+,Q在某些博客或书本上分别称为左乘、右乘矩阵.
    根据上面的性质,可将公式(3)写成如下形式:
    Q b k + 1 b k + q c b = Q c k + 1 c k − q c b (4) {\mathbf{Q}_{b_{k+1}}^{b_{k}+}}\mathbf{q}_{c}^{b} = {\mathbf{Q}_{c_{k+1}}^{c_{k}-}}\mathbf{q}_{c}^{b} \tag{4} Qbk+1bk+qcb=Qck+1ckqcb(4)
    合并同类项得:
    ( Q b k + 1 b k + − Q c k + 1 c k − ) q c b = 0 (5) ({\mathbf{Q}_{b_{k+1}}^{b_{k}+}}-{\mathbf{Q}_{c_{k+1}}^{c_{k}-}})\mathbf{q}_{c}^{b} = \mathbf{0} \tag{5} (Qbk+1bk+Qck+1ck)qcb=0(5)
    假设有n组测量数据用于外参标定,可建立如下方程组:
    { ( Q b 1 b 0 + − Q c 1 c 0 − ) q c b = 0 ( Q b 2 b 1 + − Q c 2 c 1 − ) q c b = 0 . . . . . . ( Q b n b n − 1 + − Q c n c n − 1 − ) q c b = 0 (6) \left\{\begin{matrix} ({\mathbf{Q}_{b_{1}}^{b_{0}+}}-{\mathbf{Q}_{c_{1}}^{c_{0}-}})\mathbf{q}_{c}^{b} = \mathbf{0} \\ ({\mathbf{Q}_{b_{2}}^{b_{1}+}}-{\mathbf{Q}_{c_{2}}^{c_{1}-}})\mathbf{q}_{c}^{b} = \mathbf{0} \\ ...... \\ ({\mathbf{Q}_{b_{n}}^{b_{n-1}+}}-{\mathbf{Q}_{c_{n}}^{c_{n-1}-}})\mathbf{q}_{c}^{b} = \mathbf{0} \end{matrix}\right. \tag{6} (Qb1b0+Qc1c0)qcb=0(Qb2b1+Qc2c1)qcb=0......(Qbnbn1+Qcncn1)qcb=0(6)
    写成矩阵形式:
    [ Q b 1 b 0 + − Q c 1 c 0 − Q b 2 b 1 + − Q c 2 c 1 − . . . . . . Q b n b n − 1 + − Q c n c n − 1 − ] 4 n × 4 q c b = A 4 n × 4 q c b = 0 (7) \begin{bmatrix} {\mathbf{Q}_{b_{1}}^{b_{0}+}}-{\mathbf{Q}_{c_{1}}^{c_{0}-}} \\ {\mathbf{Q}_{b_{2}}^{b_{1}+}}-{\mathbf{Q}_{c_{2}}^{c_{1}-}} \\ ...... \\ {\mathbf{Q}_{b_{n}}^{b_{n-1}+}}-{\mathbf{Q}_{c_{n}}^{c_{n-1}-}} \end{bmatrix}_{4n\times4} \mathbf{q}_{c}^{b} = \mathbf{A}_{4n\times4}\mathbf{q}_{c}^{b} = \mathbf{0} \tag{7} Qb1b0+Qc1c0Qb2b1+Qc2c1......Qbnbn1+Qcncn14n×4qcb=A4n×4qcb=0(7)
    公式(7)是一个齐次线性方程组,可通过SVD方法求解: 该方法首先对 A 4 n × 4 \mathbf{A}_{4n\times4} A4n×4 进行SVD分解,然后取最小奇异值对应的特征向量作为 q c b \mathbf{q}_{c}^{b} qcb最终结果.
  • 源码解析
bool InitialEXRotation::CalibrationExRotation(vector> corres, Quaterniond delta_q_imu, Matrix3d &calib_ric_result)
{
    frame_count++; // 总共用于外参标定的数据帧数
    Rc.push_back(solveRelativeR(corres)); //通过本质矩阵求解相邻两帧之间的旋转矩阵 q_c(k+1)_c(k)
    Rimu.push_back(delta_q_imu.toRotationMatrix()); //从b_(k+1)到b_(k)时刻IMU姿态预积分结果 q_b(k+1)_b(k)
    Rc_g.push_back(ric.inverse() * delta_q_imu * ric);

    Eigen::MatrixXd A(frame_count * 4, 4); //申明并定义矩阵A,维度为4nx4
    A.setZero();
    int sum_ok = 0;
    for (int i = 1; i <= frame_count; i++)
    {
        Quaterniond r1(Rc[i]); //对应公式(4)中的q_c(k+1)_c(k)
        Quaterniond r2(Rc_g[i]); //对应公式(4)中的q_b(k+1)_b(k)

        double angular_distance = 180 / M_PI * r1.angularDistance(r2); // 计算相机姿态增量和imu姿态增量之间的夹角
        ROS_DEBUG(
            "%d %f", i, angular_distance);

        // 根据两姿态之间的夹角计算Huber核系数,降噪声影响
        double huber = angular_distance > 5.0 ? 5.0 / angular_distance : 1.0;
        ++sum_ok;
        Matrix4d L, R;

        // 计算左乘矩阵,对应公式(5)中的Q_(+)
        double w = Quaterniond(Rc[i]).w();
        Vector3d q = Quaterniond(Rc[i]).vec();
        L.block<3, 3>(0, 0) = w * Matrix3d::Identity() + Utility::skewSymmetric(q);
        L.block<3, 1>(0, 3) = q;
        L.block<1, 3>(3, 0) = -q.transpose();
        L(3, 3) = w;

        // 计算右乘矩阵,对应公式(5)中的Q_(-)
        Quaterniond R_ij(Rimu[i]);
        w = R_ij.w();
        q = R_ij.vec();
        R.block<3, 3>(0, 0) = w * Matrix3d::Identity() - Utility::skewSymmetric(q);
        R.block<3, 1>(0, 3) = q;
        R.block<1, 3>(3, 0) = -q.transpose();
        R(3, 3) = w;

        // 对应公式(7),其实一组数据就可以解算出外参信息,此处累积多组数据构成超定方程,提升结果的准确性
        A.block<4, 4>((i - 1) * 4, 0) = huber * (L - R);
    }

    // 进行SVD分解求解齐次线性方程组
    JacobiSVD svd(A, ComputeFullU | ComputeFullV);
    // 最小奇异值对应的特征向量即为求解的结果
    Matrix x = svd.matrixV().col(3);
    Quaterniond estimated_R(x);
    ric = estimated_R.toRotationMatrix().inverse();
    //cout << svd.singularValues().transpose() << endl;
    //cout << ric << endl;
    // 将SVD分解后的最小的三个奇异值作为外参旋转的协方差值(只有对角线上有值)
    Vector3d ric_cov;
    ric_cov = svd.singularValues().tail<3>();
    if (frame_count >= WINDOW_SIZE && ric_cov(1) > 0.25)
    {
        calib_ric_result = ric;
        return true;
    }
    else
        return false;
}

如果算法对相机与IMU之间的平移变换要求不高的话,就可以利用该旋转变换结果进行算法开发.

旋转和平移变换在线优化矫正

problem.AddParameterBlock(para_Ex_Pose[i], SIZE_POSE, local_parameterization);

VINS-Mono在获得旋转变换之后,在进行VIO的过程中,将相机与IMU外参作为优化参数在整个算法运行过程中进行矫正,从而保证外参的准确性.

代码注释

https://github.com/chennuo0125-HIT/vins-note

你可能感兴趣的:(VINS-Mono-相机与IMU外参标定原理及源码解析)