39 mbResetRequested(false), mbFinishRequested(false), mbFinished(true), mpMap(pMap),
40 mpKeyFrameDB(pDB), mpORBVocabulary(pVoc), mpMatchedKF(NULL), mLastLoopKFid(0), mbRunningGBA(false), mbFinishedGBA(true),
41 mbStopGBA(false), mpThreadGBA(NULL), mbFixScale(bFixScale), mnFullBAIdx(false)
84 std::this_thread::sleep_for(std::chrono::microseconds(5000));
127 for(
size_t i=0; i<vpConnectedKeyFrames.size(); i++)
129 KeyFrame* pKF = vpConnectedKeyFrames[i];
144 if(vpCandidateKFs.empty())
158 vector<ConsistentGroup> vCurrentConsistentGroups;
160 for(
size_t i=0, iend=vpCandidateKFs.size(); i<iend; i++)
162 KeyFrame* pCandidateKF = vpCandidateKFs[i];
165 spCandidateGroup.insert(pCandidateKF);
167 bool bEnoughConsistent =
false;
168 bool bConsistentForSomeGroup =
false;
173 bool bConsistent =
false;
174 for(set<KeyFrame*>::iterator sit=spCandidateGroup.begin(), send=spCandidateGroup.end(); sit!=send;sit++)
176 if(sPreviousGroup.count(*sit))
179 bConsistentForSomeGroup=
true;
187 int nCurrentConsistency = nPreviousConsistency + 1;
188 if(!vbConsistentGroup[iG])
191 vCurrentConsistentGroups.push_back(cg);
192 vbConsistentGroup[iG]=
true;
197 bEnoughConsistent=
true;
203 if(!bConsistentForSomeGroup)
206 vCurrentConsistentGroups.push_back(cg);
241 vector<Sim3Solver*> vpSim3Solvers;
242 vpSim3Solvers.resize(nInitialCandidates);
244 vector<vector<MapPoint*> > vvpMapPointMatches;
245 vvpMapPointMatches.resize(nInitialCandidates);
247 vector<bool> vbDiscarded;
248 vbDiscarded.resize(nInitialCandidates);
252 for(
int i=0; i<nInitialCandidates; i++)
261 vbDiscarded[i] =
true;
269 vbDiscarded[i] =
true;
276 vpSim3Solvers[i] = pSolver;
286 while(nCandidates>0 && !bMatch)
288 for(
int i=0; i<nInitialCandidates; i++)
296 vector<bool> vbInliers;
301 cv::Mat Scm = pSolver->
iterate(5,bNoMore,vbInliers,nInliers);
313 vector<MapPoint*> vpMapPointMatches(vvpMapPointMatches[i].size(), static_cast<MapPoint*>(NULL));
314 for(
size_t j=0, jend=vbInliers.size(); j<jend; j++)
317 vpMapPointMatches[j]=vvpMapPointMatches[i][j];
346 for(
int i=0; i<nInitialCandidates; i++)
356 for(vector<KeyFrame*>::iterator vit=vpLoopConnectedKFs.begin(); vit!=vpLoopConnectedKFs.end(); vit++)
360 for(
size_t i=0, iend=vpMapPoints.size(); i<iend; i++)
378 int nTotalMatches = 0;
385 if(nTotalMatches>=40)
387 for(
int i=0; i<nInitialCandidates; i++)
394 for(
int i=0; i<nInitialCandidates; i++)
404 cout <<
"Loop detected!" << endl;
428 std::this_thread::sleep_for(std::chrono::microseconds(1000));
455 cv::Mat Tic = Tiw*Twc;
456 cv::Mat Ric = Tic.rowRange(0,3).colRange(0,3);
457 cv::Mat tic = Tic.rowRange(0,3).col(3);
461 CorrectedSim3[pKFi]=g2oCorrectedSiw;
464 cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3);
465 cv::Mat tiw = Tiw.rowRange(0,3).col(3);
468 NonCorrectedSim3[pKFi]=g2oSiw;
472 for(KeyFrameAndPose::iterator mit=CorrectedSim3.begin(), mend=CorrectedSim3.end(); mit!=mend; mit++)
478 g2o::Sim3 g2oSiw =NonCorrectedSim3[pKFi];
481 for(
size_t iMP=0, endMPi = vpMPsi.size(); iMP<endMPi; iMP++)
494 Eigen::Matrix<double,3,1> eigCorrectedP3Dw = g2oCorrectedSwi.
map(g2oSiw.
map(eigP3Dw));
504 Eigen::Matrix3d eigR = g2oCorrectedSiw.
rotation().toRotationMatrix();
505 Eigen::Vector3d eigt = g2oCorrectedSiw.
translation();
506 double s = g2oCorrectedSiw.
scale();
546 map<KeyFrame*, set<KeyFrame*> > LoopConnections;
556 for(vector<KeyFrame*>::iterator vit_prev=vpPreviousNeighbors.begin(), vend_prev=vpPreviousNeighbors.end(); vit_prev!=vend_prev; vit_prev++)
558 LoopConnections[pKFi].erase(*vit_prev);
562 LoopConnections[pKFi].erase(*vit2);
591 for(KeyFrameAndPose::const_iterator mit=CorrectedPosesMap.begin(), mend=CorrectedPosesMap.end(); mit!=mend;mit++)
604 for(
int i=0; i<nLP;i++)
606 MapPoint* pRep = vpReplacePoints[i];
630 std::this_thread::sleep_for(std::chrono::microseconds(5000));
647 cout <<
"Starting Global Bundle Adjustment" << endl;
663 cout <<
"Global Bundle Adjustment finished" << endl;
664 cout <<
"Updating map ..." << endl;
670 std::this_thread::sleep_for(std::chrono::microseconds(1000));
679 while(!lpKFtoCheck.empty())
681 KeyFrame* pKF = lpKFtoCheck.front();
682 const set<KeyFrame*> sChilds = pKF->
GetChilds();
684 for(set<KeyFrame*>::const_iterator sit=sChilds.begin();sit!=sChilds.end();sit++)
689 cv::Mat Tchildc = pChild->
GetPose()*Twc;
694 lpKFtoCheck.push_back(pChild);
699 lpKFtoCheck.pop_front();
705 for(
size_t i=0; i<vpMPs.size(); i++)
726 cv::Mat Rcw = pRefKF->
mTcwBefGBA.rowRange(0,3).colRange(0,3);
727 cv::Mat tcw = pRefKF->
mTcwBefGBA.rowRange(0,3).col(3);
732 cv::Mat Rwc = Twc.rowRange(0,3).colRange(0,3);
733 cv::Mat twc = Twc.rowRange(0,3).col(3);
743 cout <<
"Map updated!" << endl;
double score(const BowVector &a, const BowVector &b) const
static Eigen::Matrix< double, 3, 3 > toMatrix3d(const cv::Mat &cvMat3)
static int OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale)
map< KeyFrame *, g2o::Sim3, std::less< KeyFrame * >, Eigen::aligned_allocator< std::pair< KeyFrame *const, g2o::Sim3 > > > KeyFrameAndPose
std::vector< KeyFrame * > mvpCurrentConnectedKFs
long unsigned int mnBAGlobalForKF
void InformNewBigChange()
std::set< KeyFrame * > GetConnectedKeyFrames()
long unsigned int mnLoopPointForKF
cv::Mat iterate(int nIterations, bool &bNoMore, std::vector< bool > &vbInliers, int &nInliers)
LoopClosing(Map *pMap, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale)
int SearchByBoW(KeyFrame *pKF, Frame &F, std::vector< MapPoint * > &vpMapPointMatches)
void AddMapPoint(MapPoint *pMP, const size_t &idx)
void InsertKeyFrame(KeyFrame *pKF)
int SearchBySim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th)
float mnCovisibilityConsistencyTh
long unsigned int mnCorrectedByKF
static cv::Mat toCvSE3(const Eigen::Matrix< double, 3, 3 > &R, const Eigen::Matrix< double, 3, 1 > &t)
std::mutex mMutexMapUpdate
ORBVocabulary * mpORBVocabulary
LocalMapping * mpLocalMapper
void SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap)
long unsigned int mnBAGlobalForKF
std::vector< MapPoint * > GetMapPointMatches()
void SetLocalMapper(LocalMapping *pLocalMapper)
KeyFrameDatabase * mpKeyFrameDB
void AddObservation(KeyFrame *pKF, size_t idx)
static cv::Mat toCvMat(const g2o::SE3Quat &SE3)
const Vector3d & translation() const
long unsigned int mLastLoopKFid
void UpdateNormalAndDepth()
std::vector< MapPoint * > GetAllMapPoints()
cv::Mat GetEstimatedRotation()
pair< set< KeyFrame * >, int > ConsistentGroup
std::vector< KeyFrame * > mvpEnoughConsistentCandidates
vector< KeyFrame * > mvpKeyFrameOrigins
static void GlobalBundleAdjustemnt(Map *pMap, int nIterations=5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, const bool bRobust=true)
void SetTracker(Tracking *pTracker)
static void OptimizeEssentialGraph(Map *pMap, KeyFrame *pLoopKF, KeyFrame *pCurKF, const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, const LoopClosing::KeyFrameAndPose &CorrectedSim3, const map< KeyFrame *, set< KeyFrame * > > &LoopConnections, const bool &bFixScale)
float GetEstimatedScale()
KeyFrame * GetReferenceKeyFrame()
static Eigen::Matrix< double, 3, 1 > toVector3d(const cv::Mat &cvVector)
void Replace(MapPoint *pMP)
void SetWorldPos(const cv::Mat &Pos)
void RunGlobalBundleAdjustment(unsigned long nLoopKF)
Vector of words to represent images.
int SearchByProjection(Frame &F, const std::vector< MapPoint * > &vpMapPoints, const float th=3)
std::list< KeyFrame * > mlpLoopKeyFrameQueue
MapPoint * GetMapPoint(const size_t &idx)
void SetPose(const cv::Mat &Tcw)
std::vector< KeyFrame * > GetVectorCovisibleKeyFrames()
void AddLoopEdge(KeyFrame *pKF)
void SetRansacParameters(double probability=0.99, int minInliers=6, int maxIterations=300)
const double & scale() const
std::set< KeyFrame * > GetChilds()
std::vector< KeyFrame * > DetectLoopCandidates(KeyFrame *pKF, float minScore)
std::mutex mMutexLoopQueue
Vector3d map(const Vector3d &xyz) const
long unsigned int mnCorrectedReference
void ComputeDistinctiveDescriptors()
std::vector< MapPoint * > mvpLoopMapPoints
std::thread * mpThreadGBA
std::vector< MapPoint * > mvpCurrentMatchedPoints
const Quaterniond & rotation() const
cv::Mat GetEstimatedTranslation()
std::vector< ConsistentGroup > mvConsistentGroups
int Fuse(KeyFrame *pKF, const vector< MapPoint * > &vpMapPoints, const float th=3.0)