orb_slam3_details/src/LoopClosing.cc

2868 lines
128 KiB
C++
Raw Normal View History

2020-12-01 11:58:17 +08:00
/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
* License as published by the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with ORB-SLAM3.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "LoopClosing.h"
#include "Sim3Solver.h"
#include "Converter.h"
#include "Optimizer.h"
#include "ORBmatcher.h"
#include "G2oTypes.h"
#include<mutex>
#include<thread>
namespace ORB_SLAM3
{
LoopClosing::LoopClosing(Atlas *pAtlas, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale):
mbResetRequested(false), mbResetActiveMapRequested(false), mbFinishRequested(false), mbFinished(true), mpAtlas(pAtlas),
mpKeyFrameDB(pDB), mpORBVocabulary(pVoc), mpMatchedKF(NULL), mLastLoopKFid(0), mbRunningGBA(false), mbFinishedGBA(true),
mbStopGBA(false), mpThreadGBA(NULL), mbFixScale(bFixScale), mnFullBAIdx(0), mnLoopNumCoincidences(0), mnMergeNumCoincidences(0),
mbLoopDetected(false), mbMergeDetected(false), mnLoopNumNotFound(0), mnMergeNumNotFound(0)
{
// 连续性阈值
mnCovisibilityConsistencyTh = 3;
mpLastCurrentKF = static_cast<KeyFrame*>(NULL);
}
// 设置追踪线程句柄
void LoopClosing::SetTracker(Tracking *pTracker)
{
mpTracker=pTracker;
}
// 设置局部建图线程的句柄
void LoopClosing::SetLocalMapper(LocalMapping *pLocalMapper)
{
mpLocalMapper=pLocalMapper;
}
// 回环线程主函数
void LoopClosing::Run()
{
mbFinished =false;
// 线程主循环
while(1)
{
// Check if there are keyframes in the queue
// Loopclosing中的关键帧是LocalMapping发送过来的LocalMapping是Tracking中发过来的
// 在LocalMapping中通过 InsertKeyFrame 将关键帧插入闭环检测队列mlpLoopKeyFrameQueue
// Step 1 查看闭环检测队列mlpLoopKeyFrameQueue中有没有关键帧进来
if(CheckNewKeyFrames())
{
2021-09-03 14:24:01 +08:00
if(mpLastCurrentKF) // 这部分后续未使用
2020-12-01 11:58:17 +08:00
{
mpLastCurrentKF->mvpLoopCandKFs.clear();
mpLastCurrentKF->mvpMergeCandKFs.clear();
}
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
timeDetectBoW = 0;
std::chrono::steady_clock::time_point time_StartDetectBoW = std::chrono::steady_clock::now();
#endif
2021-09-03 14:24:01 +08:00
// Step 2 检测有没有共视的区域
2021-08-09 19:34:51 +08:00
bool bDetected = NewDetectCommonRegions();
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndDetectBoW = std::chrono::steady_clock::now();
double timeDetect = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndDetectBoW - time_StartDetectBoW).count();
double timeDetectSE3 = timeDetect - timeDetectBoW;
if(timeDetectBoW > 0)
{
vTimeBoW_ms.push_back(timeDetectBoW);
}
vTimeSE3_ms.push_back(timeDetectSE3);
vTimePRTotal_ms.push_back(timeDetect);
#endif
if(bDetected)
2020-12-01 11:58:17 +08:00
{
2021-09-03 14:24:01 +08:00
// Step 3 如果检测到融合(当前关键帧与其他地图有关联), 则合并地图
2020-12-01 11:58:17 +08:00
if(mbMergeDetected)
{
2021-09-03 14:24:01 +08:00
// 在imu模式下没有初始化就放弃融合
2020-12-01 11:58:17 +08:00
if ((mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) &&
(!mpCurrentKF->GetMap()->isImuInitialized()))
{
cout << "IMU is not initilized, merge is aborted" << endl;
}
2021-09-03 14:24:01 +08:00
// 如果imu模式下成功初始化,或者非imu模式
2020-12-01 11:58:17 +08:00
else
{
Verbose::PrintMess("*Merged detected", Verbose::VERBOSITY_QUIET);
Verbose::PrintMess("Number of KFs in the current map: " + to_string(mpCurrentKF->GetMap()->KeyFramesInMap()), Verbose::VERBOSITY_DEBUG);
2021-09-03 14:24:01 +08:00
// 拿到融合帧在自己地图所在坐标系(w2)下的位姿
2020-12-01 11:58:17 +08:00
cv::Mat mTmw = mpMergeMatchedKF->GetPose();
g2o::Sim3 gSmw2(Converter::toMatrix3d(mTmw.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTmw.rowRange(0, 3).col(3)),1.0);
2021-09-03 14:24:01 +08:00
// 拿到当前帧在自己地图所在坐标系(w1)下的位姿
2020-12-01 11:58:17 +08:00
cv::Mat mTcw = mpCurrentKF->GetPose();
g2o::Sim3 gScw1(Converter::toMatrix3d(mTcw.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTcw.rowRange(0, 3).col(3)),1.0);
2021-09-03 14:24:01 +08:00
// 根据共同区域检测时的Sim3结果得到当前帧在w2下的位姿
// l = c , w2 = 2
2020-12-01 11:58:17 +08:00
g2o::Sim3 gSw2c = mg2oMergeSlw.inverse();
2021-09-03 14:24:01 +08:00
// 这个没有用到 : 融合帧在w1下的位姿
2020-12-01 11:58:17 +08:00
g2o::Sim3 gSw1m = mg2oMergeSlw;
2021-09-03 14:24:01 +08:00
// 记录焊接变换(Sim3) T_w2_w1 , 这个量实际是两个地图坐标系的关系 T_w2_w1 = T_w2_c * T_c_w1
2020-12-01 11:58:17 +08:00
mSold_new = (gSw2c * gScw1);
2021-09-03 14:24:01 +08:00
// 如果是imu模式
2020-12-01 11:58:17 +08:00
if(mpCurrentKF->GetMap()->IsInertial() && mpMergeMatchedKF->GetMap()->IsInertial())
{
2021-09-03 14:24:01 +08:00
// 如果尺度变换太大, 则放弃融合
2020-12-01 11:58:17 +08:00
if(mSold_new.scale()<0.90||mSold_new.scale()>1.1){
mpMergeLastCurrentKF->SetErase();
mpMergeMatchedKF->SetErase();
mnMergeNumCoincidences = 0;
mvpMergeMatchedMPs.clear();
mvpMergeMPs.clear();
mnMergeNumNotFound = 0;
mbMergeDetected = false;
Verbose::PrintMess("scale bad estimated. Abort merging", Verbose::VERBOSITY_NORMAL);
continue;
}
// If inertial, force only yaw
2021-09-03 14:24:01 +08:00
// 如果是imu模式,强制将焊接变换的的 roll 和 pitch 设为0
2020-12-01 11:58:17 +08:00
if ((mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) &&
mpCurrentKF->GetMap()->GetIniertialBA1()) // TODO, maybe with GetIniertialBA1
{
Eigen::Vector3d phi = LogSO3(mSold_new.rotation().toRotationMatrix());
phi(0)=0;
phi(1)=0;
mSold_new = g2o::Sim3(ExpSO3(phi),mSold_new.translation(),1.0);
}
}
2021-09-03 14:24:01 +08:00
// 这个变量没有用到
2020-12-01 11:58:17 +08:00
mg2oMergeSmw = gSmw2 * gSw2c * gScw1;
2021-09-03 14:24:01 +08:00
// 更新mg2oMergeScw
2020-12-01 11:58:17 +08:00
mg2oMergeScw = mg2oMergeSlw;
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartMerge = std::chrono::steady_clock::now();
#endif
2020-12-01 11:58:17 +08:00
if (mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO)
2021-09-03 14:24:01 +08:00
// 如果是imu模式,则开启 Visual-Inertial Map Merging
2020-12-01 11:58:17 +08:00
MergeLocal2();
else
2021-09-03 14:24:01 +08:00
// 如果是纯视觉模式,则开启 Visual-Welding Map Merging
2020-12-01 11:58:17 +08:00
MergeLocal();
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndMerge = std::chrono::steady_clock::now();
double timeMerge = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndMerge - time_StartMerge).count();
vTimeMergeTotal_ms.push_back(timeMerge);
#endif
2020-12-01 11:58:17 +08:00
}
2021-09-03 14:24:01 +08:00
// 记录时间戳
2020-12-01 11:58:17 +08:00
vdPR_CurrentTime.push_back(mpCurrentKF->mTimeStamp);
vdPR_MatchedTime.push_back(mpMergeMatchedKF->mTimeStamp);
2021-09-03 14:24:01 +08:00
// 标记Place recognition结果为地图融合
2020-12-01 11:58:17 +08:00
vnPR_TypeRecogn.push_back(1);
// Reset all variables
2021-09-03 14:24:01 +08:00
// 重置所有融合相关变量
2020-12-01 11:58:17 +08:00
mpMergeLastCurrentKF->SetErase();
mpMergeMatchedKF->SetErase();
mnMergeNumCoincidences = 0;
mvpMergeMatchedMPs.clear();
mvpMergeMPs.clear();
mnMergeNumNotFound = 0;
mbMergeDetected = false;
2021-09-03 14:24:01 +08:00
// 重置所有回环相关变量, 说明对与当前帧同时有回环和融合的情况只进行融合
2020-12-01 11:58:17 +08:00
if(mbLoopDetected)
{
// Reset Loop variables
mpLoopLastCurrentKF->SetErase();
mpLoopMatchedKF->SetErase();
mnLoopNumCoincidences = 0;
mvpLoopMatchedMPs.clear();
mvpLoopMPs.clear();
mnLoopNumNotFound = 0;
mbLoopDetected = false;
}
}
2021-09-03 14:24:01 +08:00
// Step 4 如果(没有检测到融合)检测到回环, 则回环矫正
2020-12-01 11:58:17 +08:00
if(mbLoopDetected)
{
2021-09-03 14:24:01 +08:00
// 标记时间戳
2020-12-01 11:58:17 +08:00
vdPR_CurrentTime.push_back(mpCurrentKF->mTimeStamp);
vdPR_MatchedTime.push_back(mpLoopMatchedKF->mTimeStamp);
vnPR_TypeRecogn.push_back(0);
Verbose::PrintMess("*Loop detected", Verbose::VERBOSITY_QUIET);
2021-09-03 14:24:01 +08:00
// 更新 mg2oLoopScw
2020-12-01 11:58:17 +08:00
mg2oLoopScw = mg2oLoopSlw; //*mvg2oSim3LoopTcw[nCurrentIndex];
2021-09-03 14:24:01 +08:00
// 如果是带imu的模式
2020-12-01 11:58:17 +08:00
if(mpCurrentKF->GetMap()->IsInertial())
{
2021-09-03 14:24:01 +08:00
// 拿到当前关键帧相对于世界坐标系的位姿
2020-12-01 11:58:17 +08:00
cv::Mat Twc = mpCurrentKF->GetPoseInverse();
g2o::Sim3 g2oTwc(Converter::toMatrix3d(Twc.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(Twc.rowRange(0, 3).col(3)),1.0);
2021-09-03 14:24:01 +08:00
// mg2oLoopScw是通过回环检测的Sim3计算出的回环矫正后的当前关键帧的初始位姿, Twc是当前关键帧回环矫正前的位姿.
// g2oSww_new 可以理解为correction
2020-12-01 11:58:17 +08:00
g2o::Sim3 g2oSww_new = g2oTwc*mg2oLoopScw;
2021-09-03 14:24:01 +08:00
// 拿到 roll ,pitch ,yaw
2020-12-01 11:58:17 +08:00
Eigen::Vector3d phi = LogSO3(g2oSww_new.rotation().toRotationMatrix());
//cout << "tw2w1: " << g2oSww_new.translation() << endl;
//cout << "Rw2w1: " << g2oSww_new.rotation().toRotationMatrix() << endl;
//cout << "Angle Rw2w1: " << 180*phi/3.14 << endl;
//cout << "scale w2w1: " << g2oSww_new.scale() << endl;
2021-09-03 14:24:01 +08:00
// 这里算是通过imu重力方向验证回环结果, 如果pitch或roll角度偏差稍微有一点大,则回环失败. 对phi容忍比较大(20度)
2020-12-01 11:58:17 +08:00
if (fabs(phi(0))<0.008f && fabs(phi(1))<0.008f && fabs(phi(2))<0.349f)
{
2021-09-03 14:24:01 +08:00
// 如果是imu模式
2020-12-01 11:58:17 +08:00
if(mpCurrentKF->GetMap()->IsInertial())
{
// If inertial, force only yaw
2021-09-03 14:24:01 +08:00
// 如果是imu模式,强制将焊接变换的的 roll 和 pitch 设为0
2020-12-01 11:58:17 +08:00
if ((mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) &&
mpCurrentKF->GetMap()->GetIniertialBA2()) // TODO, maybe with GetIniertialBA1
{
phi(0)=0;
phi(1)=0;
g2oSww_new = g2o::Sim3(ExpSO3(phi),g2oSww_new.translation(),1.0);
mg2oLoopScw = g2oTwc.inverse()*g2oSww_new;
}
}
mvpLoopMapPoints = mvpLoopMPs;//*mvvpLoopMapPoints[nCurrentIndex];
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartLoop = std::chrono::steady_clock::now();
#endif
2021-09-03 14:24:01 +08:00
// 开启回环矫正
2020-12-01 11:58:17 +08:00
CorrectLoop();
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndLoop = std::chrono::steady_clock::now();
double timeLoop = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndLoop - time_StartLoop).count();
vTimeLoopTotal_ms.push_back(timeLoop);
#endif
2020-12-01 11:58:17 +08:00
}
2021-09-03 14:24:01 +08:00
// 如果pitch或roll角度偏差稍微有一点大,或 yaw大与20度则回环失败.
2020-12-01 11:58:17 +08:00
else
{
cout << "BAD LOOP!!!" << endl;
}
}
2021-09-03 14:24:01 +08:00
// 如果是纯视觉模式
2020-12-01 11:58:17 +08:00
else
{
mvpLoopMapPoints = mvpLoopMPs;
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartLoop = std::chrono::steady_clock::now();
#endif
2020-12-01 11:58:17 +08:00
CorrectLoop();
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndLoop = std::chrono::steady_clock::now();
double timeLoop = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndLoop - time_StartLoop).count();
vTimeLoopTotal_ms.push_back(timeLoop);
#endif
2020-12-01 11:58:17 +08:00
}
// Reset all variables
2021-09-03 14:24:01 +08:00
// 重置所有的回环变量
2020-12-01 11:58:17 +08:00
mpLoopLastCurrentKF->SetErase();
mpLoopMatchedKF->SetErase();
mnLoopNumCoincidences = 0;
mvpLoopMatchedMPs.clear();
mvpLoopMPs.clear();
mnLoopNumNotFound = 0;
mbLoopDetected = false;
}
}
mpLastCurrentKF = mpCurrentKF;
}
// 查看是否有外部线程请求复位当前线程
ResetIfRequested();
// 查看外部线程是否有终止当前线程的请求,如果有的话就跳出这个线程的主函数的主循环
if(CheckFinish()){
// cout << "LC: Finish requested" << endl;
break;
}
usleep(5000);
}
//ofstream f_stats;
//f_stats.open("PlaceRecognition_stats" + mpLocalMapper->strSequence + ".txt");
//f_stats << "# current_timestamp, matched_timestamp, [0:Loop, 1:Merge]" << endl;
//f_stats << fixed;
//for(int i=0; i< vdPR_CurrentTime.size(); ++i)
//{
// f_stats << 1e9*vdPR_CurrentTime[i] << "," << 1e9*vdPR_MatchedTime[i] << "," << vnPR_TypeRecogn[i] << endl;
//}
//f_stats.close();
SetFinish();
}
// 将某个关键帧加入到回环检测的过程中,由局部建图线程调用
void LoopClosing::InsertKeyFrame(KeyFrame *pKF)
{
unique_lock<mutex> lock(mMutexLoopQueue);
// 注意这里第0个关键帧不能够参与到回环检测的过程中,因为第0关键帧定义了整个地图的世界坐标系
if(pKF->mnId!=0)
mlpLoopKeyFrameQueue.push_back(pKF);
}
/*
*
* @return true
*/
bool LoopClosing::CheckNewKeyFrames()
{
unique_lock<mutex> lock(mMutexLoopQueue);
return(!mlpLoopKeyFrameQueue.empty());
}
2021-09-03 14:24:01 +08:00
/**
* @brief ,,sim3,
* ORB-SLAM2DetectLoop
* @return true
* @return false
*/
2020-12-01 11:58:17 +08:00
bool LoopClosing::NewDetectCommonRegions()
{
{
2021-09-03 14:24:01 +08:00
// Step 1 从队列中取出一个关键帧,作为当前检测共同区域的关键帧
2020-12-01 11:58:17 +08:00
unique_lock<mutex> lock(mMutexLoopQueue);
// 从队列头开始取,也就是先取早进来的关键帧
mpCurrentKF = mlpLoopKeyFrameQueue.front();
// 取出关键帧后从队列里弹出该关键帧
mlpLoopKeyFrameQueue.pop_front();
// Avoid that a keyframe can be erased while it is being process by this thread
// 设置当前关键帧不要在优化的过程中被删除
mpCurrentKF->SetNotErase();
mpCurrentKF->mbCurrentPlaceRecognition = true;
2021-09-03 14:24:01 +08:00
// 当前关键帧对应的地图
2020-12-01 11:58:17 +08:00
mpLastMap = mpCurrentKF->GetMap();
}
2021-09-03 14:24:01 +08:00
// Step 2 在某些情况下不进行共同区域检测
// 1.imu模式下还没经过第二阶段初始化则不考虑
2020-12-01 11:58:17 +08:00
if(mpLastMap->IsInertial() && !mpLastMap->GetIniertialBA1())
{
mpKeyFrameDB->add(mpCurrentKF);
mpCurrentKF->SetErase();
return false;
}
2021-09-03 14:24:01 +08:00
// 2.双目模式下且当前地图关键帧数少于5则不考虑
2020-12-01 11:58:17 +08:00
if(mpTracker->mSensor == System::STEREO && mpLastMap->GetAllKeyFrames().size() < 5) //12
{
mpKeyFrameDB->add(mpCurrentKF);
mpCurrentKF->SetErase();
return false;
}
2021-09-03 14:24:01 +08:00
// 3.当前地图关键帧少于12则不进行检测
2020-12-01 11:58:17 +08:00
if(mpLastMap->GetAllKeyFrames().size() < 12)
{
mpKeyFrameDB->add(mpCurrentKF);
mpCurrentKF->SetErase();
return false;
}
//Check the last candidates with geometric validation
2021-09-03 14:24:01 +08:00
// Step 3 基于前一帧的历史信息判断是否进行时序几何校验,注意这里是基于共视几何校验失败才会运行的代码,阅读代码的时候可以先看后面
2020-12-01 11:58:17 +08:00
// Loop candidates
bool bLoopDetectedInKF = false;
bool bCheckSpatial = false;
2021-09-03 14:24:01 +08:00
// Step 3.1 回环的时序几何校验: 这里的判断条件里mnLoopNumCoincidences刚开始为0, 所以可以先跳过看后面
// 如果回环的共视几何验证成功帧数目大于0
2020-12-01 11:58:17 +08:00
if(mnLoopNumCoincidences > 0)
{
bCheckSpatial = true;
// Find from the last KF candidates
2021-09-03 14:24:01 +08:00
// 通过上一关键帧的信息,计算新的当前帧的sim3
// Tcl = Tcw*Twl
2020-12-01 11:58:17 +08:00
cv::Mat mTcl = mpCurrentKF->GetPose() * mpLoopLastCurrentKF->GetPoseInverse();
g2o::Sim3 gScl(Converter::toMatrix3d(mTcl.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTcl.rowRange(0, 3).col(3)),1.0);
g2o::Sim3 gScw = gScl * mg2oLoopSlw;
int numProjMatches = 0;
vector<MapPoint*> vpMatchedMPs;
2021-09-03 14:24:01 +08:00
// 通过把候选帧局部窗口内的地图点向新进来的关键帧投影来验证回环检测结果,并优化Sim3位姿
2020-12-01 11:58:17 +08:00
bool bCommonRegion = DetectAndReffineSim3FromLastKF(mpCurrentKF, mpLoopMatchedKF, gScw, numProjMatches, mvpLoopMPs, vpMatchedMPs);
2021-09-03 14:24:01 +08:00
// 如果找到共同区域(时序验证成功一次)
2020-12-01 11:58:17 +08:00
if(bCommonRegion)
{
2021-09-03 14:24:01 +08:00
//标记时序检验成功一次
2020-12-01 11:58:17 +08:00
bLoopDetectedInKF = true;
2021-09-03 14:24:01 +08:00
// 累计正检验的成功次数
2020-12-01 11:58:17 +08:00
mnLoopNumCoincidences++;
2021-09-03 14:24:01 +08:00
// 不再参与新的回环检测
2020-12-01 11:58:17 +08:00
mpLoopLastCurrentKF->SetErase();
mpLoopLastCurrentKF = mpCurrentKF;
2021-09-03 14:24:01 +08:00
mg2oLoopSlw = gScw; // 记录当前优化的结果为{last T_cw}即为 T_lw
// 记录匹配到的点
2020-12-01 11:58:17 +08:00
mvpLoopMatchedMPs = vpMatchedMPs;
2021-09-03 14:24:01 +08:00
// 如果验证数大于等于3则为成功回环
2020-12-01 11:58:17 +08:00
mbLoopDetected = mnLoopNumCoincidences >= 3;
2021-09-03 14:24:01 +08:00
// 记录失败的时序校验数为0
2020-12-01 11:58:17 +08:00
mnLoopNumNotFound = 0;
2021-09-03 14:24:01 +08:00
//! 这里的条件反了,不过对功能没什么影响,只是打印信息
2020-12-01 11:58:17 +08:00
if(!mbLoopDetected)
{
//f_succes_pr << mpCurrentKF->mNameFile << " " << "8"<< endl;
//f_succes_pr << "% Number of spatial consensous: " << std::to_string(mnLoopNumCoincidences) << endl;
cout << "PR: Loop detected with Reffine Sim3" << endl;
}
}
2021-09-03 14:24:01 +08:00
// 如果没找到共同区域(时序验证失败一次)
2020-12-01 11:58:17 +08:00
else
{
2021-09-03 14:24:01 +08:00
// 当前时序验证失败
2020-12-01 11:58:17 +08:00
bLoopDetectedInKF = false;
/*f_succes_pr << mpCurrentKF->mNameFile << " " << "8"<< endl;
f_succes_pr << "% Number of spatial consensous: " << std::to_string(mnLoopNumCoincidences) << endl;*/
2021-09-03 14:24:01 +08:00
// 递增失败的时序验证次数
2020-12-01 11:58:17 +08:00
mnLoopNumNotFound++;
2021-09-03 14:24:01 +08:00
//若果连续两帧时序验证失败则整个回环检测失败
2020-12-01 11:58:17 +08:00
if(mnLoopNumNotFound >= 2)
{
/*for(int i=0; i<mvpLoopLastKF.size(); ++i)
{
mvpLoopLastKF[i]->SetErase();
mvpLoopCandidateKF[i]->SetErase();
mvpLoopLastKF[i]->mbCurrentPlaceRecognition = true;
}
mvpLoopCandidateKF.clear();
mvpLoopLastKF.clear();
mvg2oSim3LoopTcw.clear();
mvnLoopNumMatches.clear();
mvvpLoopMapPoints.clear();
mvvpLoopMatchedMapPoints.clear();*/
2021-09-03 14:24:01 +08:00
// 失败后标记重置一些信息
2020-12-01 11:58:17 +08:00
mpLoopLastCurrentKF->SetErase();
mpLoopMatchedKF->SetErase();
//mg2oLoopScw;
mnLoopNumCoincidences = 0;
mvpLoopMatchedMPs.clear();
mvpLoopMPs.clear();
mnLoopNumNotFound = 0;
}
}
}
//Merge candidates
bool bMergeDetectedInKF = false;
2021-09-03 14:24:01 +08:00
// Step 3.2 融合的时序几何校验: 这里的判断条件里mnMergeNumCoincidences刚开始为0, 所以可以先跳过看后面
// 如果融合的共视几何验证成功帧数目大于0
2020-12-01 11:58:17 +08:00
if(mnMergeNumCoincidences > 0)
{
// Find from the last KF candidates
2021-09-03 14:24:01 +08:00
// 通过上一关键帧的信息,计算新的当前帧的sim3
// Tcl = Tcw*Twl
2020-12-01 11:58:17 +08:00
cv::Mat mTcl = mpCurrentKF->GetPose() * mpMergeLastCurrentKF->GetPoseInverse();
g2o::Sim3 gScl(Converter::toMatrix3d(mTcl.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTcl.rowRange(0, 3).col(3)),1.0);
g2o::Sim3 gScw = gScl * mg2oMergeSlw;
int numProjMatches = 0;
vector<MapPoint*> vpMatchedMPs;
2021-09-03 14:24:01 +08:00
// 通过把候选帧局部窗口内的地图点向新进来的关键帧投影来验证回环检测结果,并优化Sim3位姿
2020-12-01 11:58:17 +08:00
bool bCommonRegion = DetectAndReffineSim3FromLastKF(mpCurrentKF, mpMergeMatchedKF, gScw, numProjMatches, mvpMergeMPs, vpMatchedMPs);
2021-09-03 14:24:01 +08:00
// 如果找到共同区域(时序验证成功一次)
2020-12-01 11:58:17 +08:00
if(bCommonRegion)
{
//cout << "BoW: Merge reffined Sim3 transformation suscelful" << endl;
2021-09-03 14:24:01 +08:00
//标记时序检验成功一次
2020-12-01 11:58:17 +08:00
bMergeDetectedInKF = true;
2021-09-03 14:24:01 +08:00
// 累计正检验的成功次数
2020-12-01 11:58:17 +08:00
mnMergeNumCoincidences++;
2021-09-03 14:24:01 +08:00
// 不再参与新的回环检测
2020-12-01 11:58:17 +08:00
mpMergeLastCurrentKF->SetErase();
mpMergeLastCurrentKF = mpCurrentKF;
mg2oMergeSlw = gScw;
mvpMergeMatchedMPs = vpMatchedMPs;
2021-09-03 14:24:01 +08:00
// 如果验证数大于等于3则为成功回环
2020-12-01 11:58:17 +08:00
mbMergeDetected = mnMergeNumCoincidences >= 3;
}
else
2021-09-03 14:24:01 +08:00
// 如果没找到共同区域(时序验证失败一次)
2020-12-01 11:58:17 +08:00
{
//cout << "BoW: Merge reffined Sim3 transformation failed" << endl;
2021-09-03 14:24:01 +08:00
// 没有找到融合
2020-12-01 11:58:17 +08:00
mbMergeDetected = false;
2021-09-03 14:24:01 +08:00
// 当前时序验证失败
2020-12-01 11:58:17 +08:00
bMergeDetectedInKF = false;
2021-09-03 14:24:01 +08:00
// 递增失败的时序验证次数
2020-12-01 11:58:17 +08:00
mnMergeNumNotFound++;
2021-09-03 14:24:01 +08:00
//若果连续两帧时序验证失败则整个融合检测失败
2020-12-01 11:58:17 +08:00
if(mnMergeNumNotFound >= 2)
{
/*cout << "+++++++Merge detected failed in KF" << endl;
for(int i=0; i<mvpMergeLastKF.size(); ++i)
{
mvpMergeLastKF[i]->SetErase();
mvpMergeCandidateKF[i]->SetErase();
mvpMergeLastKF[i]->mbCurrentPlaceRecognition = true;
}
mvpMergeCandidateKF.clear();
mvpMergeLastKF.clear();
mvg2oSim3MergeTcw.clear();
mvnMergeNumMatches.clear();
mvvpMergeMapPoints.clear();
mvvpMergeMatchedMapPoints.clear();*/
2021-09-03 14:24:01 +08:00
// 失败后标记重置一些信息
2020-12-01 11:58:17 +08:00
mpMergeLastCurrentKF->SetErase();
mpMergeMatchedKF->SetErase();
mnMergeNumCoincidences = 0;
mvpMergeMatchedMPs.clear();
mvpMergeMPs.clear();
mnMergeNumNotFound = 0;
}
}
}
2021-09-03 14:24:01 +08:00
// Step 3.3 若校验成功则把当前帧添加进数据库,且返回true表示找到共同区域
2020-12-01 11:58:17 +08:00
if(mbMergeDetected || mbLoopDetected)
{
//f_time_pr << "Geo" << " " << timeGeoKF_ms.count() << endl;
mpKeyFrameDB->add(mpCurrentKF);
return true;
}
//-------------
//TODO: This is only necessary if we use a minimun score for pick the best candidates
2021-09-03 14:24:01 +08:00
// 这两句并没有使用,作者把orbslam2里面通过minScore作为阀值筛选候选帧的策略抛弃了
2020-12-01 11:58:17 +08:00
const vector<KeyFrame*> vpConnectedKeyFrames = mpCurrentKF->GetVectorCovisibleKeyFrames();
const DBoW2::BowVector &CurrentBowVec = mpCurrentKF->mBowVec;
/*float minScore = 1;
for(size_t i=0; i<vpConnectedKeyFrames.size(); i++)
{
KeyFrame* pKF = vpConnectedKeyFrames[i];
if(pKF->isBad())
continue;
const DBoW2::BowVector &BowVec = pKF->mBowVec;
float score = mpORBVocabulary->score(CurrentBowVec, BowVec);
if(score<minScore)
minScore = score;
}*/
//-------------
// Extract candidates from the bag of words
2021-09-03 14:24:01 +08:00
// Step 4 若当前关键帧没有被检测到回环或融合,则分别通过bow拿到当前帧最好的三个回环候选帧和融合候选帧
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpMergeBowCand, vpLoopBowCand;
//cout << "LC: bMergeDetectedInKF: " << bMergeDetectedInKF << " bLoopDetectedInKF: " << bLoopDetectedInKF << endl;
if(!bMergeDetectedInKF || !bLoopDetectedInKF)
{
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartDetectBoW = std::chrono::steady_clock::now();
#endif
2020-12-01 11:58:17 +08:00
// Search in BoW
2021-09-03 14:24:01 +08:00
// 分别找到3个最好的候选帧, 回环候选帧放在vpLoopBowCand中,融合候选帧放在vpMergeBowCand中
2020-12-01 11:58:17 +08:00
mpKeyFrameDB->DetectNBestCandidates(mpCurrentKF, vpLoopBowCand, vpMergeBowCand,3);
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndDetectBoW = std::chrono::steady_clock::now();
timeDetectBoW = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndDetectBoW - time_StartDetectBoW).count();
#endif
2020-12-01 11:58:17 +08:00
}
// Check the BoW candidates if the geometric candidate list is empty
//Loop candidates
/*#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point timeStartGeoBoW = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point timeStartGeoBoW = std::chrono::monotonic_clock::now();
#endif*/
2021-09-03 14:24:01 +08:00
// Step 4.1 若当前关键帧没有被检测到回环,并且候选帧数量不为0,则对回环候选帧进行论文中第8页的2-5步
2020-12-01 11:58:17 +08:00
if(!bLoopDetectedInKF && !vpLoopBowCand.empty())
{
mbLoopDetected = DetectCommonRegionsFromBoW(vpLoopBowCand, mpLoopMatchedKF, mpLoopLastCurrentKF, mg2oLoopSlw, mnLoopNumCoincidences, mvpLoopMPs, mvpLoopMatchedMPs);
}
// Merge candidates
//cout << "LC: Find BoW candidates" << endl;
2021-09-03 14:24:01 +08:00
// Step 4.2 若当前关键帧没有被检测到融合,并且候选帧数量不为0,则对融合候帧进行论文中第8页的2-5步
2020-12-01 11:58:17 +08:00
if(!bMergeDetectedInKF && !vpMergeBowCand.empty())
{
mbMergeDetected = DetectCommonRegionsFromBoW(vpMergeBowCand, mpMergeMatchedKF, mpMergeLastCurrentKF, mg2oMergeSlw, mnMergeNumCoincidences, mvpMergeMPs, mvpMergeMatchedMPs);
}
//cout << "LC: add to KFDB" << endl;
2021-09-03 14:24:01 +08:00
// Step 5 根据结果确定有没有检测到共同区域
// 把当前帧添加到关键帧数据库中
2020-12-01 11:58:17 +08:00
mpKeyFrameDB->add(mpCurrentKF);
2021-09-03 14:24:01 +08:00
// 如果检测到共同区域返回true
2020-12-01 11:58:17 +08:00
if(mbMergeDetected || mbLoopDetected)
{
return true;
}
2021-09-03 14:24:01 +08:00
// 如果没检测到则把当前关键帧erase(不参与后续共同区域检测)
2020-12-01 11:58:17 +08:00
//cout << "LC: erase KF" << endl;
mpCurrentKF->SetErase();
2021-09-03 14:24:01 +08:00
// 标记当前关键帧不是当前在进行共同区域检测的帧
2020-12-01 11:58:17 +08:00
mpCurrentKF->mbCurrentPlaceRecognition = false;
return false;
}
2021-09-03 14:24:01 +08:00
/**
* @brief , Tcw
*
* @param[in] pCurrentKF
* @param[in] pMatchedKF
* @param[out] gScw Sim3
* @param[out] nNumProjMatches
* @param[out] vpMPs
* @param[out] vpMatchedMPs
* @return true
* @return false
*/
2020-12-01 11:58:17 +08:00
bool LoopClosing::DetectAndReffineSim3FromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches,
std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs)
{
2021-09-03 14:24:01 +08:00
// 还没有匹配点,所以为空
2020-12-01 11:58:17 +08:00
set<MapPoint*> spAlreadyMatchedMPs;
2021-09-03 14:24:01 +08:00
// 把候选帧局部窗口内的地图点投向新进来的当前关键帧,看是否有足够的匹配点
2020-12-01 11:58:17 +08:00
nNumProjMatches = FindMatchesByProjection(pCurrentKF, pMatchedKF, gScw, spAlreadyMatchedMPs, vpMPs, vpMatchedMPs);
int nProjMatches = 30;
int nProjOptMatches = 50;
int nProjMatchesRep = 100;
/*if(mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO)
{
nProjMatches = 50;
nProjOptMatches = 50;
nProjMatchesRep = 80;
}*/
2021-09-03 14:24:01 +08:00
// 如果大于一定的数量
2020-12-01 11:58:17 +08:00
if(nNumProjMatches >= nProjMatches)
{
2021-09-03 14:24:01 +08:00
// 为OptimizeSim3接口准备数据
2020-12-01 11:58:17 +08:00
cv::Mat mScw = Converter::toCvMat(gScw);
cv::Mat mTwm = pMatchedKF->GetPoseInverse();
g2o::Sim3 gSwm(Converter::toMatrix3d(mTwm.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTwm.rowRange(0, 3).col(3)),1.0);
g2o::Sim3 gScm = gScw * gSwm;
Eigen::Matrix<double, 7, 7> mHessian7x7;
2021-09-03 14:24:01 +08:00
// 单目情况下不锁定尺度
2020-12-01 11:58:17 +08:00
bool bFixedScale = mbFixScale; // TODO CHECK; Solo para el monocular inertial
2021-09-03 14:24:01 +08:00
// 如果是imu模式且地图没成熟,不锁定尺度
2020-12-01 11:58:17 +08:00
if(mpTracker->mSensor==System::IMU_MONOCULAR && !pCurrentKF->GetMap()->GetIniertialBA2())
bFixedScale=false;
2021-09-03 14:24:01 +08:00
// 继续优化 Sim3
2020-12-01 11:58:17 +08:00
int numOptMatches = Optimizer::OptimizeSim3(mpCurrentKF, pMatchedKF, vpMatchedMPs, gScm, 10, bFixedScale, mHessian7x7, true);
2021-09-03 14:24:01 +08:00
// 若果匹配的数量大于一定的数目
2020-12-01 11:58:17 +08:00
if(numOptMatches > nProjOptMatches)
{
g2o::Sim3 gScw_estimation(Converter::toMatrix3d(mScw.rowRange(0, 3).colRange(0, 3)),
Converter::toVector3d(mScw.rowRange(0, 3).col(3)),1.0);
vector<MapPoint*> vpMatchedMP;
vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
2021-09-03 14:24:01 +08:00
// 再次通过优化后的Sim3搜索匹配点
2020-12-01 11:58:17 +08:00
nNumProjMatches = FindMatchesByProjection(pCurrentKF, pMatchedKF, gScw_estimation, spAlreadyMatchedMPs, vpMPs, vpMatchedMPs);
//cout << "REFFINE-SIM3: Projection with optimize Sim3 from last KF with " << nNumProjMatches << " matches" << endl;
2021-09-03 14:24:01 +08:00
// 若果大于期望数目,接受这个结果
2020-12-01 11:58:17 +08:00
if(nNumProjMatches >= nProjMatchesRep)
{
gScw = gScw_estimation;
2021-09-03 14:24:01 +08:00
// 验证成功
2020-12-01 11:58:17 +08:00
return true;
}
}
}
2021-09-03 14:24:01 +08:00
// 验证失败
2020-12-01 11:58:17 +08:00
return false;
}
2021-09-03 14:24:01 +08:00
/**
* @brief 82-5()
* 1.
* 2. Ransac T_am
* 3. guided matching refinement
* 4. ()
*
* @param[in] vpBowCand bow
* @param[out] pMatchedKF2
* @param[out] pLastCurrentKF ()
* @param[out] g2oScw Sim3
* @param[out] nNumCoincidences validation
* @param[out] vpMPs
* @param[out] vpMatchedMPs
* @return true commen region
* @return false commen region
*/
2020-12-01 11:58:17 +08:00
bool LoopClosing::DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand, KeyFrame* &pMatchedKF2, KeyFrame* &pLastCurrentKF, g2o::Sim3 &g2oScw,
int &nNumCoincidences, std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs)
{
2021-09-03 14:24:01 +08:00
// 一些后面会使用的阀值
int nBoWMatches = 20; // 最低bow匹配特征点数
int nBoWInliers = 15; // RANSAC最低的匹配点数
int nSim3Inliers = 20; // sim3 最低内点数
int nProjMatches = 50; // 通过投影得到的匹配点数量最低阀值
int nProjOptMatches = 80; // 通过更小的半径,更严的距离搜索到的匹配点数量
2020-12-01 11:58:17 +08:00
/*if(mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO)
{
nBoWMatches = 20;
nBoWInliers = 15;
nSim3Inliers = 20;
nProjMatches = 35;
nProjOptMatches = 50;
}*/
2021-09-03 14:24:01 +08:00
//获取当前帧的共视帧(在共同区域检测中应该避免当前关键帧的共视关键帧中)
2020-12-01 11:58:17 +08:00
set<KeyFrame*> spConnectedKeyFrames = mpCurrentKF->GetConnectedKeyFrames();
2021-09-03 14:24:01 +08:00
// 定义最佳共视关键帧的数量
2020-12-01 11:58:17 +08:00
int nNumCovisibles = 5;
2021-09-03 14:24:01 +08:00
// 用于search by bow
2020-12-01 11:58:17 +08:00
ORBmatcher matcherBoW(0.9, true);
2021-09-03 14:24:01 +08:00
// 用与seach by projection
2020-12-01 11:58:17 +08:00
ORBmatcher matcher(0.75, true);
2021-09-03 14:24:01 +08:00
// 没有用到
2020-12-01 11:58:17 +08:00
int nNumGuidedMatching = 0;
// Varibles to select the best numbe
2021-09-03 14:24:01 +08:00
// 一些用与统计最优数据的变量,我们最后返回的是最佳的一个关键帧(几何校验匹配数最高的)
2020-12-01 11:58:17 +08:00
KeyFrame* pBestMatchedKF;
int nBestMatchesReproj = 0;
int nBestNumCoindicendes = 0;
g2o::Sim3 g2oBestScw;
std::vector<MapPoint*> vpBestMapPoints;
std::vector<MapPoint*> vpBestMatchedMapPoints;
2021-09-03 14:24:01 +08:00
// bow中候选关键帧的数量
2020-12-01 11:58:17 +08:00
int numCandidates = vpBowCand.size();
2021-09-03 14:24:01 +08:00
// 这三个变量是作者为了后面打印观察记录的信息,可以忽略
2020-12-01 11:58:17 +08:00
vector<int> vnStage(numCandidates, 0);
vector<int> vnMatchesStage(numCandidates, 0);
int index = 0;
2021-09-03 14:24:01 +08:00
//对于每个候选关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : vpBowCand)
{
//cout << endl << "-------------------------------" << endl;
if(!pKFi || pKFi->isBad())
continue;
// Current KF against KF with covisibles version
2021-09-03 14:24:01 +08:00
// Step 1 获得候选关键帧的局部窗口 W_m
// 拿到候选关键帧的5个最优共视帧
2020-12-01 11:58:17 +08:00
std::vector<KeyFrame*> vpCovKFi = pKFi->GetBestCovisibilityKeyFrames(nNumCovisibles);
2021-09-03 14:24:01 +08:00
// 再加上候选关键帧自己(这里操作比较迷,看起来只是为了把候选关键帧放到容器的第一顺位)
2020-12-01 11:58:17 +08:00
vpCovKFi.push_back(vpCovKFi[0]);
vpCovKFi[0] = pKFi;
2021-09-03 14:24:01 +08:00
// search by bow 返回的参数, 记录窗口Wm中每个关键帧有哪些点能在当前关键帧Ka中通过bow找到匹配点
2020-12-01 11:58:17 +08:00
std::vector<std::vector<MapPoint*> > vvpMatchedMPs;
vvpMatchedMPs.resize(vpCovKFi.size());
2021-09-03 14:24:01 +08:00
// 记录整个窗口中有那些点能在Ka中通过bow找到匹配点(这个set是辅助容器,避免重复添加地图点)
2020-12-01 11:58:17 +08:00
std::set<MapPoint*> spMatchedMPi;
int numBoWMatches = 0;
2021-09-03 14:24:01 +08:00
// 记录窗口中能通过bow在当前关键帧ka中找到最多匹配点的关键帧
2020-12-01 11:58:17 +08:00
KeyFrame* pMostBoWMatchesKF = pKFi;
2021-09-03 14:24:01 +08:00
// 记录窗口中能通过bow在当前关键帧ka中找到最多匹配点的数量
2020-12-01 11:58:17 +08:00
int nMostBoWNumMatches = 0;
2021-09-03 14:24:01 +08:00
// 下面两个变量是为了sim3 solver准备的
//记录窗口中的地图点能在当前关键帧中找到的匹配的点(数量的上限是当前关键帧地图点的数量)
2020-12-01 11:58:17 +08:00
std::vector<MapPoint*> vpMatchedPoints = std::vector<MapPoint*>(mpCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
2021-09-03 14:24:01 +08:00
// 记录上面的地图点分别对应窗口中的关键帧(数量的上限是当前关键帧地图点的数量)
2020-12-01 11:58:17 +08:00
std::vector<KeyFrame*> vpKeyFrameMatchedMP = std::vector<KeyFrame*>(mpCurrentKF->GetMapPointMatches().size(), static_cast<KeyFrame*>(NULL));
2021-09-03 14:24:01 +08:00
// 记录在W_km中有最多匹配点的帧的局部index, 这个后面没有用到
2020-12-01 11:58:17 +08:00
int nIndexMostBoWMatchesKF=0;
2021-09-03 14:24:01 +08:00
//! bug: 并没有重新赋值pMostBoWMatchesKF, 一直是初始值: 候选关键帧
// 遍历窗口内Wm的每个关键帧
// Step 1.1 通过Bow寻找候选帧窗口内的关键帧地图点与当前关键帧的匹配点
2020-12-01 11:58:17 +08:00
for(int j=0; j<vpCovKFi.size(); ++j)
{
if(!vpCovKFi[j] || vpCovKFi[j]->isBad())
continue;
int num = matcherBoW.SearchByBoW(mpCurrentKF, vpCovKFi[j], vvpMatchedMPs[j]);
//cout << "BoW: " << num << " putative matches with KF " << vpCovKFi[j]->mnId << endl;
if (num > nMostBoWNumMatches)
{
nMostBoWNumMatches = num;
nIndexMostBoWMatchesKF = j;
}
}
2021-09-03 14:24:01 +08:00
// 标记是否因为窗口内有当前关键帧的共视关键帧
2020-12-01 11:58:17 +08:00
bool bAbortByNearKF = false;
2021-09-03 14:24:01 +08:00
// 遍历窗口内的每个关键帧
// Step 1.2 把窗口内的匹配点转换为Sim3Solver接口定义的格式
2020-12-01 11:58:17 +08:00
for(int j=0; j<vpCovKFi.size(); ++j)
2021-09-03 14:24:01 +08:00
{
// 如果窗口中的帧是当前帧的共视帧帧则结束这个循环
2020-12-01 11:58:17 +08:00
if(spConnectedKeyFrames.find(vpCovKFi[j]) != spConnectedKeyFrames.end())
{
bAbortByNearKF = true;
//cout << "BoW: Candidate KF aborted by proximity" << endl;
break;
}
//cout << "Matches: " << num << endl;
2021-09-03 14:24:01 +08:00
// 遍历窗口内的某一个关键帧与当前关键帧由bow得到的匹配的地图点
// 注意这里每个vvpMatchedMPs[j]的大小都是相等的且等于当前关键帧中的总地图点数量,详细请看searchByBow
2020-12-01 11:58:17 +08:00
for(int k=0; k < vvpMatchedMPs[j].size(); ++k)
{
2021-09-03 14:24:01 +08:00
// 地图点指针
2020-12-01 11:58:17 +08:00
MapPoint* pMPi_j = vvpMatchedMPs[j][k];
2021-09-03 14:24:01 +08:00
// 如果指针为空活地图点被标记为bad,则跳过当前循环
2020-12-01 11:58:17 +08:00
if(!pMPi_j || pMPi_j->isBad())
continue;
2021-09-03 14:24:01 +08:00
// 窗口内不同关键帧与当前关键帧可能能看到相同的3D点, 利用辅助容器避免重复添加
2020-12-01 11:58:17 +08:00
if(spMatchedMPi.find(pMPi_j) == spMatchedMPi.end())
{
2021-09-03 14:24:01 +08:00
// 利用辅助容器记录添加过的点
2020-12-01 11:58:17 +08:00
spMatchedMPi.insert(pMPi_j);
2021-09-03 14:24:01 +08:00
// 统计窗口内有多少地图点能在当前关键中找到匹配
2020-12-01 11:58:17 +08:00
numBoWMatches++;
2021-09-03 14:24:01 +08:00
//记录窗口中的地图点能在当前关键帧中找到的匹配的点
2020-12-01 11:58:17 +08:00
vpMatchedPoints[k]= pMPi_j;
2021-09-03 14:24:01 +08:00
// 记录上面的地图点分别对应窗口中的关键帧(数量的上限是当前关键帧地图点的数量)
2020-12-01 11:58:17 +08:00
vpKeyFrameMatchedMP[k] = vpCovKFi[j];
}
}
}
//cout <<"BoW: " << numBoWMatches << " independent putative matches" << endl;
2021-09-03 14:24:01 +08:00
// 当窗口内的帧不是当前关键帧的相邻帧且匹配点足够多时
// Step 2 利用RANSAC寻找候选关键帧窗口与当前关键帧的相对位姿T_am的初始值(可能是Sim3)
2020-12-01 11:58:17 +08:00
if(!bAbortByNearKF && numBoWMatches >= nBoWMatches) // TODO pick a good threshold
{
/*cout << "-------------------------------" << endl;
cout << "Geometric validation with " << numBoWMatches << endl;
cout << "KFc: " << mpCurrentKF->mnId << "; KFm: " << pMostBoWMatchesKF->mnId << endl;*/
// Geometric validation
bool bFixedScale = mbFixScale;
2021-09-03 14:24:01 +08:00
//? 如果是单目带imu的模式且地图没有成熟则不固定scale
2020-12-01 11:58:17 +08:00
if(mpTracker->mSensor==System::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2())
bFixedScale=false;
2021-09-03 14:24:01 +08:00
// 初始化sim3 solver
// Sim3Solver 的接口与orbslam2略有不同, 因为现在是1-N的对应关系
2020-12-01 11:58:17 +08:00
Sim3Solver solver = Sim3Solver(mpCurrentKF, pMostBoWMatchesKF, vpMatchedPoints, bFixedScale, vpKeyFrameMatchedMP);
2021-09-03 14:24:01 +08:00
//Sim3Solver Ransac 置信度0.99至少20个inliers 最多300次迭
2020-12-01 11:58:17 +08:00
solver.SetRansacParameters(0.99, nBoWInliers, 300); // at least 15 inliers
bool bNoMore = false;
vector<bool> vbInliers;
int nInliers;
bool bConverge = false;
cv::Mat mTcm;
2021-09-03 14:24:01 +08:00
// 迭代到收敛
2020-12-01 11:58:17 +08:00
while(!bConverge && !bNoMore)
{
mTcm = solver.iterate(20,bNoMore, vbInliers, nInliers, bConverge);
}
//cout << "Num inliers: " << nInliers << endl;
2021-09-03 14:24:01 +08:00
// Step 3 Guide matching refinement: 利用初始的Tam信息,进行双向重投影,并非线性优化得到更精确的Tam
2020-12-01 11:58:17 +08:00
if(bConverge)
{
//cout <<"BoW: " << nInliers << " inliers in Sim3Solver" << endl;
// Match by reprojection
//int nNumCovisibles = 5;
vpCovKFi.clear();
2021-09-03 14:24:01 +08:00
// 拿到窗口内匹配最多的帧的最佳5个共视帧和它自己组成的窗口
2020-12-01 11:58:17 +08:00
vpCovKFi = pMostBoWMatchesKF->GetBestCovisibilityKeyFrames(nNumCovisibles);
int nInitialCov = vpCovKFi.size();
vpCovKFi.push_back(pMostBoWMatchesKF);
2021-09-03 14:24:01 +08:00
// 这个后面没有用到
2020-12-01 11:58:17 +08:00
set<KeyFrame*> spCheckKFs(vpCovKFi.begin(), vpCovKFi.end());
2021-09-03 14:24:01 +08:00
// 辅助容器,避免重复添加地图点
2020-12-01 11:58:17 +08:00
set<MapPoint*> spMapPoints;
2021-09-03 14:24:01 +08:00
// 这两个容器是searchByProjection定义的容器
// 记录窗口内地图点
2020-12-01 11:58:17 +08:00
vector<MapPoint*> vpMapPoints;
2021-09-03 14:24:01 +08:00
// 记录每个地图点对应的串口内的关键帧
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpKeyFrames;
2021-09-03 14:24:01 +08:00
// 遍历窗Wm内的所有关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pCovKFi : vpCovKFi)
{
2021-09-03 14:24:01 +08:00
// 遍历窗口内每个关键帧的所有地图点
2020-12-01 11:58:17 +08:00
for(MapPoint* pCovMPij : pCovKFi->GetMapPointMatches())
{
2021-09-03 14:24:01 +08:00
// 如果指针为空或者改地图点被标记为bad
2020-12-01 11:58:17 +08:00
if(!pCovMPij || pCovMPij->isBad())
continue;
2021-09-03 14:24:01 +08:00
// 避免重复添加
2020-12-01 11:58:17 +08:00
if(spMapPoints.find(pCovMPij) == spMapPoints.end())
2021-09-03 14:24:01 +08:00
{
// 辅助容器用来记录点是否已经添加
2020-12-01 11:58:17 +08:00
spMapPoints.insert(pCovMPij);
2021-09-03 14:24:01 +08:00
// 把地图点和对应关键帧记录下来
2020-12-01 11:58:17 +08:00
vpMapPoints.push_back(pCovMPij);
vpKeyFrames.push_back(pCovKFi);
}
}
}
//cout << "Point cloud: " << vpMapPoints.size() << endl;
2021-09-03 14:24:01 +08:00
// 拿到solver 估计的 Tam初始值, 为后续的非线性优化做准备, 在这里 c 表示当前关键帧, m 表示回环/融合候选帧
2020-12-01 11:58:17 +08:00
g2o::Sim3 gScm(Converter::toMatrix3d(solver.GetEstimatedRotation()),Converter::toVector3d(solver.GetEstimatedTranslation()),solver.GetEstimatedScale());
g2o::Sim3 gSmw(Converter::toMatrix3d(pMostBoWMatchesKF->GetRotation()),Converter::toVector3d(pMostBoWMatchesKF->GetTranslation()),1.0);
2021-09-03 14:24:01 +08:00
// 利用初始的Tam估计确定世界坐标系在当前相机中的位姿
2020-12-01 11:58:17 +08:00
g2o::Sim3 gScw = gScm*gSmw; // Similarity matrix of current from the world position
2021-09-03 14:24:01 +08:00
// 准备用来SearchByProjection的位姿信息
2020-12-01 11:58:17 +08:00
cv::Mat mScw = Converter::toCvMat(gScw);
2021-09-03 14:24:01 +08:00
// 记录最后searchByProjection的结果
2020-12-01 11:58:17 +08:00
vector<MapPoint*> vpMatchedMP;
vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
vector<KeyFrame*> vpMatchedKF;
vpMatchedKF.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast<KeyFrame*>(NULL));
2021-09-03 14:24:01 +08:00
// Step 3.1 重新利用之前计算的mScw信息, 通过投影寻找更多的匹配点
2020-12-01 11:58:17 +08:00
int numProjMatches = matcher.SearchByProjection(mpCurrentKF, mScw, vpMapPoints, vpKeyFrames, vpMatchedMP, vpMatchedKF, 8, 1.5);
2021-09-03 14:24:01 +08:00
// 如果拿到了足够多的匹配点
2020-12-01 11:58:17 +08:00
if(numProjMatches >= nProjMatches)
{
// Optimize Sim3 transformation with every matches
Eigen::Matrix<double, 7, 7> mHessian7x7;
bool bFixedScale = mbFixScale;
2021-09-03 14:24:01 +08:00
// 在imu模式下没有成熟的地图就不固定scale
2020-12-01 11:58:17 +08:00
if(mpTracker->mSensor==System::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2())
bFixedScale=false;
2021-09-03 14:24:01 +08:00
// Step 3.2 利用搜索到的更多的匹配点优化双向投影误差得到的更好的 gScm (Tam)
2020-12-01 11:58:17 +08:00
int numOptMatches = Optimizer::OptimizeSim3(mpCurrentKF, pKFi, vpMatchedMP, gScm, 10, mbFixScale, mHessian7x7, true);
//cout <<"BoW: " << numOptMatches << " inliers in the Sim3 optimization" << endl;
//cout << "Inliers in Sim3 optimization: " << numOptMatches << endl;
2021-09-03 14:24:01 +08:00
// Step 3.3 如果内点足够多,用更小的半径搜索匹配点,并且再次进行优化(p.s.这里与论文不符,并没有再次优化)
2020-12-01 11:58:17 +08:00
if(numOptMatches >= nSim3Inliers)
{
//cout <<"BoW: " << numOptMatches << " inliers in Sim3 optimization" << endl;
2021-09-03 14:24:01 +08:00
// 前面已经声明了这些变量了,无需再次声明
2020-12-01 11:58:17 +08:00
g2o::Sim3 gSmw(Converter::toMatrix3d(pMostBoWMatchesKF->GetRotation()),Converter::toVector3d(pMostBoWMatchesKF->GetTranslation()),1.0);
g2o::Sim3 gScw = gScm*gSmw; // Similarity matrix of current from the world position
cv::Mat mScw = Converter::toCvMat(gScw);
vector<MapPoint*> vpMatchedMP;
vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
2021-09-03 14:24:01 +08:00
// Step 3.4 重新利用之前计算的mScw信息, 通过更小的半径和更严格的距离的投影寻找匹配点
// 5 : 半径的增益系数(对比之前下降了)---> 更小的半径, 1.0 , hamming distance 的阀值增益系数---> 允许更小的距离
2020-12-01 11:58:17 +08:00
int numProjOptMatches = matcher.SearchByProjection(mpCurrentKF, mScw, vpMapPoints, vpMatchedMP, 5, 1.0);
//cout <<"BoW: " << numProjOptMatches << " matches after of the Sim3 optimization" << endl;
2021-09-03 14:24:01 +08:00
// ? 论文中说好的再优化一次呢?只做了搜索并没有再次进行OptimizeSim3
// 当新的投影得到的内点数量大于nProjOptMatches时
2020-12-01 11:58:17 +08:00
if(numProjOptMatches >= nProjOptMatches)
{
2021-09-03 14:24:01 +08:00
// Step 4. 用当前关键帧的相邻关键来验证前面得到的Tam(共视几何校验)
// 统计验证成功的关键帧数量
2020-12-01 11:58:17 +08:00
int nNumKFs = 0;
//vpMatchedMPs = vpMatchedMP;
//vpMPs = vpMapPoints;
// Check the Sim3 transformation with the current KeyFrame covisibles
2021-09-03 14:24:01 +08:00
// Step 4.1 拿到用来验证的关键帧组(后称为验证组): 当前关键帧的共视关键帧
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpCurrentCovKFs = mpCurrentKF->GetBestCovisibilityKeyFrames(nNumCovisibles);
//cout << "---" << endl;
//cout << "BoW: Geometrical validation" << endl;
int j = 0;
2021-09-03 14:24:01 +08:00
// 遍历验证组当有三个关键帧验证成功或遍历所有的关键帧后结束循环
2020-12-01 11:58:17 +08:00
while(nNumKFs < 3 && j<vpCurrentCovKFs.size())
//for(int j=0; j<vpCurrentCovKFs.size(); ++j)
2021-09-03 14:24:01 +08:00
{
// 拿出验证组中的一个关键帧
2020-12-01 11:58:17 +08:00
KeyFrame* pKFj = vpCurrentCovKFs[j];
2021-09-03 14:24:01 +08:00
// 为 DetectCommonRegionsFromLastKF准备一个初始位姿, 这个用来进行searchByProjection
2020-12-01 11:58:17 +08:00
cv::Mat mTjc = pKFj->GetPose() * mpCurrentKF->GetPoseInverse();
g2o::Sim3 gSjc(Converter::toMatrix3d(mTjc.rowRange(0, 3).colRange(0, 3)),Converter::toVector3d(mTjc.rowRange(0, 3).col(3)),1.0);
g2o::Sim3 gSjw = gSjc * gScw;
int numProjMatches_j = 0;
vector<MapPoint*> vpMatchedMPs_j;
2021-09-03 14:24:01 +08:00
// Step 4.2 几何校验函数, 这个函数里面其实是个searchByProjection : 通过之前计算的位姿转换地图点并通过投影搜索匹配点, 若大于一定数目的任务成功验证一次
2020-12-01 11:58:17 +08:00
bool bValid = DetectCommonRegionsFromLastKF(pKFj,pMostBoWMatchesKF, gSjw,numProjMatches_j, vpMapPoints, vpMatchedMPs_j);
if(bValid)
{
2021-09-03 14:24:01 +08:00
// 统计valid的帧的数量
2020-12-01 11:58:17 +08:00
nNumKFs++;
}
j++;
}
2021-09-03 14:24:01 +08:00
// 这里又是没有用的代码,只是记录一点信息,可能是为了方便打印检查
2020-12-01 11:58:17 +08:00
if(nNumKFs < 3)
{
vnStage[index] = 8;
vnMatchesStage[index] = nNumKFs;
}
2021-09-03 14:24:01 +08:00
// 记录第二次searchByProjection得到最多匹配点的关键帧的各种信息,最后作为回环帧/融合帧
2020-12-01 11:58:17 +08:00
if(nBestMatchesReproj < numProjOptMatches)
{
2021-09-03 14:24:01 +08:00
nBestMatchesReproj = numProjOptMatches; // 投影匹配的数量
nBestNumCoindicendes = nNumKFs; // 成功验证的帧数
pBestMatchedKF = pMostBoWMatchesKF; // 记录候选帧窗口内与当前关键帧相似度最高的帧
g2oBestScw = gScw; // 记录最优的位姿(这个位姿是由Tam推到出来的 : Taw = Tam * Tmw,这里a表示c)
vpBestMapPoints = vpMapPoints; // 记录所有的地图点
vpBestMatchedMapPoints = vpMatchedMP; // 记录所有的地图点中被成功匹配的点
2020-12-01 11:58:17 +08:00
}
}
}
}
}
}
index++;
}
2021-09-03 14:24:01 +08:00
// 如果成功找到了共同区域帧把记录的最优值存到输出变量中
2020-12-01 11:58:17 +08:00
if(nBestMatchesReproj > 0)
{
pLastCurrentKF = mpCurrentKF;
nNumCoincidences = nBestNumCoindicendes;
pMatchedKF2 = pBestMatchedKF;
pMatchedKF2->SetNotErase();
g2oScw = g2oBestScw;
vpMPs = vpBestMapPoints;
vpMatchedMPs = vpBestMatchedMapPoints;
2021-09-03 14:24:01 +08:00
//如果有三个成功验证则return ture
2020-12-01 11:58:17 +08:00
return nNumCoincidences >= 3;
}
else
{
2021-09-03 14:24:01 +08:00
// 这里是一些无用的变量, 左值只用来打印检查
2020-12-01 11:58:17 +08:00
int maxStage = -1;
int maxMatched;
for(int i=0; i<vnStage.size(); ++i)
{
if(vnStage[i] > maxStage)
{
maxStage = vnStage[i];
maxMatched = vnMatchesStage[i];
}
}
// f_succes_pr << mpCurrentKF->mNameFile << " " << std::to_string(maxStage) << endl;
// f_succes_pr << "% NumCand: " << std::to_string(numCandidates) << "; matches: " << std::to_string(maxMatched) << endl;
}
2021-09-03 14:24:01 +08:00
// 如果少于3个当前关键帧的共视关键帧验证了这个候选帧,那么返回失败,注意,这里的失败并不代表最终的验证失败,后续会开启时序校验
2020-12-01 11:58:17 +08:00
return false;
}
2021-09-03 14:24:01 +08:00
/**
* @brief , , ,DetectCommonRegionsFromCoVKF
*
* @param[in] pCurrentKF
* @param[in] pMatchedKF
* @param[in] gScw Sim3
* @param[out] nNumProjMatches
* @param[out] vpMPs
* @param[out] vpMatchedMPs
* @return true
* @return false
*/
2020-12-01 11:58:17 +08:00
bool LoopClosing::DetectCommonRegionsFromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches,
std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs)
2021-09-03 14:24:01 +08:00
{
// 所有的匹配点
2020-12-01 11:58:17 +08:00
set<MapPoint*> spAlreadyMatchedMPs(vpMatchedMPs.begin(), vpMatchedMPs.end());
2021-09-03 14:24:01 +08:00
// 通过Sim3变换后投影寻找匹配点
2020-12-01 11:58:17 +08:00
nNumProjMatches = FindMatchesByProjection(pCurrentKF, pMatchedKF, gScw, spAlreadyMatchedMPs, vpMPs, vpMatchedMPs);
//cout << "Projection from last KF with " << nNumProjMatches << " matches" << endl;
int nProjMatches = 30;
2021-09-03 14:24:01 +08:00
// 如果匹配点数目大于一定的阀值,则认为验证成功,返回ture
2020-12-01 11:58:17 +08:00
if(nNumProjMatches >= nProjMatches)
{
/*cout << "PR_From_LastKF: KF " << pCurrentKF->mnId << " has " << nNumProjMatches << " with KF " << pMatchedKF->mnId << endl;
int max_x = -1, min_x = 1000000;
int max_y = -1, min_y = 1000000;
for(MapPoint* pMPi : vpMatchedMPs)
{
if(!pMPi || pMPi->isBad())
{
continue;
}
tuple<size_t,size_t> indexes = pMPi->GetIndexInKeyFrame(pMatchedKF);
int index = get<0>(indexes);
if(index >= 0)
{
int coord_x = pCurrentKF->mvKeysUn[index].pt.x;
if(coord_x < min_x)
{
min_x = coord_x;
}
if(coord_x > max_x)
{
max_x = coord_x;
}
int coord_y = pCurrentKF->mvKeysUn[index].pt.y;
if(coord_y < min_y)
{
min_y = coord_y;
}
if(coord_y > max_y)
{
max_y = coord_y;
}
}
}*/
//cout << "PR_From_LastKF: Coord in X -> " << min_x << ", " << max_x << "; and Y -> " << min_y << ", " << max_y << endl;
//cout << "PR_From_LastKF: features area in X -> " << (max_x - min_x) << " and Y -> " << (max_y - min_y) << endl;
return true;
}
return false;
}
2021-09-03 14:24:01 +08:00
/**
* @brief searchByProjection, ,
*
* @param[in] pCurrentKF
* @param[in] pMatchedKFw
* @param[in] g2oScw 姿
* @param[in] spMatchedMPinOrigin ?
* @param[in] vpMapPoints
* @param[in] vpMatchedMapPoints
* @return int
*/
2020-12-01 11:58:17 +08:00
int LoopClosing::FindMatchesByProjection(KeyFrame* pCurrentKF, KeyFrame* pMatchedKFw, g2o::Sim3 &g2oScw,
set<MapPoint*> &spMatchedMPinOrigin, vector<MapPoint*> &vpMapPoints,
vector<MapPoint*> &vpMatchedMapPoints)
{
int nNumCovisibles = 5;
2021-09-03 14:24:01 +08:00
//拿出候选帧的五个最好的共视关键帧
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpCovKFm = pMatchedKFw->GetBestCovisibilityKeyFrames(nNumCovisibles);
int nInitialCov = vpCovKFm.size();
2021-09-03 14:24:01 +08:00
// 把自己也加进去, 组成一个局部窗口
2020-12-01 11:58:17 +08:00
vpCovKFm.push_back(pMatchedKFw);
2021-09-03 14:24:01 +08:00
// 辅助容器,防止重复添加
2020-12-01 11:58:17 +08:00
set<KeyFrame*> spCheckKFs(vpCovKFm.begin(), vpCovKFm.end());
2021-09-03 14:24:01 +08:00
// 拿出当前关键帧的共视关键帧
2020-12-01 11:58:17 +08:00
set<KeyFrame*> spCurrentCovisbles = pCurrentKF->GetConnectedKeyFrames();
2021-09-03 14:24:01 +08:00
// 扩充窗口
// 对于之前里的每个关键帧
2020-12-01 11:58:17 +08:00
for(int i=0; i<nInitialCov; ++i)
{
2021-09-03 14:24:01 +08:00
// 拿到共视关键帧
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpKFs = vpCovKFm[i]->GetBestCovisibilityKeyFrames(nNumCovisibles);
int nInserted = 0;
int j = 0;
2021-09-03 14:24:01 +08:00
// 这个while循环统计的遍历后面都没有用到, 没有任何作用
2020-12-01 11:58:17 +08:00
while(j < vpKFs.size() && nInserted < nNumCovisibles)
{
2021-09-03 14:24:01 +08:00
// 如果没有被重复添加且不是当前关键帧的共视关键帧
2020-12-01 11:58:17 +08:00
if(spCheckKFs.find(vpKFs[j]) == spCheckKFs.end() && spCurrentCovisbles.find(vpKFs[j]) == spCurrentCovisbles.end())
{
spCheckKFs.insert(vpKFs[j]);
++nInserted;
}
++j;
}
2021-09-03 14:24:01 +08:00
// 把每个帧的共视关键帧都加到窗口内
2020-12-01 11:58:17 +08:00
vpCovKFm.insert(vpCovKFm.end(), vpKFs.begin(), vpKFs.end());
}
2021-09-03 14:24:01 +08:00
// 辅助容器, 防止地图点被重复添加
2020-12-01 11:58:17 +08:00
set<MapPoint*> spMapPoints;
2021-09-03 14:24:01 +08:00
// 清空这两个容器,重新进行searchByProjection
2020-12-01 11:58:17 +08:00
vpMapPoints.clear();
vpMatchedMapPoints.clear();
2021-09-03 14:24:01 +08:00
// 对于窗口内每个关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : vpCovKFm)
{
2021-09-03 14:24:01 +08:00
// 对于每个关键帧的地图点
2020-12-01 11:58:17 +08:00
for(MapPoint* pMPij : pKFi->GetMapPointMatches())
{
2021-09-03 14:24:01 +08:00
// 如果指针不是空,且点不是bad
2020-12-01 11:58:17 +08:00
if(!pMPij || pMPij->isBad())
continue;
2021-09-03 14:24:01 +08:00
// 如果没有被重复添加
2020-12-01 11:58:17 +08:00
if(spMapPoints.find(pMPij) == spMapPoints.end())
{
spMapPoints.insert(pMPij);
vpMapPoints.push_back(pMPij);
}
}
}
//cout << "Point cloud: " << vpMapPoints.size() << endl;
cv::Mat mScw = Converter::toCvMat(g2oScw);
ORBmatcher matcher(0.9, true);
2021-09-03 14:24:01 +08:00
// 初始化被匹配到的地图点容器, 匹配上限是当前帧的地图点数量
2020-12-01 11:58:17 +08:00
vpMatchedMapPoints.resize(pCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
2021-09-03 14:24:01 +08:00
// 把窗口中的点向当前关键帧投影, 搜索匹配点, 注意验证的时候用的搜索半径是最小的
2020-12-01 11:58:17 +08:00
int num_matches = matcher.SearchByProjection(pCurrentKF, mScw, vpMapPoints, vpMatchedMapPoints, 3, 1.5);
return num_matches;
}
void LoopClosing::CorrectLoop()
{
cout << "Loop detected!" << endl;
// Send a stop signal to Local Mapping
// Avoid new keyframes are inserted while correcting the loop
// Step 0结束局部地图线程、全局BA为闭环矫正做准备
// 请求局部地图停止防止在回环矫正时局部地图线程中InsertKeyFrame函数插入新的关键帧
mpLocalMapper->RequestStop();
mpLocalMapper->EmptyQueue(); // Proccess keyframes in the queue
// If a Global Bundle Adjustment is running, abort it
cout << "Request GBA abort" << endl;
if(isRunningGBA())
{
// 如果有全局BA在运行终止掉迎接新的全局BA
unique_lock<mutex> lock(mMutexGBA);
mbStopGBA = true;
// 记录全局BA次数
mnFullBAIdx++;
if(mpThreadGBA)
{
cout << "GBA running... Abort!" << endl;
mpThreadGBA->detach();
delete mpThreadGBA;
}
}
// Wait until Local Mapping has effectively stopped
// 一直等到局部地图线程结束再继续
while(!mpLocalMapper->isStopped())
{
usleep(1000);
}
// Ensure current keyframe is updated
// Step 1根据共视关系更新当前关键帧与其它关键帧之间的连接关系
// 因为之前闭环检测、计算Sim3中改变了该关键帧的地图点所以需要更新
cout << "start updating connections" << endl;
mpCurrentKF->UpdateConnections();
// Retrive keyframes connected to the current keyframe and compute corrected Sim3 pose by propagation
// Step 2通过位姿传播得到Sim3优化后与当前帧相连的关键帧的位姿以及它们的地图点
// 当前帧与世界坐标系之间的Sim变换在ComputeSim3函数中已经确定并优化
// 通过相对位姿关系可以确定这些相连的关键帧与世界坐标系之间的Sim3变换
// 取出当前关键帧及其共视关键帧,称为“当前关键帧组”
mvpCurrentConnectedKFs = mpCurrentKF->GetVectorCovisibleKeyFrames();
mvpCurrentConnectedKFs.push_back(mpCurrentKF);
// CorrectedSim3存放闭环g2o优化后当前关键帧的共视关键帧的世界坐标系下Sim3 变换
// NonCorrectedSim3存放没有矫正的当前关键帧的共视关键帧的世界坐标系下Sim3 变换
KeyFrameAndPose CorrectedSim3, NonCorrectedSim3;
// 先将mpCurrentKF的Sim3变换存入认为是准的所以固定不动
CorrectedSim3[mpCurrentKF]=mg2oLoopScw;
// 当前关键帧到世界坐标系下的变换矩阵
cv::Mat Twc = mpCurrentKF->GetPoseInverse();
Map* pLoopMap = mpCurrentKF->GetMap();
// 对地图点操作
{
// Get Map Mutex
// 锁定地图点
unique_lock<mutex> lock(pLoopMap->mMutexMapUpdate);
const bool bImuInit = pLoopMap->isImuInitialized();
// Step 2.1通过mg2oLoopScw认为是准的来进行位姿传播得到当前关键帧的共视关键帧的世界坐标系下Sim3 位姿(还没有修正)
// 遍历"当前关键帧组""
for(vector<KeyFrame*>::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++)
{
KeyFrame* pKFi = *vit;
cv::Mat Tiw = pKFi->GetPose();
if(pKFi!=mpCurrentKF) //跳过当前关键帧,因为当前关键帧的位姿已经在前面优化过了,在这里是参考基准
{
// 得到当前关键帧 mpCurrentKF 到其共视关键帧 pKFi 的相对变换
cv::Mat Tic = Tiw*Twc;
cv::Mat Ric = Tic.rowRange(0,3).colRange(0,3);
cv::Mat tic = Tic.rowRange(0,3).col(3);
// g2oSic当前关键帧 mpCurrentKF 到其共视关键帧 pKFi 的Sim3 相对变换
// 这里是non-correct, 所以scale=1.0
g2o::Sim3 g2oSic(Converter::toMatrix3d(Ric),Converter::toVector3d(tic),1.0);
// 当前帧的位姿固定不动其它的关键帧根据相对关系得到Sim3调整的位姿
g2o::Sim3 g2oCorrectedSiw = g2oSic*mg2oLoopScw;
//Pose corrected with the Sim3 of the loop closure
// 存放闭环g2o优化后当前关键帧的共视关键帧的Sim3 位姿
CorrectedSim3[pKFi]=g2oCorrectedSiw;
}
cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3);
cv::Mat tiw = Tiw.rowRange(0,3).col(3);
g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0);
//Pose without correction
NonCorrectedSim3[pKFi]=g2oSiw;
}
// Correct all MapPoints obsrved by current keyframe and neighbors, so that they align with the other side of the loop
// Step 2.2:得到矫正的当前关键帧的共视关键帧位姿后,修正这些关键帧的地图点
// 遍历待矫正的共视关键帧(不包括当前关键帧)
for(KeyFrameAndPose::iterator mit=CorrectedSim3.begin(), mend=CorrectedSim3.end(); mit!=mend; mit++)
{
KeyFrame* pKFi = mit->first;
g2o::Sim3 g2oCorrectedSiw = mit->second;
g2o::Sim3 g2oCorrectedSwi = g2oCorrectedSiw.inverse();
g2o::Sim3 g2oSiw =NonCorrectedSim3[pKFi];
vector<MapPoint*> vpMPsi = pKFi->GetMapPointMatches();
// 遍历待矫正共视关键帧中的每一个地图点
for(size_t iMP=0, endMPi = vpMPsi.size(); iMP<endMPi; iMP++)
{
MapPoint* pMPi = vpMPsi[iMP];
if(!pMPi)
continue;
if(pMPi->isBad())
continue;
if(pMPi->mnCorrectedByKF==mpCurrentKF->mnId) // 标记,防止重复矫正
continue;
// 矫正过程本质上也是基于当前关键帧的优化后的位姿展开的
// Project with non-corrected pose and project back with corrected pose
// 将该未校正的eigP3Dw先从世界坐标系映射到未校正的pKFi相机坐标系然后再反映射到校正后的世界坐标系下
cv::Mat P3Dw = pMPi->GetWorldPos();
// 地图点世界坐标系下坐标
Eigen::Matrix<double,3,1> eigP3Dw = Converter::toVector3d(P3Dw);
// map(P) 内部做了变换 R*P +t
// 下面变换是eigP3Dw world →g2oSiw→ i →g2oCorrectedSwi→ world
Eigen::Matrix<double,3,1> eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oSiw.map(eigP3Dw));
cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw);
pMPi->SetWorldPos(cvCorrectedP3Dw);
// 记录矫正该地图点的关键帧id防止重复
pMPi->mnCorrectedByKF = mpCurrentKF->mnId;
// 记录该地图点所在的关键帧id
pMPi->mnCorrectedReference = pKFi->mnId;
// 因为地图点更新了,需要更新其平均观测方向以及观测距离范围
pMPi->UpdateNormalAndDepth();
}
// Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation)
// Step 2.3将共视关键帧的Sim3转换为SE3根据更新的Sim3更新关键帧的位姿
// 其实是现在已经有了更新后的关键帧组中关键帧的位姿,但是在上面的操作时只是暂时存储到了 KeyFrameAndPose 类型的变量中,还没有写回到关键帧对象中
// 调用toRotationMatrix 可以自动归一化旋转矩阵
Eigen::Matrix3d eigR = g2oCorrectedSiw.rotation().toRotationMatrix();
Eigen::Vector3d eigt = g2oCorrectedSiw.translation();
double s = g2oCorrectedSiw.scale();
// cout << "scale for loop-closing: " << s << endl;
// 平移向量中包含有尺度信息,还需要用尺度归一化
eigt *=(1./s); //[R t/s;0 1]
cv::Mat correctedTiw = Converter::toCvSE3(eigR,eigt);
// 设置矫正后的新的pose
pKFi->SetPose(correctedTiw);
// Correct velocity according to orientation correction
if(bImuInit)
{
Eigen::Matrix3d Rcor = eigR.transpose()*g2oSiw.rotation().toRotationMatrix();
pKFi->SetVelocity(Converter::toCvMat(Rcor)*pKFi->GetVelocity());
}
// Make sure connections are updated
// Step 2.4:根据共视关系更新当前帧与其它关键帧之间的连接
// 地图点的位置改变了,可能会引起共视关系\权值的改变
pKFi->UpdateConnections();
}
// TODO Check this index increasement
2021-08-09 19:34:51 +08:00
pLoopMap->IncreaseChangeIndex();
2020-12-01 11:58:17 +08:00
// Start Loop Fusion
// Update matched map points and replace if duplicated
// Step 3检查当前帧的地图点与经过闭环匹配后该帧的地图点是否存在冲突对冲突的进行替换或填补
// mvpCurrentMatchedPoints 是当前关键帧和闭环关键帧组的所有地图点进行投影得到的匹配点
for(size_t i=0; i<mvpLoopMatchedMPs.size(); i++)
{
if(mvpLoopMatchedMPs[i])
{
//取出同一个索引对应的两种地图点,决定是否要替换
// 匹配投影得到的地图点
MapPoint* pLoopMP = mvpLoopMatchedMPs[i];
// 原来的地图点
MapPoint* pCurMP = mpCurrentKF->GetMapPoint(i);
if(pCurMP)
// 如果有重复的MapPoint则用匹配的地图点代替现有的
// 因为匹配的地图点是经过一系列操作后比较精确的,现有的地图点很可能有累计误差
pCurMP->Replace(pLoopMP);
else
{
// 如果当前帧没有该MapPoint则直接添加
mpCurrentKF->AddMapPoint(pLoopMP,i);
pLoopMP->AddObservation(mpCurrentKF,i);
pLoopMP->ComputeDistinctiveDescriptors();
}
}
}
}
// Project MapPoints observed in the neighborhood of the loop keyframe
// into the current keyframe and neighbors using corrected poses.
// Fuse duplications.
// Step 4将闭环相连关键帧组mvpLoopMapPoints 投影到当前关键帧组中进行匹配融合新增或替换当前关键帧组中KF的地图点
// 因为 闭环相连关键帧组mvpLoopMapPoints 在地图中时间比较久经历了多次优化,认为是准确的
// 而当前关键帧组中的关键帧的地图点是最近新计算的,可能有累积误差
// CorrectedSim3存放矫正后当前关键帧的共视关键帧及其世界坐标系下Sim3 变换
SearchAndFuse(CorrectedSim3, mvpLoopMapPoints);
//cout << "LC: end SearchAndFuse" << endl;
// After the MapPoint fusion, new links in the covisibility graph will appear attaching both sides of the loop
// Step 5更新当前关键帧之间的共视相连关系得到因闭环时MapPoints融合而新得到的连接关系
// LoopConnections存储因为闭环地图点调整而新生成的连接关系
map<KeyFrame*, set<KeyFrame*> > LoopConnections;
// Step 5.1:遍历当前帧相连关键帧组(一级相连)
for(vector<KeyFrame*>::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++)
{
KeyFrame* pKFi = *vit;
// Step 5.2:得到与当前帧相连关键帧的相连关键帧(二级相连)
vector<KeyFrame*> vpPreviousNeighbors = pKFi->GetVectorCovisibleKeyFrames();
// Update connections. Detect new links.
// Step 5.3:更新一级相连关键帧的连接关系(会把当前关键帧添加进去,因为地图点已经更新和替换了)
pKFi->UpdateConnections();
// Step 5.4:取出该帧更新后的连接关系
LoopConnections[pKFi]=pKFi->GetConnectedKeyFrames();
// Step 5.5:从连接关系中去除闭环之前的二级连接关系,剩下的连接就是由闭环得到的连接关系
for(vector<KeyFrame*>::iterator vit_prev=vpPreviousNeighbors.begin(), vend_prev=vpPreviousNeighbors.end(); vit_prev!=vend_prev; vit_prev++)
{
LoopConnections[pKFi].erase(*vit_prev);
}
// Step 5.6:从连接关系中去除闭环之前的一级连接关系,剩下的连接就是由闭环得到的连接关系
for(vector<KeyFrame*>::iterator vit2=mvpCurrentConnectedKFs.begin(), vend2=mvpCurrentConnectedKFs.end(); vit2!=vend2; vit2++)
{
LoopConnections[pKFi].erase(*vit2);
}
}
//cout << "LC: end updating covisibility graph" << endl;
// Optimize graph
//cout << "start opt essentialgraph" << endl;
bool bFixedScale = mbFixScale;
// TODO CHECK; Solo para el monocular inertial
if(mpTracker->mSensor==System::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2())
bFixedScale=false;
//cout << "Optimize essential graph" << endl;
if(pLoopMap->IsInertial() && pLoopMap->isImuInitialized())
{
//cout << "With 4DoF" << endl;
Optimizer::OptimizeEssentialGraph4DoF(pLoopMap, mpLoopMatchedKF, mpCurrentKF, NonCorrectedSim3, CorrectedSim3, LoopConnections);
}
else
{
//cout << "With 7DoF" << endl;
// Step 6进行EssentialGraph优化LoopConnections是形成闭环后新生成的连接关系不包括步骤7中当前帧与闭环匹配帧之间的连接关系
Optimizer::OptimizeEssentialGraph(pLoopMap, mpLoopMatchedKF, mpCurrentKF, NonCorrectedSim3, CorrectedSim3, LoopConnections, bFixedScale);
}
//cout << "Optimize essential graph finished" << endl;
//usleep(5*1000*1000);
mpAtlas->InformNewBigChange();
// Add loop edge
// Step 7添加当前帧与闭环匹配帧之间的边这个连接关系不优化
// !这两句话应该放在OptimizeEssentialGraph之前因为OptimizeEssentialGraph的步骤4.2中有优化
mpLoopMatchedKF->AddLoopEdge(mpCurrentKF);
mpCurrentKF->AddLoopEdge(mpLoopMatchedKF);
// Launch a new thread to perform Global Bundle Adjustment (Only if few keyframes, if not it would take too much time)
2021-09-03 14:24:01 +08:00
// 闭环地图没有imu初始化或者 仅有一个地图且内部关键帧<200时才执行全局BA否则太慢
2020-12-01 11:58:17 +08:00
if(!pLoopMap->isImuInitialized() || (pLoopMap->KeyFramesInMap()<200 && mpAtlas->CountMaps()==1))
{
// Step 8新建一个线程用于全局BA优化
// OptimizeEssentialGraph只是优化了一些主要关键帧的位姿这里进行全局BA可以全局优化所有位姿和MapPoints
mbRunningGBA = true;
mbFinishedGBA = false;
mbStopGBA = false;
mpThreadGBA = new thread(&LoopClosing::RunGlobalBundleAdjustment, this, pLoopMap, mpCurrentKF->mnId);
}
// Loop closed. Release Local Mapping.
mpLocalMapper->Release();
mLastLoopKFid = mpCurrentKF->mnId; //TODO old varible, it is not use in the new algorithm
}
2021-09-03 14:24:01 +08:00
/**
* @brief :
* 1. BA
* 2. Essential Graph BA
*
*/
2020-12-01 11:58:17 +08:00
void LoopClosing::MergeLocal()
{
2021-08-09 19:34:51 +08:00
Verbose::PrintMess("MERGE: Merge Visual detected!!!!", Verbose::VERBOSITY_NORMAL);
2021-09-03 14:24:01 +08:00
//mpTracker->SetStepByStep(true);
// 窗口内共视关键帧的数量
2020-12-01 11:58:17 +08:00
int numTemporalKFs = 15; //TODO (set by parameter): Temporal KFs in the local window if the map is inertial.
//Relationship to rebuild the essential graph, it is used two times, first in the local window and later in the rest of the map
2021-09-03 14:24:01 +08:00
// 建立本质图必须的量
2020-12-01 11:58:17 +08:00
KeyFrame* pNewChild;
KeyFrame* pNewParent;
2021-09-03 14:24:01 +08:00
// 当前关键帧的窗口
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpLocalCurrentWindowKFs;
2021-09-03 14:24:01 +08:00
// 候选关键帧的窗口
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpMergeConnectedKFs;
// Flag that is true only when we stopped a running BA, in this case we need relaunch at the end of the merge
2021-09-03 14:24:01 +08:00
// 记录是否把全局BA停下
2020-12-01 11:58:17 +08:00
bool bRelaunchBA = false;
2021-08-09 19:34:51 +08:00
Verbose::PrintMess("MERGE: Check Full Bundle Adjustment", Verbose::VERBOSITY_DEBUG);
2020-12-01 11:58:17 +08:00
// If a Global Bundle Adjustment is running, abort it
if(isRunningGBA())
{
unique_lock<mutex> lock(mMutexGBA);
mbStopGBA = true;
mnFullBAIdx++;
if(mpThreadGBA)
{
mpThreadGBA->detach();
delete mpThreadGBA;
}
bRelaunchBA = true;
}
2021-08-09 19:34:51 +08:00
Verbose::PrintMess("MERGE: Request Stop Local Mapping", Verbose::VERBOSITY_DEBUG);
2021-09-03 14:24:01 +08:00
// 请求局部建图线程停止
2020-12-01 11:58:17 +08:00
mpLocalMapper->RequestStop();
// Wait until Local Mapping has effectively stopped
2021-09-03 14:24:01 +08:00
// 等待局部建图工作停止
2020-12-01 11:58:17 +08:00
while(!mpLocalMapper->isStopped())
{
usleep(1000);
}
2021-08-09 19:34:51 +08:00
Verbose::PrintMess("MERGE: Local Map stopped", Verbose::VERBOSITY_DEBUG);
2020-12-01 11:58:17 +08:00
mpLocalMapper->EmptyQueue();
// Merge map will become in the new active map with the local window of KFs and MPs from the current map.
// Later, the elements of the current map will be transform to the new active map reference, in order to keep real time tracking
2021-09-03 14:24:01 +08:00
// 当前关键帧的共视关键帧和他们观测到的地图点会先被融合, 融合后的图会变成新的当前激活地图.
// 之后, 所有当前地图的其他部分会被转换到当前地图中, 这样是为了保证tracking的实时性.
// 当前关键帧地图的指针
2020-12-01 11:58:17 +08:00
Map* pCurrentMap = mpCurrentKF->GetMap();
2021-09-03 14:24:01 +08:00
// 融合关键帧地图的指针
2020-12-01 11:58:17 +08:00
Map* pMergeMap = mpMergeMatchedKF->GetMap();
// Ensure current keyframe is updated
2021-09-03 14:24:01 +08:00
// 先保证当前关键帧的链接关系是最新的
2020-12-01 11:58:17 +08:00
mpCurrentKF->UpdateConnections();
2021-09-03 14:24:01 +08:00
// Step 1 构建当前关键帧和融合关键帧的局部窗口(关键帧+地图点)
2020-12-01 11:58:17 +08:00
//Get the current KF and its neighbors(visual->covisibles; inertial->temporal+covisibles)
2021-09-03 14:24:01 +08:00
// 当前关键帧的局部窗口(仅是辅助容器,防止重复添加)
2020-12-01 11:58:17 +08:00
set<KeyFrame*> spLocalWindowKFs;
//Get MPs in the welding area from the current map
2021-09-03 14:24:01 +08:00
// 当前关键帧局部串口能观测到的所有地图点(仅是辅助容器,防止重复添加)
2020-12-01 11:58:17 +08:00
set<MapPoint*> spLocalWindowMPs;
2021-09-03 14:24:01 +08:00
// 这段代码只在visual状态下才会被使用所以只会执行else
// Step 1.1 构造当前关键帧局部共视帧窗口
2020-12-01 11:58:17 +08:00
if(pCurrentMap->IsInertial() && pMergeMap->IsInertial()) //TODO Check the correct initialization
{
KeyFrame* pKFi = mpCurrentKF;
int nInserted = 0;
while(pKFi && nInserted < numTemporalKFs)
{
spLocalWindowKFs.insert(pKFi);
pKFi = mpCurrentKF->mPrevKF;
nInserted++;
set<MapPoint*> spMPi = pKFi->GetMapPoints();
spLocalWindowMPs.insert(spMPi.begin(), spMPi.end());
}
pKFi = mpCurrentKF->mNextKF;
2021-09-03 14:24:01 +08:00
while(pKFi) //! 这里会死循环,不过无所谓这个外面的if永远不会执行
2020-12-01 11:58:17 +08:00
{
spLocalWindowKFs.insert(pKFi);
set<MapPoint*> spMPi = pKFi->GetMapPoints();
spLocalWindowMPs.insert(spMPi.begin(), spMPi.end());
}
}
else
{
2021-09-03 14:24:01 +08:00
// 把自己先加到窗口内
2020-12-01 11:58:17 +08:00
spLocalWindowKFs.insert(mpCurrentKF);
}
2021-09-03 14:24:01 +08:00
//拿到当前关键帧的numTemporalKFs(15)个最佳共视关键帧
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpCovisibleKFs = mpCurrentKF->GetBestCovisibilityKeyFrames(numTemporalKFs);
2021-09-03 14:24:01 +08:00
// 把当前帧的共视帧都加到窗口里
2020-12-01 11:58:17 +08:00
spLocalWindowKFs.insert(vpCovisibleKFs.begin(), vpCovisibleKFs.end());
2021-09-03 14:24:01 +08:00
// 限制while循环次数
2020-12-01 11:58:17 +08:00
const int nMaxTries = 3;
int nNumTries = 0;
2021-09-03 14:24:01 +08:00
// 如果窗口里的关键帧数量不够就再拉一些窗口里的关键帧的共视关键帧(二级共视关键帧)进来
2020-12-01 11:58:17 +08:00
while(spLocalWindowKFs.size() < numTemporalKFs && nNumTries < nMaxTries)
{
vector<KeyFrame*> vpNewCovKFs;
vpNewCovKFs.empty();
2021-09-03 14:24:01 +08:00
// 遍历创口内的每一个关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : spLocalWindowKFs)
{
2021-09-03 14:24:01 +08:00
// 拿到一些二级共视关键帧
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpKFiCov = pKFi->GetBestCovisibilityKeyFrames(numTemporalKFs/2);
2021-09-03 14:24:01 +08:00
// 对于每个二级共视关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFcov : vpKFiCov)
{
2021-09-03 14:24:01 +08:00
// 如果指针不为空,且关键帧没有被标记为bad,且没有被添加过则加到窗口内
2020-12-01 11:58:17 +08:00
if(pKFcov && !pKFcov->isBad() && spLocalWindowKFs.find(pKFcov) == spLocalWindowKFs.end())
{
vpNewCovKFs.push_back(pKFcov);
}
}
}
2021-09-03 14:24:01 +08:00
// 用set记录,防止重复添加
2020-12-01 11:58:17 +08:00
spLocalWindowKFs.insert(vpNewCovKFs.begin(), vpNewCovKFs.end());
2021-09-03 14:24:01 +08:00
// 递增循环次数
2020-12-01 11:58:17 +08:00
nNumTries++;
}
2021-09-03 14:24:01 +08:00
// Step 1.2 把当前关键帧窗口里关键帧观测到的地图点加进来
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : spLocalWindowKFs)
{
if(!pKFi || pKFi->isBad())
continue;
set<MapPoint*> spMPs = pKFi->GetMapPoints();
spLocalWindowMPs.insert(spMPs.begin(), spMPs.end());
}
2021-09-03 14:24:01 +08:00
// Step 1.3 构造融合帧的共视帧窗口
// 融合关键帧能的共视关键帧们
2020-12-01 11:58:17 +08:00
set<KeyFrame*> spMergeConnectedKFs;
2021-09-03 14:24:01 +08:00
// 这段代码只在visual状态下才会被使用所以只会执行else
2020-12-01 11:58:17 +08:00
if(pCurrentMap->IsInertial() && pMergeMap->IsInertial()) //TODO Check the correct initialization
{
KeyFrame* pKFi = mpMergeMatchedKF;
int nInserted = 0;
while(pKFi && nInserted < numTemporalKFs)
{
spMergeConnectedKFs.insert(pKFi);
pKFi = mpCurrentKF->mPrevKF;
nInserted++;
}
pKFi = mpMergeMatchedKF->mNextKF;
2021-09-03 14:24:01 +08:00
while(pKFi)//! 这里会死循环,不过无所谓if永远不会执行
2020-12-01 11:58:17 +08:00
{
spMergeConnectedKFs.insert(pKFi);
}
}
else
{
2021-09-03 14:24:01 +08:00
// 先把融合关键帧自己添加到窗口内
2020-12-01 11:58:17 +08:00
spMergeConnectedKFs.insert(mpMergeMatchedKF);
}
2021-09-03 14:24:01 +08:00
// 拿到融合关键帧最好的numTemporalKFs(15)个最佳共视关键帧
2020-12-01 11:58:17 +08:00
vpCovisibleKFs = mpMergeMatchedKF->GetBestCovisibilityKeyFrames(numTemporalKFs);
spMergeConnectedKFs.insert(vpCovisibleKFs.begin(), vpCovisibleKFs.end());
2021-09-03 14:24:01 +08:00
// 记录循环次数
2020-12-01 11:58:17 +08:00
nNumTries = 0;
2021-09-03 14:24:01 +08:00
// 如果融合关键帧窗口里的关键帧不够就再拉一些窗口里的关键帧的共视帧进来(二级共视关键帧)
2020-12-01 11:58:17 +08:00
while(spMergeConnectedKFs.size() < numTemporalKFs && nNumTries < nMaxTries)
{
vector<KeyFrame*> vpNewCovKFs;
2021-09-03 14:24:01 +08:00
// 遍历融合关键帧内的所有的一级共视关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : spMergeConnectedKFs)
{
2021-09-03 14:24:01 +08:00
// 拿到一些二级共视关键帧
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpKFiCov = pKFi->GetBestCovisibilityKeyFrames(numTemporalKFs/2);
2021-09-03 14:24:01 +08:00
// 对于每个二级共视关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFcov : vpKFiCov)
{
2021-09-03 14:24:01 +08:00
// 如果指针不为空,且关键帧没有被标记为bad,且没有被添加过则加到窗口内
2020-12-01 11:58:17 +08:00
if(pKFcov && !pKFcov->isBad() && spMergeConnectedKFs.find(pKFcov) == spMergeConnectedKFs.end())
{
vpNewCovKFs.push_back(pKFcov);
}
}
}
2021-09-03 14:24:01 +08:00
// 用set记录,防止重复添加
2020-12-01 11:58:17 +08:00
spMergeConnectedKFs.insert(vpNewCovKFs.begin(), vpNewCovKFs.end());
2021-09-03 14:24:01 +08:00
// 递增循环次数
2020-12-01 11:58:17 +08:00
nNumTries++;
}
2021-09-03 14:24:01 +08:00
// 融合关键帧共视窗口内的所有地图点
2020-12-01 11:58:17 +08:00
set<MapPoint*> spMapPointMerge;
2021-09-03 14:24:01 +08:00
// Step 1.4 把融合关键帧窗口里关键帧观测到的地图点加进来
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : spMergeConnectedKFs)
{
set<MapPoint*> vpMPs = pKFi->GetMapPoints();
spMapPointMerge.insert(vpMPs.begin(),vpMPs.end());
}
2021-09-03 14:24:01 +08:00
//把融合关键帧窗口内的地图点加到待融合的向量中
2020-12-01 11:58:17 +08:00
vector<MapPoint*> vpCheckFuseMapPoint;
vpCheckFuseMapPoint.reserve(spMapPointMerge.size());
std::copy(spMapPointMerge.begin(), spMapPointMerge.end(), std::back_inserter(vpCheckFuseMapPoint));
2021-09-03 14:24:01 +08:00
// Step 2 根据之前的Sim3初始值, 记录当前帧窗口内关键帧,地图点的矫正前的值,和矫正后的初始值
// Step 2.1 先计算当前关键帧矫正前的值,后矫正后的初始值
2020-12-01 11:58:17 +08:00
cv::Mat Twc = mpCurrentKF->GetPoseInverse();
cv::Mat Rwc = Twc.rowRange(0,3).colRange(0,3);
cv::Mat twc = Twc.rowRange(0,3).col(3);
2021-09-03 14:24:01 +08:00
// 记录没有融合矫正之前的Swc和Scw
2020-12-01 11:58:17 +08:00
g2o::Sim3 g2oNonCorrectedSwc(Converter::toMatrix3d(Rwc),Converter::toVector3d(twc),1.0);
g2o::Sim3 g2oNonCorrectedScw = g2oNonCorrectedSwc.inverse();
2021-09-03 14:24:01 +08:00
// 拿到之前通过Sim3(见 NewDetectCommonRegion)计算得到的当前关键帧融合矫正之后的初始位姿
2020-12-01 11:58:17 +08:00
g2o::Sim3 g2oCorrectedScw = mg2oMergeScw; //TODO Check the transformation
2021-09-03 14:24:01 +08:00
// 记录当前关键帧窗口内所有关键帧融合矫正之前的位姿,和融合矫正之后的初始位姿
2020-12-01 11:58:17 +08:00
KeyFrameAndPose vCorrectedSim3, vNonCorrectedSim3;
vCorrectedSim3[mpCurrentKF]=g2oCorrectedScw;
vNonCorrectedSim3[mpCurrentKF]=g2oNonCorrectedScw;
2021-09-03 14:24:01 +08:00
// Step 2.2 通过当前关键帧融合矫正前后的位姿,把当前关键帧的共视窗口里面剩余的关键帧矫正前后的位姿都给填写上
// 对于每个当前关键帧共视窗口里的关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : spLocalWindowKFs)
{
2021-09-03 14:24:01 +08:00
// 跳过空的指针,或者坏的关键帧
2020-12-01 11:58:17 +08:00
if(!pKFi || pKFi->isBad())
{
continue;
}
2021-09-03 14:24:01 +08:00
// 确保这些共视关键帧在当前地图下
// 保存第i个共视关键帧融合矫正后的初始位姿
2020-12-01 11:58:17 +08:00
g2o::Sim3 g2oCorrectedSiw;
if(pKFi!=mpCurrentKF)
{
2021-09-03 14:24:01 +08:00
// 先记录下融合矫正前的位姿
2020-12-01 11:58:17 +08:00
cv::Mat Tiw = pKFi->GetPose();
cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3);
cv::Mat tiw = Tiw.rowRange(0,3).col(3);
g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0);
//Pose without correction
vNonCorrectedSim3[pKFi]=g2oSiw;
2021-09-03 14:24:01 +08:00
// 根据链式法则,利用当前关键帧和第i个共视关键帧的位姿关系,以及当前关键帧矫正后的初始位姿,推得第i个共视关键帧的矫正后的初始位姿
2020-12-01 11:58:17 +08:00
cv::Mat Tic = Tiw*Twc;
cv::Mat Ric = Tic.rowRange(0,3).colRange(0,3);
cv::Mat tic = Tic.rowRange(0,3).col(3);
g2o::Sim3 g2oSic(Converter::toMatrix3d(Ric),Converter::toVector3d(tic),1.0);
g2oCorrectedSiw = g2oSic*mg2oMergeScw;
vCorrectedSim3[pKFi]=g2oCorrectedSiw;
}
else
{
g2oCorrectedSiw = g2oCorrectedScw;
}
2021-09-03 14:24:01 +08:00
// 这一句没有什么作用,下面又被覆盖了
2020-12-01 11:58:17 +08:00
pKFi->mTcwMerge = pKFi->GetPose();
// Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation)
2021-09-03 14:24:01 +08:00
// 根据上面计算得到的融合矫正后的初始位姿(Sim3),更新窗口内每个关键帧的mTcwMerge(矫正后的初始位姿)
2020-12-01 11:58:17 +08:00
Eigen::Matrix3d eigR = g2oCorrectedSiw.rotation().toRotationMatrix();
Eigen::Vector3d eigt = g2oCorrectedSiw.translation();
double s = g2oCorrectedSiw.scale();
pKFi->mfScale = s;
2021-09-03 14:24:01 +08:00
// 修正尺度
2020-12-01 11:58:17 +08:00
eigt *=(1./s); //[R t/s;0 1]
cv::Mat correctedTiw = Converter::toCvSE3(eigR,eigt);
2021-09-03 14:24:01 +08:00
// 赋值得到的矫正后的初始位姿
2020-12-01 11:58:17 +08:00
pKFi->mTcwMerge = correctedTiw;
2021-09-03 14:24:01 +08:00
//! 貌似又是没用的代码
2020-12-01 11:58:17 +08:00
if(pCurrentMap->isImuInitialized())
{
Eigen::Matrix3d Rcor = eigR.transpose()*vNonCorrectedSim3[pKFi].rotation().toRotationMatrix();
pKFi->mVwbMerge = Converter::toCvMat(Rcor)*pKFi->GetVelocity();
}
}
2021-09-03 14:24:01 +08:00
// Step 2.3 记录所有地图点矫正前的位置,和矫正后的初始值
// 对于每个窗口内的地图点
2020-12-01 11:58:17 +08:00
for(MapPoint* pMPi : spLocalWindowMPs)
{
if(!pMPi || pMPi->isBad())
continue;
2021-09-03 14:24:01 +08:00
// 拿到参考关键帧
2020-12-01 11:58:17 +08:00
KeyFrame* pKFref = pMPi->GetReferenceKeyFrame();
2021-09-03 14:24:01 +08:00
// 拿到计算好的矫正后参考关键帧的初始位姿
2020-12-01 11:58:17 +08:00
g2o::Sim3 g2oCorrectedSwi = vCorrectedSim3[pKFref].inverse();
2021-09-03 14:24:01 +08:00
// 拿到矫正前的参考关键帧的位姿
2020-12-01 11:58:17 +08:00
g2o::Sim3 g2oNonCorrectedSiw = vNonCorrectedSim3[pKFref];
// Project with non-corrected pose and project back with corrected pose
2021-09-03 14:24:01 +08:00
// 先把3D点转换到参考关键帧矫正前的坐标系中
2020-12-01 11:58:17 +08:00
cv::Mat P3Dw = pMPi->GetWorldPos();
Eigen::Matrix<double,3,1> eigP3Dw = Converter::toVector3d(P3Dw);
2021-09-03 14:24:01 +08:00
// 再转换到矫正后的初始坐标系中
2020-12-01 11:58:17 +08:00
Eigen::Matrix<double,3,1> eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oNonCorrectedSiw.map(eigP3Dw));
2021-09-03 14:24:01 +08:00
// 计算旋转部分的变化
2020-12-01 11:58:17 +08:00
Eigen::Matrix3d eigR = g2oCorrectedSwi.rotation().toRotationMatrix();
Eigen::Matrix3d Rcor = eigR * g2oNonCorrectedSiw.rotation().toRotationMatrix();
2021-09-03 14:24:01 +08:00
// 矫正后3d点的初始位置
2020-12-01 11:58:17 +08:00
cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw);
pMPi->mPosMerge = cvCorrectedP3Dw;
2021-09-03 14:24:01 +08:00
// 用旋转部分的变化更新计算3D点normal的新值
2020-12-01 11:58:17 +08:00
pMPi->mNormalVectorMerge = Converter::toCvMat(Rcor) * pMPi->GetNormal();
2021-08-09 19:34:51 +08:00
}
2020-12-01 11:58:17 +08:00
2021-09-03 14:24:01 +08:00
// Step 3 更新两个地图的信息(当前帧所在地图,融合帧所在地图)
{ // 当前地图会被更新,老的地图中的重复地图点会被剔除
2020-12-01 11:58:17 +08:00
unique_lock<mutex> currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information
unique_lock<mutex> mergeLock(pMergeMap->mMutexMapUpdate); // We remove the Kfs and MPs in the merged area from the old map
2021-09-03 14:24:01 +08:00
// 对于当前关键帧共视窗口内的每一个关键帧
// Step 3.1 更新当前关键帧共视窗口内的关键帧信息
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : spLocalWindowKFs)
{
if(!pKFi || pKFi->isBad())
{
//cout << "Bad KF in correction" << endl;
continue;
}
2021-09-03 14:24:01 +08:00
// 记录融合矫正前的位姿
2020-12-01 11:58:17 +08:00
pKFi->mTcwBefMerge = pKFi->GetPose();
pKFi->mTwcBefMerge = pKFi->GetPoseInverse();
2021-09-03 14:24:01 +08:00
// 把这个关键帧的位姿设置为融合矫正后的初始位姿
pKFi->SetPose(pKFi->mTcwMerge);
2020-12-01 11:58:17 +08:00
// Make sure connections are updated
2021-09-03 14:24:01 +08:00
// 把这个关键帧的地图设置为融合帧所在的地图
2020-12-01 11:58:17 +08:00
pKFi->UpdateMap(pMergeMap);
2021-09-03 14:24:01 +08:00
// 记录这个关键帧是被哪个当前关键帧融合的
2020-12-01 11:58:17 +08:00
pKFi->mnMergeCorrectedForKF = mpCurrentKF->mnId;
2021-09-03 14:24:01 +08:00
// 把这个关键帧所有权给到融合帧所在地图里
2020-12-01 11:58:17 +08:00
pMergeMap->AddKeyFrame(pKFi);
2021-09-03 14:24:01 +08:00
// 把这个关键帧从当前活跃地图中删掉
2020-12-01 11:58:17 +08:00
pCurrentMap->EraseKeyFrame(pKFi);
2021-09-03 14:24:01 +08:00
// 又是没用的代码
2020-12-01 11:58:17 +08:00
if(pCurrentMap->isImuInitialized())
{
pKFi->SetVelocity(pKFi->mVwbMerge);
}
}
2021-09-03 14:24:01 +08:00
// Step 3.2 更新当前关键帧共视帧窗口所能观测到的地图点的信息
//把所有地图点的所有权给到老图里面
// 对于每个当前关键帧共视窗口内的所有地图点
2020-12-01 11:58:17 +08:00
for(MapPoint* pMPi : spLocalWindowMPs)
{
if(!pMPi || pMPi->isBad())
continue;
2021-09-03 14:24:01 +08:00
// 把3D点的位置设置成融合矫正之后的位置
2020-12-01 11:58:17 +08:00
pMPi->SetWorldPos(pMPi->mPosMerge);
2021-09-03 14:24:01 +08:00
// 把3D点normal设置成融合矫正之后的法向量
2020-12-01 11:58:17 +08:00
pMPi->SetNormalVector(pMPi->mNormalVectorMerge);
2021-09-03 14:24:01 +08:00
// 把3D点所在的地图设置成融合帧所在的地图
2020-12-01 11:58:17 +08:00
pMPi->UpdateMap(pMergeMap);
2021-09-03 14:24:01 +08:00
// 把3D点添加进融合帧所在地图
2020-12-01 11:58:17 +08:00
pMergeMap->AddMapPoint(pMPi);
2021-09-03 14:24:01 +08:00
// 把3D点从当前活跃地图中删掉
2020-12-01 11:58:17 +08:00
pCurrentMap->EraseMapPoint(pMPi);
}
2021-09-03 14:24:01 +08:00
// Step 3.3 更新剩余信息,如Altas和融合帧所在地图的信息
// 在Altas中把老图重新激活
2020-12-01 11:58:17 +08:00
mpAtlas->ChangeMap(pMergeMap);
2021-09-03 14:24:01 +08:00
// 当前地图的信息都到融合帧所在地图里去了,可以设置为bad
2020-12-01 11:58:17 +08:00
mpAtlas->SetMapBad(pCurrentMap);
2021-09-03 14:24:01 +08:00
// 记录地图变化次数
2020-12-01 11:58:17 +08:00
pMergeMap->IncreaseChangeIndex();
}
2021-09-03 14:24:01 +08:00
// Step 4 融合两个地图(当前关键帧所在地图和融合帧所在地图)的本质图(其实修改的是spanning tree)
2020-12-01 11:58:17 +08:00
//Rebuild the essential graph in the local window
2021-09-03 14:24:01 +08:00
// 重新构造essential graph的相关信息
// 设置当前地图的第一个关键帧不再是第一次生成树了
2020-12-01 11:58:17 +08:00
pCurrentMap->GetOriginKF()->SetFirstConnection(false);
2021-09-03 14:24:01 +08:00
// 从当前关键帧开始反向遍历整个地图
2020-12-01 11:58:17 +08:00
pNewChild = mpCurrentKF->GetParent(); // Old parent, it will be the new child of this KF
pNewParent = mpCurrentKF; // Old child, now it will be the parent of its own parent(we need eliminate this KF from children list in its old parent)
2021-09-03 14:24:01 +08:00
// 把当前帧的父亲设置为融合帧
2020-12-01 11:58:17 +08:00
mpCurrentKF->ChangeParent(mpMergeMatchedKF);
2021-09-03 14:24:01 +08:00
// 作者本来想先只在当前关键帧窗口内操作,但是把第二个条件注释了, 可能是为了少些代码, 但是地图太大的时候会影响实时性
2020-12-01 11:58:17 +08:00
while(pNewChild /*&& spLocalWindowKFs.find(pNewChild) != spLocalWindowKFs.end()*/)
{
2021-09-03 14:24:01 +08:00
// new parent (old child) 不再是 new child (old parent) 的 child 了
2020-12-01 11:58:17 +08:00
pNewChild->EraseChild(pNewParent); // We remove the relation between the old parent and the new for avoid loop
2021-09-03 14:24:01 +08:00
// 记录原先老parent的parent, 用于后续遍历
2020-12-01 11:58:17 +08:00
KeyFrame * pOldParent = pNewChild->GetParent();
2021-09-03 14:24:01 +08:00
// 把 new parent 设置为 new child 的 parent (父子关系互换)
2020-12-01 11:58:17 +08:00
pNewChild->ChangeParent(pNewParent);
//cout << "The new parent of KF " << pNewChild->mnId << " was " << pNewChild->GetParent()->mnId << endl;
2021-09-03 14:24:01 +08:00
// 赋值指针, 用于遍历下一组父子
2020-12-01 11:58:17 +08:00
pNewParent = pNewChild;
pNewChild = pOldParent;
}
//Update the connections between the local window
2021-09-03 14:24:01 +08:00
// 更新融合帧局部的连接关系
2020-12-01 11:58:17 +08:00
mpMergeMatchedKF->UpdateConnections();
//cout << "MERGE-VISUAL: Essential graph rebuilded" << endl;
//std::copy(spMapPointCurrent.begin(), spMapPointCurrent.end(), std::back_inserter(vpCheckFuseMapPoint));
2021-09-03 14:24:01 +08:00
// 重新拿到融合帧局部的共视帧窗窗口
2020-12-01 11:58:17 +08:00
vpMergeConnectedKFs = mpMergeMatchedKF->GetVectorCovisibleKeyFrames();
vpMergeConnectedKFs.push_back(mpMergeMatchedKF);
2021-09-03 14:24:01 +08:00
// !bug 这里前面已经做过了, 所以这里重复添加了两遍点
2020-12-01 11:58:17 +08:00
vpCheckFuseMapPoint.reserve(spMapPointMerge.size());
std::copy(spMapPointMerge.begin(), spMapPointMerge.end(), std::back_inserter(vpCheckFuseMapPoint));
// Project MapPoints observed in the neighborhood of the merge keyframe
// into the current keyframe and neighbors using corrected poses.
// Fuse duplications.
2021-09-03 14:24:01 +08:00
// Step 5 把融合关键帧的共视窗口里的地图点投到当前关键帧的共视窗口里,把重复的点融合掉(用老的位置,代替新的位置)
2020-12-01 11:58:17 +08:00
SearchAndFuse(vCorrectedSim3, vpCheckFuseMapPoint);
// Update connectivity
2021-09-03 14:24:01 +08:00
// Step 6 再次更新链接关系
// 更新当前关键帧共视窗口内所有关键帧的连接
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : spLocalWindowKFs)
{
if(!pKFi || pKFi->isBad())
continue;
pKFi->UpdateConnections();
}
2021-09-03 14:24:01 +08:00
// 更新融合关键帧共视窗口内所有关键帧的连接
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : spMergeConnectedKFs)
{
if(!pKFi || pKFi->isBad())
continue;
pKFi->UpdateConnections();
}
bool bStop = false;
2021-08-09 19:34:51 +08:00
Verbose::PrintMess("MERGE: Start local BA ", Verbose::VERBOSITY_DEBUG);
2021-09-03 14:24:01 +08:00
// 为Local BA的接口, 把set转为vector
// Step 7 焊缝BA(Welding BA)
2020-12-01 11:58:17 +08:00
vpLocalCurrentWindowKFs.clear();
vpMergeConnectedKFs.clear();
std::copy(spLocalWindowKFs.begin(), spLocalWindowKFs.end(), std::back_inserter(vpLocalCurrentWindowKFs));
std::copy(spMergeConnectedKFs.begin(), spMergeConnectedKFs.end(), std::back_inserter(vpMergeConnectedKFs));
if (mpTracker->mSensor==System::IMU_MONOCULAR || mpTracker->mSensor==System::IMU_STEREO)
2021-09-03 14:24:01 +08:00
//! 没有用的代码
2020-12-01 11:58:17 +08:00
{
Optimizer::MergeInertialBA(mpLocalMapper->GetCurrKF(),mpMergeMatchedKF,&bStop, mpCurrentKF->GetMap(),vCorrectedSim3);
}
else
{
2021-09-03 14:24:01 +08:00
// 运行的 welding BA , 优化所有的当前关键帧共视窗口里的关键帧和地图点, 固定所有融合帧共视窗口里的帧
2020-12-01 11:58:17 +08:00
Optimizer::LocalBundleAdjustment(mpCurrentKF, vpLocalCurrentWindowKFs, vpMergeConnectedKFs,&bStop);
}
// Loop closed. Release Local Mapping.
2021-09-03 14:24:01 +08:00
// 在welding BA 之后我们就可以继续建图了
2020-12-01 11:58:17 +08:00
mpLocalMapper->Release();
2021-08-09 19:34:51 +08:00
Verbose::PrintMess("MERGE: Finish the LBA", Verbose::VERBOSITY_DEBUG);
2020-12-01 11:58:17 +08:00
////
2021-09-03 14:24:01 +08:00
// Step 8 把之前的局部信息传递到整个当前帧所在地图中
2020-12-01 11:58:17 +08:00
//Update the non critical area from the current map to the merged map
2021-09-03 14:24:01 +08:00
// 把前面优位姿优化的结果传递到地图中其他的关键帧
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpCurrentMapKFs = pCurrentMap->GetAllKeyFrames();
vector<MapPoint*> vpCurrentMapMPs = pCurrentMap->GetAllMapPoints();
if(vpCurrentMapKFs.size() == 0)
{
2021-08-09 19:34:51 +08:00
Verbose::PrintMess("MERGE: There are not KFs outside of the welding area", Verbose::VERBOSITY_DEBUG);
2020-12-01 11:58:17 +08:00
}
else
{
2021-08-09 19:34:51 +08:00
Verbose::PrintMess("MERGE: Calculate the new position of the elements outside of the window", Verbose::VERBOSITY_DEBUG);
2020-12-01 11:58:17 +08:00
//Apply the transformation
{
if(mpTracker->mSensor == System::MONOCULAR)
{
2021-09-03 14:24:01 +08:00
// 锁住当前地图
2020-12-01 11:58:17 +08:00
unique_lock<mutex> currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information
2021-09-03 14:24:01 +08:00
// Step 8.1 拿到当前帧所在地图里的所有关键帧, 重复之前的过程, 不过这里是对于地图里剩余的所有的关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : vpCurrentMapKFs)
{
if(!pKFi || pKFi->isBad() || pKFi->GetMap() != pCurrentMap)
{
continue;
}
g2o::Sim3 g2oCorrectedSiw;
cv::Mat Tiw = pKFi->GetPose();
cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3);
cv::Mat tiw = Tiw.rowRange(0,3).col(3);
g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0);
//Pose without correction
vNonCorrectedSim3[pKFi]=g2oSiw;
cv::Mat Tic = Tiw*Twc;
cv::Mat Ric = Tic.rowRange(0,3).colRange(0,3);
cv::Mat tic = Tic.rowRange(0,3).col(3);
g2o::Sim3 g2oSim(Converter::toMatrix3d(Ric),Converter::toVector3d(tic),1.0);
g2oCorrectedSiw = g2oSim*mg2oMergeScw;
vCorrectedSim3[pKFi]=g2oCorrectedSiw;
// Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation)
Eigen::Matrix3d eigR = g2oCorrectedSiw.rotation().toRotationMatrix();
Eigen::Vector3d eigt = g2oCorrectedSiw.translation();
double s = g2oCorrectedSiw.scale();
pKFi->mfScale = s;
eigt *=(1./s); //[R t/s;0 1]
cv::Mat correctedTiw = Converter::toCvSE3(eigR,eigt);
pKFi->mTcwBefMerge = pKFi->GetPose();
pKFi->mTwcBefMerge = pKFi->GetPoseInverse();
pKFi->SetPose(correctedTiw);
if(pCurrentMap->isImuInitialized())
{
Eigen::Matrix3d Rcor = eigR.transpose()*vNonCorrectedSim3[pKFi].rotation().toRotationMatrix();
pKFi->SetVelocity(Converter::toCvMat(Rcor)*pKFi->GetVelocity()); // TODO: should add here scale s
}
}
for(MapPoint* pMPi : vpCurrentMapMPs)
{
if(!pMPi || pMPi->isBad()|| pMPi->GetMap() != pCurrentMap)
continue;
KeyFrame* pKFref = pMPi->GetReferenceKeyFrame();
g2o::Sim3 g2oCorrectedSwi = vCorrectedSim3[pKFref].inverse();
g2o::Sim3 g2oNonCorrectedSiw = vNonCorrectedSim3[pKFref];
// Project with non-corrected pose and project back with corrected pose
cv::Mat P3Dw = pMPi->GetWorldPos();
Eigen::Matrix<double,3,1> eigP3Dw = Converter::toVector3d(P3Dw);
Eigen::Matrix<double,3,1> eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oNonCorrectedSiw.map(eigP3Dw));
cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw);
pMPi->SetWorldPos(cvCorrectedP3Dw);
pMPi->UpdateNormalAndDepth();
}
}
}
mpLocalMapper->RequestStop();
// Wait until Local Mapping has effectively stopped
while(!mpLocalMapper->isStopped())
{
usleep(1000);
}
// Optimize graph (and update the loop position for each element form the begining to the end)
2021-09-03 14:24:01 +08:00
// Step 8.2 本质图优化
2020-12-01 11:58:17 +08:00
if(mpTracker->mSensor != System::MONOCULAR)
2021-09-03 14:24:01 +08:00
{
//固定 : 所有融合帧共视窗口内的关键帧 + 所有当前关键帧共视窗口内的关键帧
//优化: 当前关键帧所在地图里的所有关键帧(除了当前关键帧共视窗口内的关键帧) + 当前地图里的所有地图点
2020-12-01 11:58:17 +08:00
Optimizer::OptimizeEssentialGraph(mpCurrentKF, vpMergeConnectedKFs, vpLocalCurrentWindowKFs, vpCurrentMapKFs, vpCurrentMapMPs);
}
{
// Get Merge Map Mutex
unique_lock<mutex> currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information
unique_lock<mutex> mergeLock(pMergeMap->mMutexMapUpdate); // We remove the Kfs and MPs in the merged area from the old map
2021-09-03 14:24:01 +08:00
// 确保融合后信息被更新
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : vpCurrentMapKFs)
{
if(!pKFi || pKFi->isBad() || pKFi->GetMap() != pCurrentMap)
{
continue;
}
// Make sure connections are updated
pKFi->UpdateMap(pMergeMap);
pMergeMap->AddKeyFrame(pKFi);
pCurrentMap->EraseKeyFrame(pKFi);
}
for(MapPoint* pMPi : vpCurrentMapMPs)
{
if(!pMPi || pMPi->isBad())
continue;
pMPi->UpdateMap(pMergeMap);
pMergeMap->AddMapPoint(pMPi);
pCurrentMap->EraseMapPoint(pMPi);
}
}
}
2021-09-03 14:24:01 +08:00
//Essential graph 优化后可以重新开始局部建图了
2020-12-01 11:58:17 +08:00
mpLocalMapper->Release();
2021-08-09 19:34:51 +08:00
Verbose::PrintMess("MERGE:Completed!!!!!", Verbose::VERBOSITY_DEBUG);
2020-12-01 11:58:17 +08:00
2021-09-03 14:24:01 +08:00
// 如果之前停掉了全局的BA,就开启全局BA
// 这里没有imu, 所以isImuInitialized一定是false, 所以第二个条件一定是true
// Step 9 全局BA
2020-12-01 11:58:17 +08:00
if(bRelaunchBA && (!pCurrentMap->isImuInitialized() || (pCurrentMap->KeyFramesInMap()<200 && mpAtlas->CountMaps()==1)))
{
// Launch a new thread to perform Global Bundle Adjustment
Verbose::PrintMess("Relaunch Global BA", Verbose::VERBOSITY_DEBUG);
mbRunningGBA = true;
mbFinishedGBA = false;
mbStopGBA = false;
2021-09-03 14:24:01 +08:00
// 重新执行全局BA
2020-12-01 11:58:17 +08:00
mpThreadGBA = new thread(&LoopClosing::RunGlobalBundleAdjustment,this, pMergeMap, mpCurrentKF->mnId);
}
2021-09-03 14:24:01 +08:00
// 添加融合边(这里不是参与优化的边,只是记录)
2020-12-01 11:58:17 +08:00
mpMergeMatchedKF->AddMergeEdge(mpCurrentKF);
mpCurrentKF->AddMergeEdge(mpMergeMatchedKF);
pCurrentMap->IncreaseChangeIndex();
pMergeMap->IncreaseChangeIndex();
2021-09-03 14:24:01 +08:00
// altas移除不好的地图
2020-12-01 11:58:17 +08:00
mpAtlas->RemoveBadMaps();
}
2021-09-03 14:24:01 +08:00
/**
* @brief imu, 90%,
*/
2020-12-01 11:58:17 +08:00
void LoopClosing::MergeLocal2()
{
cout << "Merge detected!!!!" << endl;
2021-09-03 14:24:01 +08:00
// 没用上
2020-12-01 11:58:17 +08:00
int numTemporalKFs = 11; //TODO (set by parameter): Temporal KFs in the local window if the map is inertial.
//Relationship to rebuild the essential graph, it is used two times, first in the local window and later in the rest of the map
2021-09-03 14:24:01 +08:00
// 用来重新构造Essential Graph
2020-12-01 11:58:17 +08:00
KeyFrame* pNewChild;
KeyFrame* pNewParent;
2021-09-03 14:24:01 +08:00
// 没用上
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpLocalCurrentWindowKFs;
vector<KeyFrame*> vpMergeConnectedKFs;
2021-09-03 14:24:01 +08:00
// 记录用初始Sim3 计算出来的当前关键帧局部共视帧窗口内的所有关键帧矫正前的值和矫正后的初始值
2020-12-01 11:58:17 +08:00
KeyFrameAndPose CorrectedSim3, NonCorrectedSim3;
// NonCorrectedSim3[mpCurrentKF]=mg2oLoopScw;
// Flag that is true only when we stopped a running BA, in this case we need relaunch at the end of the merge
2021-09-03 14:24:01 +08:00
// 记录要不要重新进行全局ba
2020-12-01 11:58:17 +08:00
bool bRelaunchBA = false;
cout << "Check Full Bundle Adjustment" << endl;
// If a Global Bundle Adjustment is running, abort it
2021-09-03 14:24:01 +08:00
// ! bug, 这里停掉的GBA不会在relaunch, 后面都没有用bRelaunchBA这个变量
2020-12-01 11:58:17 +08:00
if(isRunningGBA())
{
unique_lock<mutex> lock(mMutexGBA);
mbStopGBA = true;
mnFullBAIdx++;
if(mpThreadGBA)
{
mpThreadGBA->detach();
delete mpThreadGBA;
}
bRelaunchBA = true;
}
cout << "Request Stop Local Mapping" << endl;
2021-09-03 14:24:01 +08:00
// 停下局部建图
2020-12-01 11:58:17 +08:00
mpLocalMapper->RequestStop();
// Wait until Local Mapping has effectively stopped
while(!mpLocalMapper->isStopped())
{
usleep(1000);
}
cout << "Local Map stopped" << endl;
2021-09-03 14:24:01 +08:00
// 当前关键帧地图的指针
2020-12-01 11:58:17 +08:00
Map* pCurrentMap = mpCurrentKF->GetMap();
2021-09-03 14:24:01 +08:00
// 融合关键帧地图的指针
2020-12-01 11:58:17 +08:00
Map* pMergeMap = mpMergeMatchedKF->GetMap();
2021-09-03 14:24:01 +08:00
// Step 1 利用之前计算的sim3相关信息, 把整个当前地图变换到融合帧所在地图
2020-12-01 11:58:17 +08:00
{
2021-09-03 14:24:01 +08:00
// sold 是之前sim3中计算的correction,用来把当前关键帧所在的地图位姿带到融合关键帧所在的地图
2020-12-01 11:58:17 +08:00
float s_on = mSold_new.scale();
cv::Mat R_on = Converter::toCvMat(mSold_new.rotation().toRotationMatrix());
cv::Mat t_on = Converter::toCvMat(mSold_new.translation());
2021-09-03 14:24:01 +08:00
// 锁住altas更新地图
2020-12-01 11:58:17 +08:00
unique_lock<mutex> lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate);
mpLocalMapper->EmptyQueue();
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
2021-09-03 14:24:01 +08:00
// 是否带尺度
2020-12-01 11:58:17 +08:00
bool bScaleVel=false;
if(s_on!=1)
bScaleVel=true;
2021-09-03 14:24:01 +08:00
// 利用sim3信息把整个当前地图转到融合帧所在地图
2020-12-01 11:58:17 +08:00
mpAtlas->GetCurrentMap()->ApplyScaledRotation(R_on,s_on,bScaleVel,t_on);
2021-09-03 14:24:01 +08:00
// 更具尺度信息更新imu信息
2020-12-01 11:58:17 +08:00
mpTracker->UpdateFrameIMU(s_on,mpCurrentKF->GetImuBias(),mpTracker->GetLastKeyFrame());
std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now();
}
2021-09-03 14:24:01 +08:00
// Step 2 如果地图没有成熟,在这里进行一次InertialOptimization
2020-12-01 11:58:17 +08:00
const int numKFnew=pCurrentMap->KeyFramesInMap();
2021-09-03 14:24:01 +08:00
// imu模式下,且地图没有成熟
2020-12-01 11:58:17 +08:00
if((mpTracker->mSensor==System::IMU_MONOCULAR || mpTracker->mSensor==System::IMU_STEREO)&& !pCurrentMap->GetIniertialBA2()){
// Map is not completly initialized
Eigen::Vector3d bg, ba;
bg << 0., 0., 0.;
ba << 0., 0., 0.;
2021-09-03 14:24:01 +08:00
// 优化当前地图中参数bg,ba
2020-12-01 11:58:17 +08:00
Optimizer::InertialOptimization(pCurrentMap,bg,ba);
IMU::Bias b (ba[0],ba[1],ba[2],bg[0],bg[1],bg[2]);
unique_lock<mutex> lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate);
2021-09-03 14:24:01 +08:00
// 用优化得到的 bias 更新地图
2020-12-01 11:58:17 +08:00
mpTracker->UpdateFrameIMU(1.0f,b,mpTracker->GetLastKeyFrame());
// Set map initialized
2021-09-03 14:24:01 +08:00
// 设置地图已经成熟
2020-12-01 11:58:17 +08:00
pCurrentMap->SetIniertialBA2();
pCurrentMap->SetIniertialBA1();
pCurrentMap->SetImuInitialized();
}
// Load KFs and MPs from merge map
{
// Get Merge Map Mutex (This section stops tracking!!)
unique_lock<mutex> currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information
unique_lock<mutex> mergeLock(pMergeMap->mMutexMapUpdate); // We remove the Kfs and MPs in the merged area from the old map
2021-09-03 14:24:01 +08:00
// 融合帧所在地图的所有关键帧和地图点
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpMergeMapKFs = pMergeMap->GetAllKeyFrames();
vector<MapPoint*> vpMergeMapMPs = pMergeMap->GetAllMapPoints();
2021-09-03 14:24:01 +08:00
// 遍历每个融合帧所在地图的关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : vpMergeMapKFs)
{
if(!pKFi || pKFi->isBad() || pKFi->GetMap() != pMergeMap)
{
continue;
}
// Make sure connections are updated
2021-09-03 14:24:01 +08:00
// 把关键帧从融合帧所在地图删掉,从融合帧所在地图删掉
2020-12-01 11:58:17 +08:00
pKFi->UpdateMap(pCurrentMap);
pCurrentMap->AddKeyFrame(pKFi);
pMergeMap->EraseKeyFrame(pKFi);
}
2021-09-03 14:24:01 +08:00
// 遍历每个融合帧所在地图的地图点
2020-12-01 11:58:17 +08:00
for(MapPoint* pMPi : vpMergeMapMPs)
{
if(!pMPi || pMPi->isBad() || pMPi->GetMap() != pMergeMap)
continue;
2021-09-03 14:24:01 +08:00
// 把地图点添加到当前帧所在地图,从融合帧所在地图删掉
2020-12-01 11:58:17 +08:00
pMPi->UpdateMap(pCurrentMap);
pCurrentMap->AddMapPoint(pMPi);
pMergeMap->EraseMapPoint(pMPi);
}
// Save non corrected poses (already merged maps)
2021-09-03 14:24:01 +08:00
// 存下所有关键帧在融合矫正之前的位姿
2020-12-01 11:58:17 +08:00
vector<KeyFrame*> vpKFs = pCurrentMap->GetAllKeyFrames();
for(KeyFrame* pKFi : vpKFs)
{
cv::Mat Tiw=pKFi->GetPose();
cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3);
cv::Mat tiw = Tiw.rowRange(0,3).col(3);
g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0);
NonCorrectedSim3[pKFi]=g2oSiw;
}
}
pMergeMap->GetOriginKF()->SetFirstConnection(false);
pNewChild = mpMergeMatchedKF->GetParent(); // Old parent, it will be the new child of this KF
pNewParent = mpMergeMatchedKF; // Old child, now it will be the parent of its own parent(we need eliminate this KF from children list in its old parent)
mpMergeMatchedKF->ChangeParent(mpCurrentKF);
while(pNewChild)
{
pNewChild->EraseChild(pNewParent); // We remove the relation between the old parent and the new for avoid loop
KeyFrame * pOldParent = pNewChild->GetParent();
pNewChild->ChangeParent(pNewParent);
pNewParent = pNewChild;
pNewChild = pOldParent;
}
vector<MapPoint*> vpCheckFuseMapPoint; // MapPoint vector from current map to allow to fuse duplicated points with the old map (merge)
vector<KeyFrame*> vpCurrentConnectedKFs;
2021-09-03 14:24:01 +08:00
// 拿出融合帧的局部窗口, 确保最后是(1+5), 1: 融合帧自己 2: 5个共视关键帧
2020-12-01 11:58:17 +08:00
mvpMergeConnectedKFs.push_back(mpMergeMatchedKF);
vector<KeyFrame*> aux = mpMergeMatchedKF->GetVectorCovisibleKeyFrames();
mvpMergeConnectedKFs.insert(mvpMergeConnectedKFs.end(), aux.begin(), aux.end());
if (mvpMergeConnectedKFs.size()>6)
mvpMergeConnectedKFs.erase(mvpMergeConnectedKFs.begin()+6,mvpMergeConnectedKFs.end());
2021-09-03 14:24:01 +08:00
// 拿出当前关键帧的局部窗口, 确保最后是(1+5), 1: 融合帧自己 2: 5个共视关键帧
2020-12-01 11:58:17 +08:00
mpCurrentKF->UpdateConnections();
vpCurrentConnectedKFs.push_back(mpCurrentKF);
aux = mpCurrentKF->GetVectorCovisibleKeyFrames();
vpCurrentConnectedKFs.insert(vpCurrentConnectedKFs.end(), aux.begin(), aux.end());
if (vpCurrentConnectedKFs.size()>6)
vpCurrentConnectedKFs.erase(vpCurrentConnectedKFs.begin()+6,vpCurrentConnectedKFs.end());
2021-09-03 14:24:01 +08:00
// 所有融合帧局部窗口的地图点
2020-12-01 11:58:17 +08:00
set<MapPoint*> spMapPointMerge;
for(KeyFrame* pKFi : mvpMergeConnectedKFs)
{
set<MapPoint*> vpMPs = pKFi->GetMapPoints();
spMapPointMerge.insert(vpMPs.begin(),vpMPs.end());
if(spMapPointMerge.size()>1000)
break;
}
vpCheckFuseMapPoint.reserve(spMapPointMerge.size());
std::copy(spMapPointMerge.begin(), spMapPointMerge.end(), std::back_inserter(vpCheckFuseMapPoint));
2021-09-03 14:24:01 +08:00
// 把融合帧所在局部窗口的地图点投向当前关键帧所在窗口,移除重复的点.(新值用旧值代替)
2020-12-01 11:58:17 +08:00
SearchAndFuse(vpCurrentConnectedKFs, vpCheckFuseMapPoint);
2021-09-03 14:24:01 +08:00
// 更新当前关键帧共视窗口内所有关键帧的连接
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : vpCurrentConnectedKFs)
{
if(!pKFi || pKFi->isBad())
continue;
pKFi->UpdateConnections();
}
2021-09-03 14:24:01 +08:00
// 更新融合关键帧共视窗口内所有关键帧的连接
2020-12-01 11:58:17 +08:00
for(KeyFrame* pKFi : mvpMergeConnectedKFs)
{
if(!pKFi || pKFi->isBad())
continue;
pKFi->UpdateConnections();
}
if (numKFnew<10){
mpLocalMapper->Release();
return;
}
// Perform BA
bool bStopFlag=false;
KeyFrame* pCurrKF = mpTracker->GetLastKeyFrame();
2021-09-03 14:24:01 +08:00
// Step 3 在这里进行welding BA
2020-12-01 11:58:17 +08:00
Optimizer::MergeInertialBA(pCurrKF, mpMergeMatchedKF, &bStopFlag, pCurrentMap,CorrectedSim3);
// Release Local Mapping.
mpLocalMapper->Release();
return;
}
void LoopClosing::SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap, vector<MapPoint*> &vpMapPoints)
{
ORBmatcher matcher(0.8);
int total_replaces = 0;
2021-09-03 14:24:01 +08:00
// 遍历每个关键帧
2020-12-01 11:58:17 +08:00
for(KeyFrameAndPose::const_iterator mit=CorrectedPosesMap.begin(), mend=CorrectedPosesMap.end(); mit!=mend;mit++)
{
int num_replaces = 0;
KeyFrame* pKFi = mit->first;
Map* pMap = pKFi->GetMap();
g2o::Sim3 g2oScw = mit->second;
cv::Mat cvScw = Converter::toCvMat(g2oScw);
vector<MapPoint*> vpReplacePoints(vpMapPoints.size(),static_cast<MapPoint*>(NULL));
int numFused = matcher.Fuse(pKFi,cvScw,vpMapPoints,4,vpReplacePoints);
// Get Map Mutex
unique_lock<mutex> lock(pMap->mMutexMapUpdate);
const int nLP = vpMapPoints.size();
for(int i=0; i<nLP;i++)
{
MapPoint* pRep = vpReplacePoints[i];
if(pRep)
{
num_replaces += 1;
pRep->Replace(vpMapPoints[i]);
}
}
total_replaces += num_replaces;
}
}
void LoopClosing::SearchAndFuse(const vector<KeyFrame*> &vConectedKFs, vector<MapPoint*> &vpMapPoints)
{
ORBmatcher matcher(0.8);
int total_replaces = 0;
for(auto mit=vConectedKFs.begin(), mend=vConectedKFs.end(); mit!=mend;mit++)
{
int num_replaces = 0;
KeyFrame* pKF = (*mit);
Map* pMap = pKF->GetMap();
cv::Mat cvScw = pKF->GetPose();
vector<MapPoint*> vpReplacePoints(vpMapPoints.size(),static_cast<MapPoint*>(NULL));
matcher.Fuse(pKF,cvScw,vpMapPoints,4,vpReplacePoints);
// Get Map Mutex
unique_lock<mutex> lock(pMap->mMutexMapUpdate);
const int nLP = vpMapPoints.size();
for(int i=0; i<nLP;i++)
{
MapPoint* pRep = vpReplacePoints[i];
if(pRep)
{
num_replaces += 1;
pRep->Replace(vpMapPoints[i]);
}
}
total_replaces += num_replaces;
}
}
// 由外部线程调用,请求复位当前线程
void LoopClosing::RequestReset()
{
{
unique_lock<mutex> lock(mMutexReset);
mbResetRequested = true;
}
while(1)
{
{
unique_lock<mutex> lock2(mMutexReset);
if(!mbResetRequested)
break;
}
usleep(5000);
}
}
void LoopClosing::RequestResetActiveMap(Map *pMap)
{
{
unique_lock<mutex> lock(mMutexReset);
mbResetActiveMapRequested = true;
mpMapToReset = pMap;
}
while(1)
{
{
unique_lock<mutex> lock2(mMutexReset);
if(!mbResetActiveMapRequested)
break;
}
usleep(3000);
}
}
// 当前线程调用,检查是否有外部线程请求复位当前线程,如果有的话就复位回环检测线程
void LoopClosing::ResetIfRequested()
{
unique_lock<mutex> lock(mMutexReset);
// 如果有来自于外部的线程的复位请求,那么就复位当前线程
if(mbResetRequested)
{
cout << "Loop closer reset requested..." << endl;
mlpLoopKeyFrameQueue.clear(); // 清空参与和进行回环检测的关键帧队列
mLastLoopKFid=0; // 上一次没有和任何关键帧形成闭环关系
mbResetRequested=false; // 复位请求标志复位
mbResetActiveMapRequested = false;
}
else if(mbResetActiveMapRequested)
{
for (list<KeyFrame*>::const_iterator it=mlpLoopKeyFrameQueue.begin(); it != mlpLoopKeyFrameQueue.end();)
{
KeyFrame* pKFi = *it;
if(pKFi->GetMap() == mpMapToReset)
{
it = mlpLoopKeyFrameQueue.erase(it);
}
else
++it;
}
mLastLoopKFid=mpAtlas->GetLastInitKFid(); //TODO old variable, it is not use in the new algorithm
mbResetActiveMapRequested=false;
}
}
void LoopClosing::RunGlobalBundleAdjustment(Map* pActiveMap, unsigned long nLoopKF)
{
Verbose::PrintMess("Starting Global Bundle Adjustment", Verbose::VERBOSITY_NORMAL);
const bool bImuInit = pActiveMap->isImuInitialized();
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartFGBA = std::chrono::steady_clock::now();
#endif
2020-12-01 11:58:17 +08:00
if(!bImuInit)
Optimizer::GlobalBundleAdjustemnt(pActiveMap,10,&mbStopGBA,nLoopKF,false);
else
2021-09-03 14:24:01 +08:00
// 仅有一个地图且内部关键帧<200并且IMU完成了第一阶段初始化后才会进行下面
2020-12-01 11:58:17 +08:00
Optimizer::FullInertialBA(pActiveMap,7,false,nLoopKF,&mbStopGBA);
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartMapUpdate = std::chrono::steady_clock::now();
double timeFullGBA = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_StartMapUpdate - time_StartFGBA).count();
vTimeFullGBA_ms.push_back(timeFullGBA);
#endif
2021-09-03 14:24:01 +08:00
// 记录GBA已经迭代次数,用来检查全局BA过程是否是因为意外结束的
2020-12-01 11:58:17 +08:00
int idx = mnFullBAIdx;
// Optimizer::GlobalBundleAdjustemnt(mpMap,10,&mbStopGBA,nLoopKF,false);
// Update all MapPoints and KeyFrames
// Local Mapping was active during BA, that means that there might be new keyframes
// not included in the Global BA and they are not consistent with the updated map.
// We need to propagate the correction through the spanning tree
{
unique_lock<mutex> lock(mMutexGBA);
if(idx!=mnFullBAIdx)
return;
if(!bImuInit && pActiveMap->isImuInitialized())
return;
if(!mbStopGBA)
{
Verbose::PrintMess("Global Bundle Adjustment finished", Verbose::VERBOSITY_NORMAL);
Verbose::PrintMess("Updating map ...", Verbose::VERBOSITY_NORMAL);
mpLocalMapper->RequestStop();
// Wait until Local Mapping has effectively stopped
while(!mpLocalMapper->isStopped() && !mpLocalMapper->isFinished())
{
usleep(1000);
}
// Get Map Mutex
unique_lock<mutex> lock(pActiveMap->mMutexMapUpdate);
// cout << "LC: Update Map Mutex adquired" << endl;
//pActiveMap->PrintEssentialGraph();
// Correct keyframes starting at map first keyframe
list<KeyFrame*> lpKFtoCheck(pActiveMap->mvpKeyFrameOrigins.begin(),pActiveMap->mvpKeyFrameOrigins.end());
while(!lpKFtoCheck.empty())
{
KeyFrame* pKF = lpKFtoCheck.front();
const set<KeyFrame*> sChilds = pKF->GetChilds();
//cout << "---Updating KF " << pKF->mnId << " with " << sChilds.size() << " childs" << endl;
//cout << " KF mnBAGlobalForKF: " << pKF->mnBAGlobalForKF << endl;
cv::Mat Twc = pKF->GetPoseInverse();
//cout << "Twc: " << Twc << endl;
//cout << "GBA: Correct KeyFrames" << endl;
for(set<KeyFrame*>::const_iterator sit=sChilds.begin();sit!=sChilds.end();sit++)
{
KeyFrame* pChild = *sit;
if(!pChild || pChild->isBad())
continue;
if(pChild->mnBAGlobalForKF!=nLoopKF)
{
//cout << "++++New child with flag " << pChild->mnBAGlobalForKF << "; LoopKF: " << nLoopKF << endl;
//cout << " child id: " << pChild->mnId << endl;
cv::Mat Tchildc = pChild->GetPose()*Twc;
//cout << "Child pose: " << Tchildc << endl;
//cout << "pKF->mTcwGBA: " << pKF->mTcwGBA << endl;
pChild->mTcwGBA = Tchildc*pKF->mTcwGBA;//*Tcorc*pKF->mTcwGBA;
cv::Mat Rcor = pChild->mTcwGBA.rowRange(0,3).colRange(0,3).t()*pChild->GetRotation();
if(!pChild->GetVelocity().empty()){
//cout << "Child velocity: " << pChild->GetVelocity() << endl;
pChild->mVwbGBA = Rcor*pChild->GetVelocity();
}
else
Verbose::PrintMess("Child velocity empty!! ", Verbose::VERBOSITY_NORMAL);
//cout << "Child bias: " << pChild->GetImuBias() << endl;
pChild->mBiasGBA = pChild->GetImuBias();
pChild->mnBAGlobalForKF=nLoopKF;
}
lpKFtoCheck.push_back(pChild);
}
//cout << "-------Update pose" << endl;
pKF->mTcwBefGBA = pKF->GetPose();
//cout << "pKF->mTcwBefGBA: " << pKF->mTcwBefGBA << endl;
pKF->SetPose(pKF->mTcwGBA);
/*cv::Mat Tco_cn = pKF->mTcwBefGBA * pKF->mTcwGBA.inv();
cv::Vec3d trasl = Tco_cn.rowRange(0,3).col(3);
double dist = cv::norm(trasl);
cout << "GBA: KF " << pKF->mnId << " had been moved " << dist << " meters" << endl;
double desvX = 0;
double desvY = 0;
double desvZ = 0;
if(pKF->mbHasHessian)
{
cv::Mat hessianInv = pKF->mHessianPose.inv();
double covX = hessianInv.at<double>(3,3);
desvX = std::sqrt(covX);
double covY = hessianInv.at<double>(4,4);
desvY = std::sqrt(covY);
double covZ = hessianInv.at<double>(5,5);
desvZ = std::sqrt(covZ);
pKF->mbHasHessian = false;
}
if(dist > 1)
{
cout << "--To much distance correction: It has " << pKF->GetConnectedKeyFrames().size() << " connected KFs" << endl;
cout << "--It has " << pKF->GetCovisiblesByWeight(80).size() << " connected KF with 80 common matches or more" << endl;
cout << "--It has " << pKF->GetCovisiblesByWeight(50).size() << " connected KF with 50 common matches or more" << endl;
cout << "--It has " << pKF->GetCovisiblesByWeight(20).size() << " connected KF with 20 common matches or more" << endl;
cout << "--STD in meters(x, y, z): " << desvX << ", " << desvY << ", " << desvZ << endl;
string strNameFile = pKF->mNameFile;
cv::Mat imLeft = cv::imread(strNameFile, CV_LOAD_IMAGE_UNCHANGED);
cv::cvtColor(imLeft, imLeft, CV_GRAY2BGR);
vector<MapPoint*> vpMapPointsKF = pKF->GetMapPointMatches();
int num_MPs = 0;
for(int i=0; i<vpMapPointsKF.size(); ++i)
{
if(!vpMapPointsKF[i] || vpMapPointsKF[i]->isBad())
{
continue;
}
num_MPs += 1;
string strNumOBs = to_string(vpMapPointsKF[i]->Observations());
cv::circle(imLeft, pKF->mvKeys[i].pt, 2, cv::Scalar(0, 255, 0));
cv::putText(imLeft, strNumOBs, pKF->mvKeys[i].pt, CV_FONT_HERSHEY_DUPLEX, 1, cv::Scalar(255, 0, 0));
}
cout << "--It has " << num_MPs << " MPs matched in the map" << endl;
string namefile = "./test_GBA/GBA_" + to_string(nLoopKF) + "_KF" + to_string(pKF->mnId) +"_D" + to_string(dist) +".png";
cv::imwrite(namefile, imLeft);
}*/
if(pKF->bImu)
{
//cout << "-------Update inertial values" << endl;
pKF->mVwbBefGBA = pKF->GetVelocity();
if (pKF->mVwbGBA.empty())
Verbose::PrintMess("pKF->mVwbGBA is empty", Verbose::VERBOSITY_NORMAL);
assert(!pKF->mVwbGBA.empty());
pKF->SetVelocity(pKF->mVwbGBA);
pKF->SetNewBias(pKF->mBiasGBA);
}
lpKFtoCheck.pop_front();
}
//cout << "GBA: Correct MapPoints" << endl;
// Correct MapPoints
const vector<MapPoint*> vpMPs = pActiveMap->GetAllMapPoints();
// 遍历每一个地图点
for(size_t i=0; i<vpMPs.size(); i++)
{
MapPoint* pMP = vpMPs[i];
if(pMP->isBad())
continue;
// NOTICE 并不是所有的地图点都会直接参与到全局BA优化中,但是大部分的地图点需要根据全局BA优化后的结果来重新纠正自己的位姿
// 如果这个地图点直接参与到了全局BA优化的过程,那么就直接重新设置器位姿即可
if(pMP->mnBAGlobalForKF==nLoopKF)
{
// If optimized by Global BA, just update
pMP->SetWorldPos(pMP->mPosGBA);
}
else // 如故这个地图点并没有直接参与到全局BA优化的过程中,那么就使用器参考关键帧的新位姿来优化自己的位姿
{
// Update according to the correction of its reference keyframe
KeyFrame* pRefKF = pMP->GetReferenceKeyFrame();
// 说明这个关键帧在前面的过程中也没有因为“当前关键帧”得到全局BA优化
//? 可是,为什么会出现这种情况呢? 难道是因为这个地图点的参考关键帧设置成为了bad?
if(pRefKF->mnBAGlobalForKF!=nLoopKF)
continue;
if(pRefKF->mTcwBefGBA.empty())
continue;
// Map to non-corrected camera
cv::Mat Rcw = pRefKF->mTcwBefGBA.rowRange(0,3).colRange(0,3);
cv::Mat tcw = pRefKF->mTcwBefGBA.rowRange(0,3).col(3);
// 转换到其参考关键帧相机坐标系下的坐标
cv::Mat Xc = Rcw*pMP->GetWorldPos()+tcw;
// Backproject using corrected camera
// 然后使用已经纠正过的参考关键帧的位姿,再将该地图点变换到世界坐标系下
cv::Mat Twc = pRefKF->GetPoseInverse();
cv::Mat Rwc = Twc.rowRange(0,3).colRange(0,3);
cv::Mat twc = Twc.rowRange(0,3).col(3);
pMP->SetWorldPos(Rwc*Xc+twc);
}
}
pActiveMap->InformNewBigChange();
pActiveMap->IncreaseChangeIndex();
// TODO Check this update
// mpTracker->UpdateFrameIMU(1.0f, mpTracker->GetLastKeyFrame()->GetImuBias(), mpTracker->GetLastKeyFrame());
mpLocalMapper->Release();
Verbose::PrintMess("Map updated!", Verbose::VERBOSITY_NORMAL);
}
mbFinishedGBA = true;
mbRunningGBA = false;
}
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndMapUpdate = std::chrono::steady_clock::now();
double timeMapUpdate = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndMapUpdate - time_StartMapUpdate).count();
vTimeMapUpdate_ms.push_back(timeMapUpdate);
double timeGBA = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndMapUpdate - time_StartFGBA).count();
vTimeGBATotal_ms.push_back(timeGBA);
#endif
2020-12-01 11:58:17 +08:00
}
// 由外部线程调用,请求终止当前线程
void LoopClosing::RequestFinish()
{
unique_lock<mutex> lock(mMutexFinish);
// cout << "LC: Finish requested" << endl;
mbFinishRequested = true;
}
// 当前线程调用,查看是否有外部线程请求当前线程
bool LoopClosing::CheckFinish()
{
unique_lock<mutex> lock(mMutexFinish);
return mbFinishRequested;
}
// 有当前线程调用,执行完成该函数之后线程主函数退出,线程销毁
void LoopClosing::SetFinish()
{
unique_lock<mutex> lock(mMutexFinish);
mbFinished = true;
}
// 由外部线程调用,判断当前回环检测线程是否已经正确终止了
bool LoopClosing::isFinished()
{
unique_lock<mutex> lock(mMutexFinish);
return mbFinished;
}
} //namespace ORB_SLAM