LoopClosing.cc
Go to the documentation of this file.
1 
21 #include "LoopClosing.h"
22 
23 #include "Sim3Solver.h"
24 
25 #include "Converter.h"
26 
27 #include "Optimizer.h"
28 
29 #include "ORBmatcher.h"
30 
31 #include<mutex>
32 #include<thread>
33 
34 
35 namespace ORB_SLAM2
36 {
37 
38 LoopClosing::LoopClosing(Map *pMap, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale):
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)
42 {
44 }
45 
47 {
48  mpTracker=pTracker;
49 }
50 
52 {
53  mpLocalMapper=pLocalMapper;
54 }
55 
56 
58 {
59  mbFinished =false;
60 
61  while(1)
62  {
63  // Check if there are keyframes in the queue
64  if(CheckNewKeyFrames())
65  {
66  // Detect loop candidates and check covisibility consistency
67  if(DetectLoop())
68  {
69  // Compute similarity transformation [sR|t]
70  // In the stereo/RGBD case s=1
71  if(ComputeSim3())
72  {
73  // Perform loop fusion and pose graph optimization
74  CorrectLoop();
75  }
76  }
77  }
78 
80 
81  if(CheckFinish())
82  break;
83 
84  std::this_thread::sleep_for(std::chrono::microseconds(5000));
85  }
86 
87  SetFinish();
88 }
89 
91 {
92  unique_lock<mutex> lock(mMutexLoopQueue);
93  if(pKF->mnId!=0)
94  mlpLoopKeyFrameQueue.push_back(pKF);
95 }
96 
98 {
99  unique_lock<mutex> lock(mMutexLoopQueue);
100  return(!mlpLoopKeyFrameQueue.empty());
101 }
102 
104 {
105  {
106  unique_lock<mutex> lock(mMutexLoopQueue);
108  mlpLoopKeyFrameQueue.pop_front();
109  // Avoid that a keyframe can be erased while it is being process by this thread
111  }
112 
113  //If the map contains less than 10 KF or less than 10 KF have passed from last loop detection
115  {
118  return false;
119  }
120 
121  // Compute reference BoW similarity score
122  // This is the lowest score to a connected keyframe in the covisibility graph
123  // We will impose loop candidates to have a higher similarity than this
124  const vector<KeyFrame*> vpConnectedKeyFrames = mpCurrentKF->GetVectorCovisibleKeyFrames();
125  const DBoW2::BowVector &CurrentBowVec = mpCurrentKF->mBowVec;
126  float minScore = 1;
127  for(size_t i=0; i<vpConnectedKeyFrames.size(); i++)
128  {
129  KeyFrame* pKF = vpConnectedKeyFrames[i];
130  if(pKF->isBad())
131  continue;
132  const DBoW2::BowVector &BowVec = pKF->mBowVec;
133 
134  float score = mpORBVocabulary->score(CurrentBowVec, BowVec);
135 
136  if(score<minScore)
137  minScore = score;
138  }
139 
140  // Query the database imposing the minimum score
141  vector<KeyFrame*> vpCandidateKFs = mpKeyFrameDB->DetectLoopCandidates(mpCurrentKF, minScore);
142 
143  // If there are no loop candidates, just add new keyframe and return false
144  if(vpCandidateKFs.empty())
145  {
147  mvConsistentGroups.clear();
149  return false;
150  }
151 
152  // For each loop candidate check consistency with previous loop candidates
153  // Each candidate expands a covisibility group (keyframes connected to the loop candidate in the covisibility graph)
154  // A group is consistent with a previous group if they share at least a keyframe
155  // We must detect a consistent loop in several consecutive keyframes to accept it
157 
158  vector<ConsistentGroup> vCurrentConsistentGroups;
159  vector<bool> vbConsistentGroup(mvConsistentGroups.size(),false);
160  for(size_t i=0, iend=vpCandidateKFs.size(); i<iend; i++)
161  {
162  KeyFrame* pCandidateKF = vpCandidateKFs[i];
163 
164  set<KeyFrame*> spCandidateGroup = pCandidateKF->GetConnectedKeyFrames();
165  spCandidateGroup.insert(pCandidateKF);
166 
167  bool bEnoughConsistent = false;
168  bool bConsistentForSomeGroup = false;
169  for(size_t iG=0, iendG=mvConsistentGroups.size(); iG<iendG; iG++)
170  {
171  set<KeyFrame*> sPreviousGroup = mvConsistentGroups[iG].first;
172 
173  bool bConsistent = false;
174  for(set<KeyFrame*>::iterator sit=spCandidateGroup.begin(), send=spCandidateGroup.end(); sit!=send;sit++)
175  {
176  if(sPreviousGroup.count(*sit))
177  {
178  bConsistent=true;
179  bConsistentForSomeGroup=true;
180  break;
181  }
182  }
183 
184  if(bConsistent)
185  {
186  int nPreviousConsistency = mvConsistentGroups[iG].second;
187  int nCurrentConsistency = nPreviousConsistency + 1;
188  if(!vbConsistentGroup[iG])
189  {
190  ConsistentGroup cg = make_pair(spCandidateGroup,nCurrentConsistency);
191  vCurrentConsistentGroups.push_back(cg);
192  vbConsistentGroup[iG]=true; //this avoid to include the same group more than once
193  }
194  if(nCurrentConsistency>=mnCovisibilityConsistencyTh && !bEnoughConsistent)
195  {
196  mvpEnoughConsistentCandidates.push_back(pCandidateKF);
197  bEnoughConsistent=true; //this avoid to insert the same candidate more than once
198  }
199  }
200  }
201 
202  // If the group is not consistent with any previous group insert with consistency counter set to zero
203  if(!bConsistentForSomeGroup)
204  {
205  ConsistentGroup cg = make_pair(spCandidateGroup,0);
206  vCurrentConsistentGroups.push_back(cg);
207  }
208  }
209 
210  // Update Covisibility Consistent Groups
211  mvConsistentGroups = vCurrentConsistentGroups;
212 
213 
214  // Add Current Keyframe to database
216 
218  {
220  return false;
221  }
222  else
223  {
224  return true;
225  }
226 
228  return false;
229 }
230 
232 {
233  // For each consistent loop candidate we try to compute a Sim3
234 
235  const int nInitialCandidates = mvpEnoughConsistentCandidates.size();
236 
237  // We compute first ORB matches for each candidate
238  // If enough matches are found, we setup a Sim3Solver
239  ORBmatcher matcher(0.75,true);
240 
241  vector<Sim3Solver*> vpSim3Solvers;
242  vpSim3Solvers.resize(nInitialCandidates);
243 
244  vector<vector<MapPoint*> > vvpMapPointMatches;
245  vvpMapPointMatches.resize(nInitialCandidates);
246 
247  vector<bool> vbDiscarded;
248  vbDiscarded.resize(nInitialCandidates);
249 
250  int nCandidates=0; //candidates with enough matches
251 
252  for(int i=0; i<nInitialCandidates; i++)
253  {
255 
256  // avoid that local mapping erase it while it is being processed in this thread
257  pKF->SetNotErase();
258 
259  if(pKF->isBad())
260  {
261  vbDiscarded[i] = true;
262  continue;
263  }
264 
265  int nmatches = matcher.SearchByBoW(mpCurrentKF,pKF,vvpMapPointMatches[i]);
266 
267  if(nmatches<20)
268  {
269  vbDiscarded[i] = true;
270  continue;
271  }
272  else
273  {
274  Sim3Solver* pSolver = new Sim3Solver(mpCurrentKF,pKF,vvpMapPointMatches[i],mbFixScale);
275  pSolver->SetRansacParameters(0.99,20,300);
276  vpSim3Solvers[i] = pSolver;
277  }
278 
279  nCandidates++;
280  }
281 
282  bool bMatch = false;
283 
284  // Perform alternatively RANSAC iterations for each candidate
285  // until one is succesful or all fail
286  while(nCandidates>0 && !bMatch)
287  {
288  for(int i=0; i<nInitialCandidates; i++)
289  {
290  if(vbDiscarded[i])
291  continue;
292 
294 
295  // Perform 5 Ransac Iterations
296  vector<bool> vbInliers;
297  int nInliers;
298  bool bNoMore;
299 
300  Sim3Solver* pSolver = vpSim3Solvers[i];
301  cv::Mat Scm = pSolver->iterate(5,bNoMore,vbInliers,nInliers);
302 
303  // If Ransac reachs max. iterations discard keyframe
304  if(bNoMore)
305  {
306  vbDiscarded[i]=true;
307  nCandidates--;
308  }
309 
310  // If RANSAC returns a Sim3, perform a guided matching and optimize with all correspondences
311  if(!Scm.empty())
312  {
313  vector<MapPoint*> vpMapPointMatches(vvpMapPointMatches[i].size(), static_cast<MapPoint*>(NULL));
314  for(size_t j=0, jend=vbInliers.size(); j<jend; j++)
315  {
316  if(vbInliers[j])
317  vpMapPointMatches[j]=vvpMapPointMatches[i][j];
318  }
319 
320  cv::Mat R = pSolver->GetEstimatedRotation();
321  cv::Mat t = pSolver->GetEstimatedTranslation();
322  const float s = pSolver->GetEstimatedScale();
323  matcher.SearchBySim3(mpCurrentKF,pKF,vpMapPointMatches,s,R,t,7.5);
324 
326  const int nInliers = Optimizer::OptimizeSim3(mpCurrentKF, pKF, vpMapPointMatches, gScm, 10, mbFixScale);
327 
328  // If optimization is succesful stop ransacs and continue
329  if(nInliers>=20)
330  {
331  bMatch = true;
332  mpMatchedKF = pKF;
334  mg2oScw = gScm*gSmw;
336 
337  mvpCurrentMatchedPoints = vpMapPointMatches;
338  break;
339  }
340  }
341  }
342  }
343 
344  if(!bMatch)
345  {
346  for(int i=0; i<nInitialCandidates; i++)
347  mvpEnoughConsistentCandidates[i]->SetErase();
349  return false;
350  }
351 
352  // Retrieve MapPoints seen in Loop Keyframe and neighbors
353  vector<KeyFrame*> vpLoopConnectedKFs = mpMatchedKF->GetVectorCovisibleKeyFrames();
354  vpLoopConnectedKFs.push_back(mpMatchedKF);
355  mvpLoopMapPoints.clear();
356  for(vector<KeyFrame*>::iterator vit=vpLoopConnectedKFs.begin(); vit!=vpLoopConnectedKFs.end(); vit++)
357  {
358  KeyFrame* pKF = *vit;
359  vector<MapPoint*> vpMapPoints = pKF->GetMapPointMatches();
360  for(size_t i=0, iend=vpMapPoints.size(); i<iend; i++)
361  {
362  MapPoint* pMP = vpMapPoints[i];
363  if(pMP)
364  {
365  if(!pMP->isBad() && pMP->mnLoopPointForKF!=mpCurrentKF->mnId)
366  {
367  mvpLoopMapPoints.push_back(pMP);
369  }
370  }
371  }
372  }
373 
374  // Find more matches projecting with the computed Sim3
376 
377  // If enough matches accept Loop
378  int nTotalMatches = 0;
379  for(size_t i=0; i<mvpCurrentMatchedPoints.size(); i++)
380  {
382  nTotalMatches++;
383  }
384 
385  if(nTotalMatches>=40)
386  {
387  for(int i=0; i<nInitialCandidates; i++)
389  mvpEnoughConsistentCandidates[i]->SetErase();
390  return true;
391  }
392  else
393  {
394  for(int i=0; i<nInitialCandidates; i++)
395  mvpEnoughConsistentCandidates[i]->SetErase();
397  return false;
398  }
399 
400 }
401 
403 {
404  cout << "Loop detected!" << endl;
405 
406  // Send a stop signal to Local Mapping
407  // Avoid new keyframes are inserted while correcting the loop
409 
410  // If a Global Bundle Adjustment is running, abort it
411  if(isRunningGBA())
412  {
413  unique_lock<mutex> lock(mMutexGBA);
414  mbStopGBA = true;
415 
416  mnFullBAIdx = true;
417 
418  if(mpThreadGBA)
419  {
420  mpThreadGBA->detach();
421  delete mpThreadGBA;
422  }
423  }
424 
425  // Wait until Local Mapping has effectively stopped
426  while(!mpLocalMapper->isStopped())
427  {
428  std::this_thread::sleep_for(std::chrono::microseconds(1000));
429  }
430 
431  // Ensure current keyframe is updated
433 
434  // Retrive keyframes connected to the current keyframe and compute corrected Sim3 pose by propagation
437 
438  KeyFrameAndPose CorrectedSim3, NonCorrectedSim3;
439  CorrectedSim3[mpCurrentKF]=mg2oScw;
440  cv::Mat Twc = mpCurrentKF->GetPoseInverse();
441 
442 
443  {
444  // Get Map Mutex
445  unique_lock<mutex> lock(mpMap->mMutexMapUpdate);
446 
447  for(vector<KeyFrame*>::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++)
448  {
449  KeyFrame* pKFi = *vit;
450 
451  cv::Mat Tiw = pKFi->GetPose();
452 
453  if(pKFi!=mpCurrentKF)
454  {
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);
459  g2o::Sim3 g2oCorrectedSiw = g2oSic*mg2oScw;
460  //Pose corrected with the Sim3 of the loop closure
461  CorrectedSim3[pKFi]=g2oCorrectedSiw;
462  }
463 
464  cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3);
465  cv::Mat tiw = Tiw.rowRange(0,3).col(3);
467  //Pose without correction
468  NonCorrectedSim3[pKFi]=g2oSiw;
469  }
470 
471  // Correct all MapPoints obsrved by current keyframe and neighbors, so that they align with the other side of the loop
472  for(KeyFrameAndPose::iterator mit=CorrectedSim3.begin(), mend=CorrectedSim3.end(); mit!=mend; mit++)
473  {
474  KeyFrame* pKFi = mit->first;
475  g2o::Sim3 g2oCorrectedSiw = mit->second;
476  g2o::Sim3 g2oCorrectedSwi = g2oCorrectedSiw.inverse();
477 
478  g2o::Sim3 g2oSiw =NonCorrectedSim3[pKFi];
479 
480  vector<MapPoint*> vpMPsi = pKFi->GetMapPointMatches();
481  for(size_t iMP=0, endMPi = vpMPsi.size(); iMP<endMPi; iMP++)
482  {
483  MapPoint* pMPi = vpMPsi[iMP];
484  if(!pMPi)
485  continue;
486  if(pMPi->isBad())
487  continue;
488  if(pMPi->mnCorrectedByKF==mpCurrentKF->mnId)
489  continue;
490 
491  // Project with non-corrected pose and project back with corrected pose
492  cv::Mat P3Dw = pMPi->GetWorldPos();
493  Eigen::Matrix<double,3,1> eigP3Dw = Converter::toVector3d(P3Dw);
494  Eigen::Matrix<double,3,1> eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oSiw.map(eigP3Dw));
495 
496  cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw);
497  pMPi->SetWorldPos(cvCorrectedP3Dw);
499  pMPi->mnCorrectedReference = pKFi->mnId;
500  pMPi->UpdateNormalAndDepth();
501  }
502 
503  // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation)
504  Eigen::Matrix3d eigR = g2oCorrectedSiw.rotation().toRotationMatrix();
505  Eigen::Vector3d eigt = g2oCorrectedSiw.translation();
506  double s = g2oCorrectedSiw.scale();
507 
508  eigt *=(1./s); //[R t/s;0 1]
509 
510  cv::Mat correctedTiw = Converter::toCvSE3(eigR,eigt);
511 
512  pKFi->SetPose(correctedTiw);
513 
514  // Make sure connections are updated
515  pKFi->UpdateConnections();
516  }
517 
518  // Start Loop Fusion
519  // Update matched map points and replace if duplicated
520  for(size_t i=0; i<mvpCurrentMatchedPoints.size(); i++)
521  {
523  {
524  MapPoint* pLoopMP = mvpCurrentMatchedPoints[i];
525  MapPoint* pCurMP = mpCurrentKF->GetMapPoint(i);
526  if(pCurMP)
527  pCurMP->Replace(pLoopMP);
528  else
529  {
530  mpCurrentKF->AddMapPoint(pLoopMP,i);
531  pLoopMP->AddObservation(mpCurrentKF,i);
533  }
534  }
535  }
536 
537  }
538 
539  // Project MapPoints observed in the neighborhood of the loop keyframe
540  // into the current keyframe and neighbors using corrected poses.
541  // Fuse duplications.
542  SearchAndFuse(CorrectedSim3);
543 
544 
545  // After the MapPoint fusion, new links in the covisibility graph will appear attaching both sides of the loop
546  map<KeyFrame*, set<KeyFrame*> > LoopConnections;
547 
548  for(vector<KeyFrame*>::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++)
549  {
550  KeyFrame* pKFi = *vit;
551  vector<KeyFrame*> vpPreviousNeighbors = pKFi->GetVectorCovisibleKeyFrames();
552 
553  // Update connections. Detect new links.
554  pKFi->UpdateConnections();
555  LoopConnections[pKFi]=pKFi->GetConnectedKeyFrames();
556  for(vector<KeyFrame*>::iterator vit_prev=vpPreviousNeighbors.begin(), vend_prev=vpPreviousNeighbors.end(); vit_prev!=vend_prev; vit_prev++)
557  {
558  LoopConnections[pKFi].erase(*vit_prev);
559  }
560  for(vector<KeyFrame*>::iterator vit2=mvpCurrentConnectedKFs.begin(), vend2=mvpCurrentConnectedKFs.end(); vit2!=vend2; vit2++)
561  {
562  LoopConnections[pKFi].erase(*vit2);
563  }
564  }
565 
566  // Optimize graph
567  Optimizer::OptimizeEssentialGraph(mpMap, mpMatchedKF, mpCurrentKF, NonCorrectedSim3, CorrectedSim3, LoopConnections, mbFixScale);
568 
570 
571  // Add loop edge
574 
575  // Launch a new thread to perform Global Bundle Adjustment
576  mbRunningGBA = true;
577  mbFinishedGBA = false;
578  mbStopGBA = false;
580 
581  // Loop closed. Release Local Mapping.
583 
585 }
586 
587 void LoopClosing::SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap)
588 {
589  ORBmatcher matcher(0.8);
590 
591  for(KeyFrameAndPose::const_iterator mit=CorrectedPosesMap.begin(), mend=CorrectedPosesMap.end(); mit!=mend;mit++)
592  {
593  KeyFrame* pKF = mit->first;
594 
595  g2o::Sim3 g2oScw = mit->second;
596  cv::Mat cvScw = Converter::toCvMat(g2oScw);
597 
598  vector<MapPoint*> vpReplacePoints(mvpLoopMapPoints.size(),static_cast<MapPoint*>(NULL));
599  matcher.Fuse(pKF,cvScw,mvpLoopMapPoints,4,vpReplacePoints);
600 
601  // Get Map Mutex
602  unique_lock<mutex> lock(mpMap->mMutexMapUpdate);
603  const int nLP = mvpLoopMapPoints.size();
604  for(int i=0; i<nLP;i++)
605  {
606  MapPoint* pRep = vpReplacePoints[i];
607  if(pRep)
608  {
609  pRep->Replace(mvpLoopMapPoints[i]);
610  }
611  }
612  }
613 }
614 
615 
617 {
618  {
619  unique_lock<mutex> lock(mMutexReset);
620  mbResetRequested = true;
621  }
622 
623  while(1)
624  {
625  {
626  unique_lock<mutex> lock2(mMutexReset);
627  if(!mbResetRequested)
628  break;
629  }
630  std::this_thread::sleep_for(std::chrono::microseconds(5000));
631  }
632 }
633 
635 {
636  unique_lock<mutex> lock(mMutexReset);
637  if(mbResetRequested)
638  {
639  mlpLoopKeyFrameQueue.clear();
640  mLastLoopKFid=0;
641  mbResetRequested=false;
642  }
643 }
644 
645 void LoopClosing::RunGlobalBundleAdjustment(unsigned long nLoopKF)
646 {
647  cout << "Starting Global Bundle Adjustment" << endl;
648 
649  bool idx = mnFullBAIdx;
651 
652  // Update all MapPoints and KeyFrames
653  // Local Mapping was active during BA, that means that there might be new keyframes
654  // not included in the Global BA and they are not consistent with the updated map.
655  // We need to propagate the correction through the spanning tree
656  {
657  unique_lock<mutex> lock(mMutexGBA);
658  if(idx!=mnFullBAIdx)
659  return;
660 
661  if(!mbStopGBA)
662  {
663  cout << "Global Bundle Adjustment finished" << endl;
664  cout << "Updating map ..." << endl;
666  // Wait until Local Mapping has effectively stopped
667 
669  {
670  std::this_thread::sleep_for(std::chrono::microseconds(1000));
671  }
672 
673  // Get Map Mutex
674  unique_lock<mutex> lock(mpMap->mMutexMapUpdate);
675 
676  // Correct keyframes starting at map first keyframe
677  list<KeyFrame*> lpKFtoCheck(mpMap->mvpKeyFrameOrigins.begin(),mpMap->mvpKeyFrameOrigins.end());
678 
679  while(!lpKFtoCheck.empty())
680  {
681  KeyFrame* pKF = lpKFtoCheck.front();
682  const set<KeyFrame*> sChilds = pKF->GetChilds();
683  cv::Mat Twc = pKF->GetPoseInverse();
684  for(set<KeyFrame*>::const_iterator sit=sChilds.begin();sit!=sChilds.end();sit++)
685  {
686  KeyFrame* pChild = *sit;
687  if(pChild->mnBAGlobalForKF!=nLoopKF)
688  {
689  cv::Mat Tchildc = pChild->GetPose()*Twc;
690  pChild->mTcwGBA = Tchildc*pKF->mTcwGBA;//*Tcorc*pKF->mTcwGBA;
691  pChild->mnBAGlobalForKF=nLoopKF;
692 
693  }
694  lpKFtoCheck.push_back(pChild);
695  }
696 
697  pKF->mTcwBefGBA = pKF->GetPose();
698  pKF->SetPose(pKF->mTcwGBA);
699  lpKFtoCheck.pop_front();
700  }
701 
702  // Correct MapPoints
703  const vector<MapPoint*> vpMPs = mpMap->GetAllMapPoints();
704 
705  for(size_t i=0; i<vpMPs.size(); i++)
706  {
707  MapPoint* pMP = vpMPs[i];
708 
709  if(pMP->isBad())
710  continue;
711 
712  if(pMP->mnBAGlobalForKF==nLoopKF)
713  {
714  // If optimized by Global BA, just update
715  pMP->SetWorldPos(pMP->mPosGBA);
716  }
717  else
718  {
719  // Update according to the correction of its reference keyframe
720  KeyFrame* pRefKF = pMP->GetReferenceKeyFrame();
721 
722  if(pRefKF->mnBAGlobalForKF!=nLoopKF)
723  continue;
724 
725  // Map to non-corrected camera
726  cv::Mat Rcw = pRefKF->mTcwBefGBA.rowRange(0,3).colRange(0,3);
727  cv::Mat tcw = pRefKF->mTcwBefGBA.rowRange(0,3).col(3);
728  cv::Mat Xc = Rcw*pMP->GetWorldPos()+tcw;
729 
730  // Backproject using corrected camera
731  cv::Mat Twc = pRefKF->GetPoseInverse();
732  cv::Mat Rwc = Twc.rowRange(0,3).colRange(0,3);
733  cv::Mat twc = Twc.rowRange(0,3).col(3);
734 
735  pMP->SetWorldPos(Rwc*Xc+twc);
736  }
737  }
738 
740 
742 
743  cout << "Map updated!" << endl;
744  }
745 
746  mbFinishedGBA = true;
747  mbRunningGBA = false;
748  }
749 }
750 
752 {
753  unique_lock<mutex> lock(mMutexFinish);
754  mbFinishRequested = true;
755 }
756 
758 {
759  unique_lock<mutex> lock(mMutexFinish);
760  return mbFinishRequested;
761 }
762 
764 {
765  unique_lock<mutex> lock(mMutexFinish);
766  mbFinished = true;
767 }
768 
770 {
771  unique_lock<mutex> lock(mMutexFinish);
772  return mbFinished;
773 }
774 
775 
776 } //namespace ORB_SLAM
double score(const BowVector &a, const BowVector &b) const
Definition: sim3.h:41
cv::Mat GetPoseInverse()
Definition: KeyFrame.cc:92
cv::Mat GetRotation()
Definition: KeyFrame.cc:111
static Eigen::Matrix< double, 3, 3 > toMatrix3d(const cv::Mat &cvMat3)
Definition: Converter.cc:126
static int OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale)
Definition: Optimizer.cc:1046
map< KeyFrame *, g2o::Sim3, std::less< KeyFrame * >, Eigen::aligned_allocator< std::pair< KeyFrame *const, g2o::Sim3 > > > KeyFrameAndPose
Definition: LoopClosing.h:50
std::vector< KeyFrame * > mvpCurrentConnectedKFs
Definition: LoopClosing.h:127
long unsigned int mnBAGlobalForKF
Definition: MapPoint.h:111
void InformNewBigChange()
Definition: Map.cc:70
std::set< KeyFrame * > GetConnectedKeyFrames()
Definition: KeyFrame.cc:159
long unsigned int mnLoopPointForKF
Definition: MapPoint.h:107
cv::Mat iterate(int nIterations, bool &bNoMore, std::vector< bool > &vbInliers, int &nInliers)
Definition: Sim3Solver.cc:140
LoopClosing(Map *pMap, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale)
Definition: LoopClosing.cc:38
int SearchByBoW(KeyFrame *pKF, Frame &F, std::vector< MapPoint * > &vpMapPointMatches)
cv::Mat GetPose()
Definition: KeyFrame.cc:86
void AddMapPoint(MapPoint *pMP, const size_t &idx)
Definition: KeyFrame.cc:210
void InsertKeyFrame(KeyFrame *pKF)
Definition: LoopClosing.cc:90
int SearchBySim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th)
Definition: ORBmatcher.cc:1102
long unsigned int mnCorrectedByKF
Definition: MapPoint.h:108
static cv::Mat toCvSE3(const Eigen::Matrix< double, 3, 3 > &R, const Eigen::Matrix< double, 3, 1 > &t)
Definition: Converter.cc:92
std::mutex mMutexMapUpdate
Definition: Map.h:65
XmlRpcServer s
ORBVocabulary * mpORBVocabulary
Definition: LoopClosing.h:111
LocalMapping * mpLocalMapper
Definition: LoopClosing.h:113
void SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap)
Definition: LoopClosing.cc:587
cv::Mat GetWorldPos()
Definition: MapPoint.cc:80
long unsigned int mnBAGlobalForKF
Definition: KeyFrame.h:155
std::vector< MapPoint * > GetMapPointMatches()
Definition: KeyFrame.cc:277
Sim3 inverse() const
Definition: sim3.h:233
void SetLocalMapper(LocalMapping *pLocalMapper)
Definition: LoopClosing.cc:51
KeyFrameDatabase * mpKeyFrameDB
Definition: LoopClosing.h:110
void AddObservation(KeyFrame *pKF, size_t idx)
Definition: MapPoint.cc:98
static cv::Mat toCvMat(const g2o::SE3Quat &SE3)
Definition: Converter.cc:49
const Vector3d & translation() const
Definition: sim3.h:280
long unsigned int mLastLoopKFid
Definition: LoopClosing.h:133
void UpdateNormalAndDepth()
Definition: MapPoint.cc:330
std::vector< MapPoint * > GetAllMapPoints()
Definition: Map.cc:88
cv::Mat GetEstimatedRotation()
Definition: Sim3Solver.cc:367
pair< set< KeyFrame * >, int > ConsistentGroup
Definition: LoopClosing.h:48
std::vector< KeyFrame * > mvpEnoughConsistentCandidates
Definition: LoopClosing.h:126
vector< KeyFrame * > mvpKeyFrameOrigins
Definition: Map.h:63
static void GlobalBundleAdjustemnt(Map *pMap, int nIterations=5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, const bool bRobust=true)
Definition: Optimizer.cc:41
void SetTracker(Tracking *pTracker)
Definition: LoopClosing.cc:46
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)
Definition: Optimizer.cc:781
DBoW2::BowVector mBowVec
Definition: KeyFrame.h:171
cv::Mat mTcwBefGBA
Definition: KeyFrame.h:154
cv::Mat GetTranslation()
Definition: KeyFrame.cc:117
KeyFrame * GetReferenceKeyFrame()
Definition: MapPoint.cc:92
static Eigen::Matrix< double, 3, 1 > toVector3d(const cv::Mat &cvVector)
Definition: Converter.cc:110
void Replace(MapPoint *pMP)
Definition: MapPoint.cc:177
void SetWorldPos(const cv::Mat &Pos)
Definition: MapPoint.cc:73
void RunGlobalBundleAdjustment(unsigned long nLoopKF)
Definition: LoopClosing.cc:645
Vector of words to represent images.
Definition: BowVector.h:56
int SearchByProjection(Frame &F, const std::vector< MapPoint * > &vpMapPoints, const float th=3)
std::list< KeyFrame * > mlpLoopKeyFrameQueue
Definition: LoopClosing.h:115
MapPoint * GetMapPoint(const size_t &idx)
Definition: KeyFrame.cc:283
void SetPose(const cv::Mat &Tcw)
Definition: KeyFrame.cc:70
std::vector< KeyFrame * > GetVectorCovisibleKeyFrames()
Definition: KeyFrame.cc:168
void AddLoopEdge(KeyFrame *pKF)
Definition: KeyFrame.cc:418
void SetRansacParameters(double probability=0.99, int minInliers=6, int maxIterations=300)
Definition: Sim3Solver.cc:114
const double & scale() const
Definition: sim3.h:288
std::set< KeyFrame * > GetChilds()
Definition: KeyFrame.cc:400
std::vector< KeyFrame * > DetectLoopCandidates(KeyFrame *pKF, float minScore)
std::mutex mMutexLoopQueue
Definition: LoopClosing.h:117
Vector3d map(const Vector3d &xyz) const
Definition: sim3.h:144
std::mutex mMutexReset
Definition: LoopClosing.h:99
long unsigned int mnCorrectedReference
Definition: MapPoint.h:109
void ComputeDistinctiveDescriptors()
Definition: MapPoint.cc:242
std::vector< MapPoint * > mvpLoopMapPoints
Definition: LoopClosing.h:129
std::thread * mpThreadGBA
Definition: LoopClosing.h:140
void UpdateConnections()
Definition: KeyFrame.cc:289
std::vector< MapPoint * > mvpCurrentMatchedPoints
Definition: LoopClosing.h:128
long unsigned int mnId
Definition: KeyFrame.h:125
const Quaterniond & rotation() const
Definition: sim3.h:284
cv::Mat GetEstimatedTranslation()
Definition: Sim3Solver.cc:372
std::vector< ConsistentGroup > mvConsistentGroups
Definition: LoopClosing.h:125
int Fuse(KeyFrame *pKF, const vector< MapPoint * > &vpMapPoints, const float th=3.0)
Definition: ORBmatcher.cc:825


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05