visualIntialAlign()函數視覺慣性聯合初始化
這篇文章主要集中在討論視覺部分和IMU部分之間的關聯,如何對兩部分進行對齊,使得系統完成初始化。
目錄
visualIntialAlign()函數視覺慣性聯合初始化
理論:視覺IMU對齊流程
代碼流程
VisualIMUAlignment()
理論知識:
視覺慣性校準(IMU預積分與視覺結構對齊)
1、陀螺儀零偏bg標定
2、速度v、重力g和尺度初始化s
3、重力矢量修正
陀螺儀偏置標定solveGyroscopeBias()函數
計算尺度、重力、速度 LinearAlignment()函數
重力細化RefineGravity()函數
理論:視覺IMU對齊流程
其中,步驟1的在線Cam到IMU的外參標定qbc 參考之前的博客。
**
1、陀螺儀零偏bg標定.
2、優化 速度v、重力g和尺度初始化s。我們得到了陀螺儀偏置bias的初始校準,需要將陀螺儀偏置bg代入到IMU預積分重新計算預積分.
3、重力矢量修正.**
代碼流程
**bool Estimator::visualInitialAlign()**主要過程爲:
**1、VisualIMUAlignment()**函數計算陀螺儀偏置bg,尺度s,重力加速度g和速度v.
**2、f_manager.triangulate()**計算特徵點深度estimated_depth
**3、repropagate()**陀螺儀的偏置bgs改變,重新計算預積分
**4、**將Ps、Vs、depth進行更新
**5、**將重力旋轉到Z軸,將Ps、Vs、Rs從相機參考座標系c0旋轉到世界座標系w。
1、計算陀螺儀偏置bg,尺度s,重力加速度g和速度v
bool result = VisualIMUAlignment(all_image_frame, Bgs, g, x);
if(!result)
{
ROS_DEBUG("solve g failed!");
return false;
}
這裏的**VisualIMUAlignment()**函數最重要,我們會在下一講詳細講解。
這裏先熟悉基本流程。
2、得到所有圖像幀的位姿Ps、Rs,並將其置爲關鍵幀
for (int i = 0; i <= frame_count; i++)
{
Matrix3d Ri = all_image_frame[Headers[i].stamp.toSec()].R;// 是ROS嗎?
Vector3d Pi = all_image_frame[Headers[i].stamp.toSec()].T;
Ps[i] = Pi;
Rs[i] = Ri;
all_image_frame[Headers[i].stamp.toSec()].is_key_frame = true;
}
3、重新計算特徵點的深度depth
VectorXd dep = f_manager.getDepthVector();
for (int i = 0; i < dep.size(); i++)
dep[i] = -1;
f_manager.clearDepth(dep);
Vector3d TIC_TMP[NUM_OF_CAM];
for(int i = 0; i < NUM_OF_CAM; i++)
TIC_TMP[i].setZero();
ric[0] = RIC[0];
f_manager.setRic(ric);
f_manager.triangulate(Ps, &(TIC_TMP[0]), &(RIC[0]));
// 尺度先假設
double s = (x.tail<1>())(0);
4、陀螺儀的偏置bgs改變,重新計算預積分
for (int i = 0; i <= WINDOW_SIZE; i++)
{
pre_integrations[i]->repropagate(Vector3d::Zero(), Bgs[i]);
}
這裏最要的repropagate()函數很重要。
5、將Ps、Vs、depth進行更新
5.1 目的是將姿態從相機座標系c0轉換到IMU座標系中。
姿態從相機座標系轉換到IMU座標系關係爲:
// 5、將Ps、Vs、depth進行更新
for (int i = frame_count; i >= 0; i--)
// 5.1 Ps轉變爲第i幀imu座標系到第0幀imu座標系的變換
// 之前相機第l幀爲參考系,轉換到IMU bo爲基準座標系
Ps[i] = s * Ps[i] - Rs[i] * TIC[0] - (s * Ps[0] - Rs[0] * TIC[0]);
int kv = -1;
map<double, ImageFrame>::iterator frame_i;
for (frame_i = all_image_frame.begin(); frame_i != all_image_frame.end(); frame_i++)
{
if(frame_i->second.is_key_frame)
{
kv++;
//5.2 Vs爲優化得到的速度
Vs[kv] = frame_i->second.R * x.segment<3>(kv * 3);
}
}
// 5.3 逆深度depth更新
for (auto &it_per_id : f_manager.feature)
{
it_per_id.used_num = it_per_id.feature_per_frame.size();
if (!(it_per_id.used_num >= 2 && it_per_id.start_frame < WINDOW_SIZE - 2))
continue;
it_per_id.estimated_depth *= s;
}
**
6、所有變量從參考座標系c0到世界座標系。**
```cpp
// 6 通過將重力旋轉到z軸上,得到世界座標系與攝像機座標系c0之間的旋轉矩陣rot_diff
Matrix3d R0 = Utility::g2R(g);
double yaw = Utility::R2ypr(R0 * Rs[0]).x();
R0 = Utility::ypr2R(Eigen::Vector3d{-yaw, 0, 0}) * R0;
g = R0 * g;
//Matrix3d rot_diff = R0 * Rs[0].transpose();
Matrix3d rot_diff = R0;
// 7/所有變量從參考座標系c0旋轉到世界座標系w
for (int i = 0; i <= frame_count; i++)
{
Ps[i] = rot_diff * Ps[i];
Rs[i] = rot_diff * Rs[i];
Vs[i] = rot_diff * Vs[i];
}
VisualIMUAlignment()
本節主要介紹Estimator模塊的視覺慣性聯合初始化模塊,visualIntialAlign()函數內第一步VisualIMUAlignment()函數上一節對者幾個過程進行大致概括,本節主要對第一部分VisualIMUAlignment()函數進行詳細介紹。
理論知識:
本節主要介紹初始化中視覺慣性對齊求解陀螺儀偏置bg、重力加速度g、每幀速度v、尺度s和相機到IMU的外參估計。
主要流程爲:
1、利用旋轉約束估計陀螺儀偏置bg
2、利用平移約束估計重力加速度g、每幀速度v、尺度s
3、對重力向量進一步優化
視覺慣性校準(IMU預積分與視覺結構對齊)
相機到IMU的外參矩陣求解出來,可以利用旋轉的約束,估計陀螺儀的bias.
1、陀螺儀零偏bg標定
旋轉兩種方式:陀螺儀測量值和視覺觀測值,二者的誤差其實就是陀螺儀偏置bg。
目標函數:visual給出的相鄰幀間的旋轉應等於IMU預積分的旋轉值Q之間的差。
我們得到了陀螺儀偏置bias的初始校準,需要將陀螺儀偏置bg代入到IMU預積分重新計算預積分。
2、速度v、重力g和尺度初始化s
優化變量:速度、重力向量和尺度
**目標函數:**相鄰兩幀IMU預積分增量與預測值之間平移、速度(P、V)的差。通過HX=B 利用cholesky分解獲得
結合
得到:
3、重力矢量修正
重力向量的大小是已知的,加入了模長限制,這導致三維重力向量只剩2個自由度。主要做的是優化方向,一個二維向量。
在其切線空間上用兩個變量重新參數化重力,採用球面座標進行參數化:
其中,
是已知的重力的大小,
爲重力方向的單位向量。b1和b2是跨越切平面的兩個正交基。w1和w2是待優化變量,表示沿着兩個正交基方向的位移。
替換後,Hx=b,變化爲:之後採用最小二乘對變量重新優化。
其中,待優化變量變爲:
4、將相機座標系對齊世界座標系
已知量:
1)上一步得到了重力向量g^{c0}在相機初始時刻C_{0}系下的大小,
2)重力向量在世界座標系下的絕對向量爲g=[0,0,9.81]
通過將g{c0}旋轉至慣性座標系中的z軸方向,可以計算相機繫到慣性系的旋轉矩陣q_{co}{w},從而將所有變量調整至慣性座標系中。
最後一步
VisualIMUAlignment()函數在 vins_estimator/src/initial/initial_aligment.cpp/.h。
該函數主要調用了兩個函數,分別是對陀螺儀偏置的標定和估計尺度、重力加速度和速度。
//視覺和IMU對齊
bool VisualIMUAlignment(map<double, ImageFrame> &all_image_frame, Vector3d* Bgs, Vector3d &g, VectorXd &x)
{
solveGyroscopeBias(all_image_frame, Bgs);//計算陀螺儀偏置
if(LinearAlignment(all_image_frame, g, x))//計算尺度,重力加速度和速度
return true;
else
return false;
}
其中,ImageFrame圖像幀類主要在initial_alignment.h ,這個頭文件主要就兩部分:ImageFrame類、VisualIMUAlignment()函數。ImageFrame圖像幀爲特徵點、時間戳、相機位姿、預積分對象、是否關鍵幀。
陀螺儀偏置標定solveGyroscopeBias()函數
SFM得到的旋轉矩陣和IMU預積分得到的旋轉量q求Ax=B分解得到最小誤差。注意得到了新的Bias後保存在Bgs[]中,對應的預積分需要重新計算一遍repropagate。
/**
* @brief 陀螺儀偏置校正
* @optional 根據視覺SFM的結果來校正陀螺儀Bias -> Paper V-B-1
* 主要是將相鄰幀之間SFM求解出來的旋轉矩陣與IMU預積分的旋轉量對齊
* 注意得到了新的Bias後對應的預積分需要repropagate
* @param[in] all_image_frame所有圖像幀構成的map,圖像幀保存了位姿、預積分量和關於角點的信息
* @param[out] Bgs 陀螺儀偏置
* @return void
*/
void solveGyroscopeBias(map<double, ImageFrame> &all_image_frame, Vector3d* Bgs)
{
Matrix3d A;
Vector3d b;
Vector3d delta_bg;
A.setZero();
b.setZero();
map<double, ImageFrame>::iterator frame_i;
map<double, ImageFrame>::iterator frame_j;
for (frame_i = all_image_frame.begin(); next(frame_i) != all_image_frame.end(); frame_i++)
{
frame_j = next(frame_i);
MatrixXd tmp_A(3, 3);
tmp_A.setZero();
VectorXd tmp_b(3);
tmp_b.setZero();
//R_ij = (R^c0_bk)^-1 * (R^c0_bk+1) 轉換爲四元數 q_ij = (q^c0_bk)^-1 * (q^c0_bk+1)
Eigen::Quaterniond q_ij(frame_i->second.R.transpose() * frame_j->second.R);
//tmp_A = J_j_bw
tmp_A = frame_j->second.pre_integration->jacobian.template block<3, 3>(O_R, O_BG);
//tmp_b = 2 * (r^bk_bk+1)^-1 * (q^c0_bk)^-1 * (q^c0_bk+1)
// = 2 * (r^bk_bk+1)^-1 * q_ij
tmp_b = 2 * (frame_j->second.pre_integration->delta_q.inverse() * q_ij).vec();
//tmp_A * delta_bg = tmp_b
A += tmp_A.transpose() * tmp_A;
b += tmp_A.transpose() * tmp_b;
}
// LDLT方法
delta_bg = A.ldlt().solve(b);
ROS_WARN_STREAM("gyroscope bias initial calibration " << delta_bg.transpose());
for (int i = 0; i <= WINDOW_SIZE; i++)
Bgs[i] += delta_bg;
// 得到了新的Bias後對應的預積分需要repropagate
for (frame_i = all_image_frame.begin(); next(frame_i) != all_image_frame.end( ); frame_i++)
{
frame_j = next(frame_i);
frame_j->second.pre_integration->repropagate(Vector3d::Zero(), Bgs[0]);
}
}
之所以 A +=tmp_A.transpose() * tmp_A,其實就是A^{T}A \ast x=A^{T}\ast b ,
在求解 Ax=b的最小二乘解時,兩邊同乘以A矩陣的轉置得到的AT*A一定是可逆的。
計算尺度、重力、速度 LinearAlignment()函數
主要就是對於Ax=b的填充
/**
* @brief 計算尺度,重力加速度和速度
* @optional 速度、重力向量和尺度初始化Paper -> V-B-2
* 相鄰幀之間的位置和速度與IMU預積分出來的位置和速度對齊,求解最小二乘
* 重力細化 -> Paper V-B-3
* @param[in] all_image_frame 所有圖像幀構成的map,圖像幀保存了位姿,預積分量和關於角點的信息
* @param[out] g 重力加速度
* @param[out] x 待優化變量,窗口中每幀的速度V[0:n]、重力g、尺度s
* @return void
*/
bool LinearAlignment(map<double, ImageFrame> &all_image_frame, Vector3d &g, VectorXd &x)
{
int all_frame_count = all_image_frame.size();
//優化量x的總維度
int n_state = all_frame_count * 3 + 3 + 1;
MatrixXd A{n_state, n_state};
A.setZero();
VectorXd b{n_state};
b.setZero();
map<double, ImageFrame>::iterator frame_i;
map<double, ImageFrame>::iterator frame_j;
int i = 0;
for (frame_i = all_image_frame.begin(); next(frame_i) != all_image_frame.end(); frame_i++, i++)
{
frame_j = next(frame_i);
MatrixXd tmp_A(6, 10);
tmp_A.setZero();
VectorXd tmp_b(6);
tmp_b.setZero();
double dt = frame_j->second.pre_integration->sum_dt;
// tmp_A(6,10) = H^bk_bk+1 = [-I*dt 0 (R^bk_c0)*dt*dt/2 (R^bk_c0)*((p^c0_ck+1)-(p^c0_ck)) ]
// [ -I (R^bk_c0)*(R^c0_bk+1) (R^bk_c0)*dt 0 ]
// tmp_b(6,1 ) = z^bk_bk+1 = [ (a^bk_bk+1)+(R^bk_c0)*(R^c0_bk+1)*p^b_c-p^b_c , (b^bk_bk+1)]^T
// tmp_A * x = tmp_b 求解最小二乘問題
tmp_A.block<3, 3>(0, 0) = -dt * Matrix3d::Identity();
tmp_A.block<3, 3>(0, 6) = frame_i->second.R.transpose() * dt * dt / 2 * Matrix3d::Identity();
tmp_A.block<3, 1>(0, 9) = frame_i->second.R.transpose() * (frame_j->second.T - frame_i->second.T) / 100.0;
tmp_b.block<3, 1>(0, 0) = frame_j->second.pre_integration->delta_p + frame_i->second.R.transpose() * frame_j->second.R * TIC[0] - TIC[0];
//cout << "delta_p " << frame_j->second.pre_integration->delta_p.transpose() << endl;
tmp_A.block<3, 3>(3, 0) = -Matrix3d::Identity();
tmp_A.block<3, 3>(3, 3) = frame_i->second.R.transpose() * frame_j->second.R;
tmp_A.block<3, 3>(3, 6) = frame_i->second.R.transpose() * dt * Matrix3d::Identity();
tmp_b.block<3, 1>(3, 0) = frame_j->second.pre_integration->delta_v;
//cout << "delta_v " << frame_j->second.pre_integration->delta_v.transpose() << endl;
Matrix<double, 6, 6> cov_inv = Matrix<double, 6, 6>::Zero();
//cov.block<6, 6>(0, 0) = IMU_cov[i + 1];
//MatrixXd cov_inv = cov.inverse();
cov_inv.setIdentity();
MatrixXd r_A = tmp_A.transpose() * cov_inv * tmp_A;
VectorXd r_b = tmp_A.transpose() * cov_inv * tmp_b;
A.block<6, 6>(i * 3, i * 3) += r_A.topLeftCorner<6, 6>();
b.segment<6>(i * 3) += r_b.head<6>();
A.bottomRightCorner<4, 4>() += r_A.bottomRightCorner<4, 4>();
b.tail<4>() += r_b.tail<4>();
A.block<6, 4>(i * 3, n_state - 4) += r_A.topRightCorner<6, 4>();
A.block<4, 6>(n_state - 4, i * 3) += r_A.bottomLeftCorner<4, 6>();
}
A = A * 1000.0;
b = b * 1000.0;
x = A.ldlt().solve(b);
double s = x(n_state - 1) / 100.0;
ROS_DEBUG("estimated scale: %f", s);
g = x.segment<3>(n_state - 4);
ROS_DEBUG_STREAM(" result g " << g.norm() << " " << g.transpose());
if(fabs(g.norm() - G.norm()) > 1.0 || s < 0)
{
return false;
}
//重力細化
RefineGravity(all_image_frame, g, x);
s = (x.tail<1>())(0) / 100.0;
(x.tail<1>())(0) = s;
ROS_DEBUG_STREAM(" refine " << g.norm() << " " << g.transpose());
if(s < 0.0 )
return false;
else
return true;
}
重力細化RefineGravity()函數
/**
* @brief 重力矢量細化
* @optional 重力細化,在其切線空間上用兩個變量重新參數化重力 -> Paper V-B-3
g^ = ||g|| * (g^-) + w1b1 + w2b2
* @param[in] all_image_frame 所有圖像幀構成的map,圖像幀保存了位姿,預積分量和關於角點的信息
* @param[out] g 重力加速度
* @param[out] x 待優化變量,窗口中每幀的速度V[0:n]、二自由度重力參數w[w1,w2]^T、尺度s
* @return void
*/
void RefineGravity(map<double, ImageFrame> &all_image_frame, Vector3d &g, VectorXd &x)
{
//g0 = (g^-)*||g||
Vector3d g0 = g.normalized() * G.norm();
Vector3d lx, ly;
//VectorXd x;
int all_frame_count = all_image_frame.size();
int n_state = all_frame_count * 3 + 2 + 1;
MatrixXd A{n_state, n_state};
A.setZero();
VectorXd b{n_state};
b.setZero();
map<double, ImageFrame>::iterator frame_i;
map<double, ImageFrame>::iterator frame_j;
for(int k = 0; k < 4; k++)//迭代4次
{
//lxly = b = [b1,b2]
MatrixXd lxly(3, 2);
lxly = TangentBasis(g0);
int i = 0;
for (frame_i = all_image_frame.begin(); next(frame_i) != all_image_frame.end(); frame_i++, i++)
{
frame_j = next(frame_i);
MatrixXd tmp_A(6, 9);
tmp_A.setZero();
VectorXd tmp_b(6);
tmp_b.setZero();
double dt = frame_j->second.pre_integration->sum_dt;
// tmp_A(6,9) = [-I*dt 0 (R^bk_c0)*dt*dt*b/2 (R^bk_c0)*((p^c0_ck+1)-(p^c0_ck)) ]
// [ -I (R^bk_c0)*(R^c0_bk+1) (R^bk_c0)*dt*b 0 ]
// tmp_b(6,1) = [ (a^bk_bk+1)+(R^bk_c0)*(R^c0_bk+1)*p^b_c-p^b_c - (R^bk_c0)*dt*dt*||g||*(g^-)/2 , (b^bk_bk+1)-(R^bk_c0)dt*||g||*(g^-)]^T
// tmp_A * x = tmp_b 求解最小二乘問題
tmp_A.block<3, 3>(0, 0) = -dt * Matrix3d::Identity();
tmp_A.block<3, 2>(0, 6) = frame_i->second.R.transpose() * dt * dt / 2 * Matrix3d::Identity() * lxly;
tmp_A.block<3, 1>(0, 8) = frame_i->second.R.transpose() * (frame_j->second.T - frame_i->second.T) / 100.0;
tmp_b.block<3, 1>(0, 0) = frame_j->second.pre_integration->delta_p + frame_i->second.R.transpose() * frame_j->second.R * TIC[0] - TIC[0] - frame_i->second.R.transpose() * dt * dt / 2 * g0;
tmp_A.block<3, 3>(3, 0) = -Matrix3d::Identity();
tmp_A.block<3, 3>(3, 3) = frame_i->second.R.transpose() * frame_j->second.R;
tmp_A.block<3, 2>(3, 6) = frame_i->second.R.transpose() * dt * Matrix3d::Identity() * lxly;
tmp_b.block<3, 1>(3, 0) = frame_j->second.pre_integration->delta_v - frame_i->second.R.transpose() * dt * Matrix3d::Identity() * g0;
Matrix<double, 6, 6> cov_inv = Matrix<double, 6, 6>::Zero();
//cov.block<6, 6>(0, 0) = IMU_cov[i + 1];
//MatrixXd cov_inv = cov.inverse();
cov_inv.setIdentity();
MatrixXd r_A = tmp_A.transpose() * cov_inv * tmp_A;
VectorXd r_b = tmp_A.transpose() * cov_inv * tmp_b;
A.block<6, 6>(i * 3, i * 3) += r_A.topLeftCorner<6, 6>();
b.segment<6>(i * 3) += r_b.head<6>();
A.bottomRightCorner<3, 3>() += r_A.bottomRightCorner<3, 3>();
b.tail<3>() += r_b.tail<3>();
A.block<6, 3>(i * 3, n_state - 3) += r_A.topRightCorner<6, 3>();
A.block<3, 6>(n_state - 3, i * 3) += r_A.bottomLeftCorner<3, 6>();
}
A = A * 1000.0;
b = b * 1000.0;
x = A.ldlt().solve(b);
//dg = [w1,w2]^T
VectorXd dg = x.segment<2>(n_state - 3);
g0 = (g0 + lxly * dg).normalized() * G.norm();
//double s = x(n_state - 1);
}
g = g0;
}