update bug from Jason Gao

master
lao bailaobai 2023-02-17 23:59:55 +08:00
parent 18d1ebd345
commit 33f7ef16ed
2 changed files with 10 additions and 4 deletions

View File

@ -1217,11 +1217,16 @@ int LoopClosing::FindMatchesByProjection(
{ {
spCheckKFs.insert(vpKFs[j]); spCheckKFs.insert(vpKFs[j]);
++nInserted; ++nInserted;
// 改成这样
vpCovKFm.push_back(vpKFs[j]);
} }
++j; ++j;
} }
// 这里是原来的代码,这么写不太合适,会出现重复
// 所以下面的插入可以改成放在if里面
// 把每个帧的共视关键帧都加到窗口内 // 把每个帧的共视关键帧都加到窗口内
vpCovKFm.insert(vpCovKFm.end(), vpKFs.begin(), vpKFs.end()); // vpCovKFm.insert(vpCovKFm.end(), vpKFs.begin(), vpKFs.end()); // 已放上面
} }
} }
@ -2274,8 +2279,8 @@ void LoopClosing::MergeLocal()
// Essential graph 优化后可以重新开始局部建图了 // Essential graph 优化后可以重新开始局部建图了
mpLocalMapper->Release(); mpLocalMapper->Release();
// 全局的BA(永远不会执行) // 全局的BA后面一串的判断都为true
// 这里没有imu, 所以isImuInitialized一定是false, 此时地图融合Atlas至少2个地图所以第二个条件也一定是false // !pCurrentMap->isImuInitialized()一定是true
// Step 9 全局BA // Step 9 全局BA
if(bRelaunchBA && (!pCurrentMap->isImuInitialized() || (pCurrentMap->KeyFramesInMap()<200 && mpAtlas->CountMaps()==1))) if(bRelaunchBA && (!pCurrentMap->isImuInitialized() || (pCurrentMap->KeyFramesInMap()<200 && mpAtlas->CountMaps()==1)))
{ {

View File

@ -769,7 +769,8 @@ void MapPoint::PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP)
mBackupObservationsId1.clear(); mBackupObservationsId1.clear();
mBackupObservationsId2.clear(); mBackupObservationsId2.clear();
// Save the id and position in each KF who view it // Save the id and position in each KF who view it
for(std::map<KeyFrame*,std::tuple<int,int> >::const_iterator it = mObservations.begin(), end = mObservations.end(); it != end; ++it) for(std::map<KeyFrame*,std::tuple<int,int> >::const_iterator it = mObservations.begin(),
end = mObservations.end(); it != end; ++it)
{ {
KeyFrame* pKFi = it->first; KeyFrame* pKFi = it->first;
if(spKF.find(pKFi) != spKF.end()) if(spKF.find(pKFi) != spKF.end())