本篇代码阅读笔记接着上一篇VINS-Mono代码阅读笔记(七):vins_estimator中相机与IMU的外参标定,来学习一下VINS-Mono中初始化部分的代码。单目紧耦合的VIO系统是一个高非线性系统,在系统开始运行的时候需要准确的初始化估计。VINS-Mono系统通过将IMU预积分值与视觉估计结果进行松散的对齐来得到必要的初始化。在VINS论文的第V. ESTIMATOR INITIALIZATION部分将初始化分为两部分来描述:A.在滑动窗口中仅视觉的SFM估计;B.视觉和惯导的对齐。
初始化部分是从processImage函数中开始的,所以先从processImage中初始化部分的代码开始来分析。
1.processImage中初始化代码
processImage函数中,在做完相机-IMU之间的外参标定后会进行初始化是否完成的判断,也就是下面的代码。
if (solver_flag == INITIAL)
{
//WINDOW_SIZE==10 frame_count达到了WINDOW_SIZE,这样能确保有足够的frame参与初始化
if (frame_count == WINDOW_SIZE)
{
bool result = false;
//外参初始化成功且当前帧时间戳距离上次初始化时间戳大于0.1秒,就进行初始化操作
if( ESTIMATE_EXTRINSIC != 2 && (header.stamp.toSec() - initial_timestamp) > 0.1)
{
//对视觉和惯性单元进行初始化
result = initialStructure();
//初始化时间戳更新
initial_timestamp = header.stamp.toSec();
}
if(result)//初始化成功
{
//先进行一次滑动窗口非线性优化,得到当前帧与第一帧的位姿
solver_flag = NON_LINEAR;
solveOdometry();
slideWindow();
f_manager.removeFailures();
ROS_INFO("Initialization finish!");
last_R = Rs[WINDOW_SIZE];
last_P = Ps[WINDOW_SIZE];
last_R0 = Rs[0];
last_P0 = Ps[0];
}
else
slideWindow();//初始化失败则直接滑动窗口
}
else
frame_count++;//图像帧数量+1
}
solver_flag用于判断初始化是否完成,当其值为INITIAL的时候表示初始化未完成,初始化成功后solver_flag的值会修改为NON_LINEAR。
从上边代码可以看到,只有当滑动窗口中的图像帧个数达到WINDOW_SIZE=10后才会进行初始化操作。这里滑动窗口的大小设置为10帧,是为了限制计算复杂度,因为后边的旋转和平移计算是需要遍历滑动窗口中最后一帧之前的所有帧的。可以看到,调用initialStructure函数后,如果判断初始化失败了,就直接去滑动窗口(也就是根据策略删除窗口中的某一帧)。
2.初始化结构体函数initialStructure代码分析
initialStructure代码如下:
/**
* 视觉惯导联合初始化函数
*/
bool Estimator::initialStructure()
{
TicToc t_sfm;
//1.1.check imu observibility 通过计算标准差来进行判断
{
map<double, ImageFrame>::iterator frame_it;
Vector3d sum_g;
//遍历除了第一帧图像外的所有图像帧
for (frame_it = all_image_frame.begin(), frame_it++; frame_it != all_image_frame.end(); frame_it++)
{
double dt = frame_it->second.pre_integration->sum_dt;
//计算每一帧图像对应的加速度
Vector3d tmp_g = frame_it->second.pre_integration->delta_v / dt;
//图像的加速度之累加和
sum_g += tmp_g;
}
Vector3d aver_g;
//计算平均加速度。因为上边计算的是除了第一帧图像之外的其他所有图像帧对应的加速度之和,所以这里要减去1
aver_g = sum_g * 1.0 / ((int)all_image_frame.size() - 1);
double var = 0;
for (frame_it = all_image_frame.begin(), frame_it++; frame_it != all_image_frame.end(); frame_it++)
{
double dt = frame_it->second.pre_integration->sum_dt;
//计算获得每一帧的加速度
Vector3d tmp_g = frame_it->second.pre_integration->delta_v / dt;
//加速度减去平均加速度的差值的平方的累加
var += (tmp_g - aver_g).transpose() * (tmp_g - aver_g);
//cout << "frame g " << tmp_g.transpose() << endl;
}
/**
* 简单来说,标准差是一组数值自平均值分散开来的程度的一种测量观念。
* 一个较大的标准差,代表大部分的数值和其平均值之间差异较大;一个较小的标准差,代表这些数值较接近平均值。
* 方差公式:s^2=[(x1-x)^2 +...(xn-x)^2]/n
* 标准差等于方差的算数平方根,标准差公式:s=sqrt(s^2)
*/
var = sqrt(var / ((int)all_image_frame.size() - 1));
//ROS_WARN("IMU variation %f!", var);
//通过加速度标准差判断IMU是否有充分运动,标准差必须大于等于0.25
if(var < 0.25)
{
ROS_INFO("IMU excitation not enouth!");
//return false;
}
}
// global sfm
Quaterniond Q[frame_count + 1];//旋转量,四元数数组
Vector3d T[frame_count + 1];//平移量数组
map<int, Vector3d> sfm_tracked_points;//用于存储sfm重建出来的特征点的坐标(所有观测到该特征点的图像帧ID和图像坐标)
vector<SFMFeature> sfm_f;
/**
* 1.2.将f_manager.feature中的feature存储到sfm_f中
*/
for (auto &it_per_id : f_manager.feature)
{
int imu_j = it_per_id.start_frame - 1;
SFMFeature tmp_feature;
tmp_feature.state = false;
tmp_feature.id = it_per_id.feature_id;
//遍历每一个能观察到该feature的frame
for (auto &it_per_frame : it_per_id.feature_per_frame)
{
imu_j++;
Vector3d pts_j = it_per_frame.point;
//每个特征点能够被哪些帧观测到以及特征点在这些帧中的坐标
tmp_feature.observation.push_back(make_pair(imu_j, Eigen::Vector2d{pts_j.x(), pts_j.y()}));
}
sfm_f.push_back(tmp_feature);
}
/**
* 1.3.位姿求解
*/
Matrix3d relative_R;
Vector3d relative_T;
int l;
//通过求取本质矩阵来求解出位姿
/**
* 这里的l表示滑动窗口中第l帧是从第一帧开始到滑动窗口中第一个满足与当前帧的平均视差足够大的帧,
* 会作为参考帧到下面的全局sfm使用,得到的Rt为当前帧到第l帧的坐标系变换Rt,存储在relative_R和relative_T当中
* */
if (!relativePose(relative_R, relative_T, l))
{
ROS_INFO("Not enough features or parallax; Move device around");
return false;
}
GlobalSFM sfm;
/**
* 1.4.三角化特征点,对滑窗每一帧求解sfm问题
*/
if(!sfm.construct(frame_count + 1, Q, T, l,
relative_R, relative_T,
sfm_f, sfm_tracked_points))
{
ROS_DEBUG("global SFM failed!");
marginalization_flag = MARGIN_OLD;
return false;
}
/**
* 1.5.对于所有的图像帧,包括不在滑动窗口中的,提供初始的RT估计,然后solvePnP进行优化
*/
//solve pnp for all frame
map<double, ImageFrame>::iterator frame_it;
map<int, Vector3d>::iterator it;
frame_it = all_image_frame.begin( );
//遍历所有的图像帧
for (int i = 0; frame_it != all_image_frame.end( ); frame_it++)
{
// provide initial guess
cv::Mat r, rvec, t, D, tmp_r;
if((frame_it->first) == Headers[i].stamp.toSec())
{
frame_it->second.is_key_frame = true;
//各帧相对于参考帧的旋转和相机-IMU之间的旋转做乘积,就将坐标系转换到了IMU坐标系下
frame_it->second.R = Q[i].toRotationMatrix() * RIC[0].transpose();
//各帧相对于参考帧的平移
frame_it->second.T = T[i];
i++;
continue;
}
if((frame_it->first) > Headers[i].stamp.toSec())
{
i++;
}
//注意这里的 Q和 T是图像帧的位姿,而不是求解PNP时所用的坐标系变换矩阵,两者具有对称关系
Matrix3d R_inital = (Q[i].inverse()).toRotationMatrix();
Vector3d P_inital = - R_inital * T[i];
cv::eigen2cv(R_inital, tmp_r);
//使用罗德里格斯公式将旋转矩阵转换成旋转向量
cv::Rodrigues(tmp_r, rvec);
cv::eigen2cv(P_inital, t);
frame_it->second.is_key_frame = false;
//获取 pnp需要用到的存储每个特征点三维点和图像坐标的 vector
vector<cv::Point3f> pts_3_vector;
vector<cv::Point2f> pts_2_vector;
for (auto &id_pts : frame_it->second.points)
{
int feature_id = id_pts.first;
for (auto &i_p : id_pts.second)
{
it = sfm_tracked_points.find(feature_id);
if(it != sfm_tracked_points.end())
{
Vector3d world_pts = it->second;
cv::Point3f pts_3(world_pts(0), world_pts(1), world_pts(2));
pts_3_vector.push_back(pts_3);
Vector2d img_pts = i_p.second.head<2>();
cv::Point2f pts_2(img_pts(0), img_pts(1));
pts_2_vector.push_back(pts_2);
}
}
}
/**
* 构造相机内参,因为已经是归一化后坐标了,这里的内参就是单位矩阵了
*/
cv::Mat K = (cv::Mat_<double>(3, 3) << 1, 0, 0, 0, 1, 0, 0, 0, 1);
//保证特征点数大于5,这样就可以用五点法求解
if(pts_3_vector.size() < 6)
{
cout << "pts_3_vector size " << pts_3_vector.size() << endl;
ROS_DEBUG("Not enough points for solve pnp !");
return false;
}
/**
* PnP求解位姿
* bool cv::solvePnP (
* InputArray objectPoints, 世界坐标系中的特征点的坐标
* InputArray imagePoints, 图像中的像素点的坐标
* InputArray cameraMatrix, 相机内参
* InputArray distCoeffs, 去畸变参数
* OutputArray rvec, 要求的旋转量
* OutputArray tvec, 要求的平移量
* bool useExtrinsicGuess = false,
* int flags = SOLVEPNP_ITERATIVE
* )
*/
if (! cv::solvePnP(pts_3_vector, pts_2_vector, K, D, rvec, t, 1))
{
ROS_DEBUG("solve pnp fail!");
return false;
}
//旋转向量到旋转矩阵的转换
cv::Rodrigues(rvec, r);
MatrixXd R_pnp,tmp_R_pnp;
//将矩阵从cv中的cv::Mat类型转换为eigen中的MatrixXd
cv::cv2eigen(r, tmp_R_pnp);
//这里也同样需要将坐标变换矩阵转变成图像帧位姿,并转换为IMU坐标系的位姿
R_pnp = tmp_R_pnp.transpose();
MatrixXd T_pnp;
//将位移矩阵转换为MatrixXd形式
cv::cv2eigen(t, T_pnp);
T_pnp = R_pnp * (-T_pnp);
//将求得的旋转和平移存储起来,这里RIC[0].transpose()是相机到IMU的旋转,这样就把相机坐标系中求出的位姿旋转到IMU坐标系中去了
frame_it->second.R = R_pnp * RIC[0].transpose();
frame_it->second.T = T_pnp;
}
//2.视觉惯性对齐求解
if (visualInitialAlign())
return true;
else
{
ROS_INFO("misalign visual structure with IMU");
return false;
}
}
按照作者论文中的描述,该函数中分为以下两部分:
2.1 滑动窗口中的视觉SFM
这部分代码对应的是论文中V-A部分。通常遇到比较长比较复杂的代码,我比较喜欢将代码按照逻辑划分成块来分析。这部分也照此方法来划分为下面五个部分。
2.1.1 通过标准差判断IMU的运动情况
这部分对应代码如下:
//1.1.check imu observibility 通过计算标准差来进行判断
{
map<double, ImageFrame>::iterator frame_it;
Vector3d sum_g;
//遍历除了第一帧图像外的所有图像帧
for (frame_it = all_image_frame.begin(), frame_it++; frame_it != all_image_frame.end(); frame_it++)
{
double dt = frame_it->second.pre_integration->sum_dt;
//计算每一帧图像对应的加速度
Vector3d tmp_g = frame_it->second.pre_integration->delta_v / dt;
//图像的加速度之累加和
sum_g += tmp_g;
}
Vector3d aver_g;
//计算平均加速度。因为上边计算的是除了第一帧图像之外的其他所有图像帧对应的加速度之和,所以这里要减去1
aver_g = sum_g * 1.0 / ((int)all_image_frame.size() - 1);
double var = 0;
for (frame_it = all_image_frame.begin(), frame_it++; frame_it != all_image_frame.end(); frame_it++)
{
double dt = frame_it->second.pre_integration->sum_dt;
//计算获得每一帧的加速度
Vector3d tmp_g = frame_it->second.pre_integration->delta_v / dt;
//加速度减去平均加速度的差值的平方的累加
var += (tmp_g - aver_g).transpose() * (tmp_g - aver_g);
//cout << "frame g " << tmp_g.transpose() << endl;
}
/**
* 简单来说,标准差是一组数值自平均值分散开来的程度的一种测量观念。
* 一个较大的标准差,代表大部分的数值和其平均值之间差异较大;一个较小的标准差,代表这些数值较接近平均值。
* 方差公式:s^2=[(x1-x)^2 +...(xn-x)^2]/n
* 标准差等于方差的算数平方根,标准差公式:s=sqrt(s^2)
*/
var = sqrt(var / ((int)all_image_frame.size() - 1));
//ROS_WARN("IMU variation %f!", var);
//通过加速度标准差判断IMU是否有充分运动,标准差必须大于等于0.25
if(var < 0.25)
{
ROS_INFO("IMU excitation not enouth!");
//return false;
}
}
以上代码其实是通过IMU预积分得到的图像帧对应的速度来计算所有图像的加速度累加和,再通过加速度累加和计算平均加速度,进而求得加速度的标准差。我在代码注释中也写明了标准差的物理意义:标准差是一组数值自平均值分散开来的程度的一种测量观念。对应到VINS系统中来说,这里计算的标准差可以反应IMU中加速度计运行的情况。匀速运动的加速度为0,在这种情况下加速度计就要“失效”了。
但是不清楚的是,为什么这里设定的标准差阈值0.25的情况下,在标准差小于0.25的时候分支代码中的return false作者注释掉了。这样的话这一部分代码的计算就是无用的了。为什么要注释掉呢???
2.1.2 将全局feature当中的特征存储到sfm_f中
这部分对应代码如下:
/**
* 1.2.将f_manager.feature中的feature存储到sfm_f中
*/
for (auto &it_per_id : f_manager.feature)
{
int imu_j = it_per_id.start_frame - 1;
SFMFeature tmp_feature;
tmp_feature.state = false;
tmp_feature.id = it_per_id.feature_id;
//遍历每一个能观察到该feature的frame
for (auto &it_per_frame : it_per_id.feature_per_frame)
{
imu_j++;
Vector3d pts_j = it_per_frame.point;
tmp_feature.observation.push_back(make_pair(imu_j, Eigen::Vector2d{pts_j.x(), pts_j.y()}));
}
sfm_f.push_back(tmp_feature);
}
遍历feature,获得里边每一个特征点对应的图像帧中点的x,y坐标存入tmp_feature中,最后将tmp_feature存入到sfm_f中。后边就可以通过sfm_f获取到feature的id以及有哪些帧可以观测到该feature以及在图像帧中的坐标。
2.1.3 求解最新帧和滑动窗口中第一个满足条件的帧之间的位姿关系
这部分对应代码如下:
/**
* 1.3.位姿求解
*/
Matrix3d relative_R;
Vector3d relative_T;
int l;
//通过求取本质矩阵来求解出位姿
/**
* 这里的l表示滑动窗口中第l帧是从第一帧开始到滑动窗口中第一个满足与当前帧的平均视差足够大的帧,
* 会作为参考帧到下面的全局sfm使用,得到的Rt为当前帧到第l帧的坐标系变换Rt,存储在relative_R和relative_T当中
* */
if (!relativePose(relative_R, relative_T, l))
{
ROS_INFO("Not enough features or parallax; Move device around");
return false;
}
这里是要通过relativePose函数计算出滑动窗口中第l帧和最新图像帧之间的旋转和平移的。至于这个l是怎么计算出来的,看下面的代码就知道了。
/**
* 这里的第l帧是从第一帧开始到滑动窗口中第一个满足与当前帧的平均视差足够大的帧,
* 会作为参考帧到下面的全局sfm使用,得到的Rt为当前帧到第l帧的坐标系变换Rt
* 该函数判断滑动窗口中第一个到窗口最后一帧对应特征点的平均视差大于30,且内点数目大于12的帧,此时可进行初始化,同时返回当前帧到第l帧的坐标系变换R和T
* */
bool Estimator::relativePose(Matrix3d &relative_R, Vector3d &relative_T, int &l)
{
// find previous frame which contians enough correspondance and parallex with newest frame
for (int i = 0; i < WINDOW_SIZE; i++)
{
vector<pair<Vector3d, Vector3d>> corres;
//寻找第i帧到窗口最后一帧的对应特征点,存放在corres中
corres = f_manager.getCorresponding(i, WINDOW_SIZE);
//匹配的特征点对要大于20
if (corres.size() > 20)
{
//计算平均视差
double sum_parallax = 0;
double average_parallax;
for (int j = 0; j < int(corres.size()); j++)
{
//第j个对应点在第i帧和最后一帧的(x,y)
Vector2d pts_0(corres[j].first(0), corres[j].first(1));
Vector2d pts_1(corres[j].second(0), corres[j].second(1));
//计算视差
double parallax = (pts_0 - pts_1).norm();
//计算视差的总和
sum_parallax = sum_parallax + parallax;
}
//计算平均视差
average_parallax = 1.0 * sum_parallax / int(corres.size());
//判断是否满足初始化条件:视差>30和内点数满足要求(大于12)
//solveRelativeRT()通过基础矩阵计算当前帧与第l帧之间的R和T,并判断内点数目是否足够
//同时返回窗口最后一帧(当前帧)到第l帧(参考帧)的relative_R,relative_T
if(average_parallax * 460 > 30 && m_estimator.solveRelativeRT(corres, relative_R, relative_T))
{
//l中存放的是窗口中从最前边开始遍历和最后一帧满足视差和RT估计的第一个帧的id
l = i;
ROS_DEBUG("average_parallax %f choose l %d and newest frame to triangulate the whole structure", average_parallax * 460, l);
return true;
}
}
}
return false;
}
relativePose函数中遍历滑动窗口中的图像帧,计算每一帧和最新一帧图像之间对应的匹配特征点对。在遍历滑动窗口过程中,如果匹配的特征点对数大于20则计算这些特征点对的平均视差。如果平均视差大于30,则继续根据匹配的特征点对调用solveRelativeRT计算旋转和平移。
solveRelativeRT代码如下所示:
/**
* 根据提供的特征点对计算旋转矩阵和平移向量
*/
bool MotionEstimator::solveRelativeRT(const vector<pair<Vector3d, Vector3d>> &corres, Matrix3d &Rotation, Vector3d &Translation)
{
if (corres.size() >= 15)
{
vector<cv::Point2f> ll, rr;
for (int i = 0; i < int(corres.size()); i++)
{
ll.push_back(cv::Point2f(corres[i].first(0), corres[i].first(1)));
rr.push_back(cv::Point2f(corres[i].second(0), corres[i].second(1)));
}
cv::Mat mask;
/**
* 求得本质矩阵
* Mat cv::findFundamentalMat(
* InputArray points1, //第一幅图像中的特征点数组
* InputArray points2, //第二幅图像中的特征点数组
* int method = FM_RANSAC, //计算fundamental matrix的方法,这里使用了cv::FM_RANSAC,说明使用了8点法进行求解的
* CV_FM_7POINT for a 7-point algorithm. N=7
* CV_FM_8POINT for an 8-point algorithm. N≥8
* CV_FM_RANSAC for the RANSAC algorithm. N≥8
* CV_FM_LMEDS for the LMedS algorithm. N≥8
* double ransacReprojThreshold = 3., //点到对极线的最大距离,超过这个值的点将被舍弃
* double confidence = 0.99, //矩阵正确的可信度
* OutputArray mask = noArray() //输出在计算过程中没有被舍弃的点
* )
* 该函数对应链接:https://docs.opencv.org/3.4/d9/d0c/group__calib3d.html#gae420abc34eaa03d0c6a67359609d8429
*/
cv::Mat E = cv::findFundamentalMat(ll, rr, cv::FM_RANSAC, 0.3 / 460, 0.99, mask);
//cameraMatrix初始化为单位矩阵
cv::Mat cameraMatrix = (cv::Mat_<double>(3, 3) << 1, 0, 0, 0, 1, 0, 0, 0, 1);
cv::Mat rot, trans;
//由本质矩阵恢复出位姿
/**
* int cv::recoverPose ( InputArray E, //本质矩阵
* InputArray points1, //第一幅图像点的数组
* InputArray points2, //第二幅图像点的数组
* InputArray cameraMatrix, //相机内参
* OutputArray R, //第一帧坐标系到第二帧坐标系的旋转矩阵
* OutputArray t, //第一帧坐标系到第二帧坐标系的平移向量
* InputOutputArray mask = noArray() //在findFundamentalMat()中没有被舍弃的点
* )
*/
int inlier_cnt = cv::recoverPose(E, ll, rr, cameraMatrix, rot, trans, mask);
//cout << "inlier_cnt " << inlier_cnt << endl;
Eigen::Matrix3d R;
Eigen::Vector3d T;
for (int i = 0; i < 3; i++)
{
T(i) = trans.at<double>(i, 0);
for (int j = 0; j < 3; j++)
R(i, j) = rot.at<double>(i, j);
}
//得到旋转平移
Rotation = R.transpose();
Translation = -R.transpose() * T;
//内点数必须大于12
if(inlier_cnt > 12)
return true;
else
return false;
}
return false;
}
这里计算出滑动窗口中第一个满足条件的帧和最新帧之间的旋转和平移之后,还要判断内点数是否大于12,大于12才认为计算出的旋转和平移量是有效的。
2.1.4 三角化求解地图点的深度
这部分代码如下:
GlobalSFM sfm;
/**
* 1.4.三角化特征点,对滑窗每一帧求解sfm问题
*/
if(!sfm.construct(frame_count + 1, Q, T, l,
relative_R, relative_T,
sfm_f, sfm_tracked_points))
{
ROS_DEBUG("global SFM failed!");
marginalization_flag = MARGIN_OLD;
return false;
}
construct函数代码如下,具体步骤见代码中注释部分,需要注意的是这里求解的pose[i]表示第l帧到第i帧的变换矩阵T=[R|T]。
/**
* 对窗口中每个图像帧求解sfm问题,得到所有图像帧相对于参考帧的旋转四元数Q、平移向量T和特征点坐标sfm_tracked_points
* 参数frame_num的值为frame_count + 1
* 传入的参数l就是参考帧的index
* */
bool GlobalSFM::construct(int frame_num, Quaterniond* q, Vector3d* T, int l,
const Matrix3d relative_R, const Vector3d relative_T,
vector<SFMFeature> &sfm_f, map<int, Vector3d> &sfm_tracked_points)
{
feature_num = sfm_f.size();
//cout << "set 0 and " << l << " as known " << endl;
// have relative_r relative_t
// intial two view
//q为四元数数组,大小为frame_count+1
q[l].w() = 1;
q[l].x() = 0;
q[l].y() = 0;
q[l].z() = 0;
//T为平移量数组,大小为frame_count+1
T[l].setZero();
//往q中存入最新帧的旋转,该旋转等于第l帧的旋转和相对旋转的四元数乘积
q[frame_num - 1] = q[l] * Quaterniond(relative_R);
T[frame_num - 1] = relative_T;
//cout << "init q_l " << q[l].w() << " " << q[l].vec().transpose() << endl;
//cout << "init t_l " << T[l].transpose() << endl;
//rotate to cam frame
Matrix3d c_Rotation[frame_num];
Vector3d c_Translation[frame_num];
Quaterniond c_Quat[frame_num];
double c_rotation[frame_num][4];
double c_translation[frame_num][3];
Eigen::Matrix<double, 3, 4> Pose[frame_num];
c_Quat[l] = q[l].inverse();//c_Quat[l]中存放q[l]的逆
c_Rotation[l] = c_Quat[l].toRotationMatrix();//四元数转为旋转矩阵
c_Translation[l] = -1 * (c_Rotation[l] * T[l]);
/**
* matrix.block(i,j, p, q) : 表示返回从矩阵(i, j)开始,每行取p个元素,每列取q个元素所组成的临时新矩阵对象,原矩阵的元素不变;
* matrix.block<p,q>(i, j) :<p, q>可理解为一个p行q列的子矩阵,该定义表示从原矩阵中第(i, j)开始,获取一个p行q列的子矩阵,
* 返回该子矩阵组成的临时矩阵对象,原矩阵的元素不变;
*/
//将第l帧的旋转和平移量存入到Pose当中
Pose[l].block<3, 3>(0, 0) = c_Rotation[l];
Pose[l].block<3, 1>(0, 3) = c_Translation[l];
c_Quat[frame_num - 1] = q[frame_num - 1].inverse();
c_Rotation[frame_num - 1] = c_Quat[frame_num - 1].toRotationMatrix();
c_Translation[frame_num - 1] = -1 * (c_Rotation[frame_num - 1] * T[frame_num - 1]);
Pose[frame_num - 1].block<3, 3>(0, 0) = c_Rotation[frame_num - 1];
Pose[frame_num - 1].block<3, 1>(0, 3) = c_Translation[frame_num - 1];
//至此,计算出了滑动窗口中第l帧的位姿Pose[l]和最新帧的位姿Pose[frame_num-1],下面就是三角化处理
//1: trangulate between l ----- frame_num - 1
//2: solve pnp l + 1; trangulate l + 1 ------- frame_num - 1;
for (int i = l; i < frame_num - 1 ; i++)//对于参考帧和当前帧之间的某一帧,三角化该帧和当前帧的路标点
{
// solve pnp
if (i > l)//不是参考帧
{
Matrix3d R_initial = c_Rotation[i - 1];
Vector3d P_initial = c_Translation[i - 1];
if(!solveFrameByPnP(R_initial, P_initial, i, sfm_f))
return false;
c_Rotation[i] = R_initial;
c_Translation[i] = P_initial;
c_Quat[i] = c_Rotation[i];
Pose[i].block<3, 3>(0, 0) = c_Rotation[i];
Pose[i].block<3, 1>(0, 3) = c_Translation[i];
}
// triangulate point based on the solve pnp result
triangulateTwoFrames(i, Pose[i], frame_num - 1, Pose[frame_num - 1], sfm_f);
}
//3: triangulate l-----l+1 l+2 ... frame_num -2
for (int i = l + 1; i < frame_num - 1; i++)//对于参考帧和当前帧之间的某一帧,三角化参考帧和该帧的路标点
triangulateTwoFrames(l, Pose[l], i, Pose[i], sfm_f);
//4: solve pnp l-1; triangulate l-1 ----- l
// l-2 l-2 ----- l
for (int i = l - 1; i >= 0; i--)//对于第一帧和参考帧之间的某一帧,先用PnP求解该帧位姿,然后三角化该帧到参考帧的路标点
{
//solve pnp
Matrix3d R_initial = c_Rotation[i + 1];
Vector3d P_initial = c_Translation[i + 1];
if(!solveFrameByPnP(R_initial, P_initial, i, sfm_f))
return false;
c_Rotation[i] = R_initial;
c_Translation[i] = P_initial;
c_Quat[i] = c_Rotation[i];
Pose[i].block<3, 3>(0, 0) = c_Rotation[i];
Pose[i].block<3, 1>(0, 3) = c_Translation[i];
//triangulate
triangulateTwoFrames(i, Pose[i], l, Pose[l], sfm_f);
}
//5: triangulate all other points
for (int j = 0; j < feature_num; j++)//三角化其他未恢复的路标点
{
if (sfm_f[j].state == true)
continue;
if ((int)sfm_f[j].observation.size() >= 2)
{
Vector2d point0, point1;
int frame_0 = sfm_f[j].observation[0].first;
point0 = sfm_f[j].observation[0].second;
int frame_1 = sfm_f[j].observation.back().first;
point1 = sfm_f[j].observation.back().second;
Vector3d point_3d;
triangulatePoint(Pose[frame_0], Pose[frame_1], point0, point1, point_3d);
sfm_f[j].state = true;
sfm_f[j].position[0] = point_3d(0);
sfm_f[j].position[1] = point_3d(1);
sfm_f[j].position[2] = point_3d(2);
//cout << "trangulated : " << frame_0 << " " << frame_1 << " 3d point : " << j << " " << point_3d.transpose() << endl;
}
}
/*
for (int i = 0; i < frame_num; i++)
{
q[i] = c_Rotation[i].transpose();
cout << "solvePnP q" << " i " << i <<" " <<q[i].w() << " " << q[i].vec().transpose() << endl;
}
for (int i = 0; i < frame_num; i++)
{
Vector3d t_tmp;
t_tmp = -1 * (q[i] * c_Translation[i]);
cout << "solvePnP t" << " i " << i <<" " << t_tmp.x() <<" "<< t_tmp.y() <<" "<< t_tmp.z() << endl;
}
*/
//full BA
ceres::Problem problem;
ceres::LocalParameterization* local_parameterization = new ceres::QuaternionParameterization();
//cout << " begin full BA " << endl;
for (int i = 0; i < frame_num; i++)
{
//double array for ceres
c_translation[i][0] = c_Translation[i].x();
c_translation[i][1] = c_Translation[i].y();
c_translation[i][2] = c_Translation[i].z();
c_rotation[i][0] = c_Quat[i].w();
c_rotation[i][1] = c_Quat[i].x();
c_rotation[i][2] = c_Quat[i].y();
c_rotation[i][3] = c_Quat[i].z();
problem.AddParameterBlock(c_rotation[i], 4, local_parameterization);
problem.AddParameterBlock(c_translation[i], 3);
if (i == l)
{
problem.SetParameterBlockConstant(c_rotation[i]);
}
if (i == l || i == frame_num - 1)
{
problem.SetParameterBlockConstant(c_translation[i]);
}
}
for (int i = 0; i < feature_num; i++)
{
if (sfm_f[i].state != true)
continue;
for (int j = 0; j < int(sfm_f[i].observation.size()); j++)
{
int l = sfm_f[i].observation[j].first;
ceres::CostFunction* cost_function = ReprojectionError3D::Create(
sfm_f[i].observation[j].second.x(),
sfm_f[i].observation[j].second.y());
problem.AddResidualBlock(cost_function, NULL, c_rotation[l], c_translation[l],
sfm_f[i].position);
}
}
ceres::Solver::Options options;
options.linear_solver_type = ceres::DENSE_SCHUR;
//options.minimizer_progress_to_stdout = true;
options.max_solver_time_in_seconds = 0.2;
ceres::Solver::Summary summary;
ceres::Solve(options, &problem, &summary);
//std::cout << summary.BriefReport() << "\n";
if (summary.termination_type == ceres::CONVERGENCE || summary.final_cost < 5e-03)
{
//cout << "vision only BA converge" << endl;
}
else
{
//cout << "vision only BA not converge " << endl;
return false;
}
for (int i = 0; i < frame_num; i++)
{
q[i].w() = c_rotation[i][0];
q[i].x() = c_rotation[i][1];
q[i].y() = c_rotation[i][2];
q[i].z() = c_rotation[i][3];
q[i] = q[i].inverse();
//cout << "final q" << " i " << i <<" " <<q[i].w() << " " << q[i].vec().transpose() << endl;
}
for (int i = 0; i < frame_num; i++)
{
T[i] = -1 * (q[i] * Vector3d(c_translation[i][0], c_translation[i][1], c_translation[i][2]));
//cout << "final t" << " i " << i <<" " << T[i](0) <<" "<< T[i](1) <<" "<< T[i](2) << endl;
}
for (int i = 0; i < (int)sfm_f.size(); i++)
{
if(sfm_f[i].state)
sfm_tracked_points[sfm_f[i].id] = Vector3d(sfm_f[i].position[0], sfm_f[i].position[1], sfm_f[i].position[2]);
}
return true;
}
2.1.5 PnP求解位姿
/**
* 1.5.对于所有的图像帧,包括不在滑动窗口中的,提供初始的RT估计,然后solvePnP进行优化
*/
//solve pnp for all frame
map<double, ImageFrame>::iterator frame_it;
map<int, Vector3d>::iterator it;
frame_it = all_image_frame.begin( );
for (int i = 0; frame_it != all_image_frame.end( ); frame_it++)
{
// provide initial guess
cv::Mat r, rvec, t, D, tmp_r;
if((frame_it->first) == Headers[i].stamp.toSec())
{
frame_it->second.is_key_frame = true;
frame_it->second.R = Q[i].toRotationMatrix() * RIC[0].transpose();
frame_it->second.T = T[i];
i++;
continue;
}
if((frame_it->first) > Headers[i].stamp.toSec())
{
i++;
}
//注意这里的 Q和 T是图像帧的位姿,而不是求解PNP时所用的坐标系变换矩阵,两者具有对称关系
Matrix3d R_inital = (Q[i].inverse()).toRotationMatrix();
Vector3d P_inital = - R_inital * T[i];
cv::eigen2cv(R_inital, tmp_r);
//罗德里格斯公式将旋转矩阵转换成旋转向量
cv::Rodrigues(tmp_r, rvec);
cv::eigen2cv(P_inital, t);
frame_it->second.is_key_frame = false;
//获取 pnp需要用到的存储每个特征点三维点和图像坐标的 vector
vector<cv::Point3f> pts_3_vector;
vector<cv::Point2f> pts_2_vector;
for (auto &id_pts : frame_it->second.points)
{
int feature_id = id_pts.first;
for (auto &i_p : id_pts.second)
{
it = sfm_tracked_points.find(feature_id);
if(it != sfm_tracked_points.end())
{
Vector3d world_pts = it->second;
cv::Point3f pts_3(world_pts(0), world_pts(1), world_pts(2));
pts_3_vector.push_back(pts_3);
Vector2d img_pts = i_p.second.head<2>();
cv::Point2f pts_2(img_pts(0), img_pts(1));
pts_2_vector.push_back(pts_2);
}
}
}
//保证特征点数大于 5
cv::Mat K = (cv::Mat_<double>(3, 3) << 1, 0, 0, 0, 1, 0, 0, 0, 1);
if(pts_3_vector.size() < 6)
{
cout << "pts_3_vector size " << pts_3_vector.size() << endl;
ROS_DEBUG("Not enough points for solve pnp !");
return false;
}
//PnP求解位姿
if (! cv::solvePnP(pts_3_vector, pts_2_vector, K, D, rvec, t, 1))
{
ROS_DEBUG("solve pnp fail!");
return false;
}
cv::Rodrigues(rvec, r);
MatrixXd R_pnp,tmp_R_pnp;
cv::cv2eigen(r, tmp_R_pnp);
//这里也同样需要将坐标变换矩阵转变成图像帧位姿,并转换为IMU坐标系的位姿
R_pnp = tmp_R_pnp.transpose();
MatrixXd T_pnp;
cv::cv2eigen(t, T_pnp);
T_pnp = R_pnp * (-T_pnp);
frame_it->second.R = R_pnp * RIC[0].transpose();
frame_it->second.T = T_pnp;
}
这里需要重点了解一下solvePnP这个函数,该函数是opencv提供的在给出世界坐标系下的3d点坐标和与这些3d点坐标对应的像素平面上的2d点坐标的情况下求解旋转和平移量的函数。代码中求解出来的就是rvec旋转量和t平移量。这个图示过程可以参看下图所示,该图来自opencv中solvePnP函数的解释中,路径如下:solvePnP函数官方解释
2.2 视觉惯导对齐
这部分代码对应的是论文中V-B部分。