LoopClosing.h 6.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * 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.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #ifndef LOOPCLOSING_H
  19. #define LOOPCLOSING_H
  20. #include "KeyFrame.h"
  21. #include "LocalMapping.h"
  22. #include "Atlas.h"
  23. #include "ORBVocabulary.h"
  24. #include "Tracking.h"
  25. #include "KeyFrameDatabase.h"
  26. #include <boost/algorithm/string.hpp>
  27. #include <thread>
  28. #include <mutex>
  29. #include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h"
  30. namespace ORB_SLAM3
  31. {
  32. class Tracking;
  33. class LocalMapping;
  34. class KeyFrameDatabase;
  35. class Map;
  36. class LoopClosing
  37. {
  38. public:
  39. typedef pair<set<KeyFrame*>,int> ConsistentGroup;
  40. typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>,
  41. Eigen::aligned_allocator<std::pair<const KeyFrame*, g2o::Sim3> > > KeyFrameAndPose;
  42. public:
  43. LoopClosing(Atlas* pAtlas, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale);
  44. void SetTracker(Tracking* pTracker);
  45. void SetLocalMapper(LocalMapping* pLocalMapper);
  46. // Main function
  47. void Run();
  48. void InsertKeyFrame(KeyFrame *pKF);
  49. void RequestReset();
  50. void RequestResetActiveMap(Map* pMap);
  51. // This function will run in a separate thread
  52. void RunGlobalBundleAdjustment(Map* pActiveMap, unsigned long nLoopKF);
  53. bool isRunningGBA(){
  54. unique_lock<std::mutex> lock(mMutexGBA);
  55. return mbRunningGBA;
  56. }
  57. bool isFinishedGBA(){
  58. unique_lock<std::mutex> lock(mMutexGBA);
  59. return mbFinishedGBA;
  60. }
  61. void RequestFinish();
  62. bool isFinished();
  63. Viewer* mpViewer;
  64. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  65. protected:
  66. bool CheckNewKeyFrames();
  67. //Methods to implement the new place recognition algorithm
  68. bool NewDetectCommonRegions();
  69. bool DetectAndReffineSim3FromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches,
  70. std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs);
  71. bool DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand, KeyFrame* &pMatchedKF, KeyFrame* &pLastCurrentKF, g2o::Sim3 &g2oScw,
  72. int &nNumCoincidences, std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs);
  73. bool DetectCommonRegionsFromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches,
  74. std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs);
  75. int FindMatchesByProjection(KeyFrame* pCurrentKF, KeyFrame* pMatchedKFw, g2o::Sim3 &g2oScw,
  76. set<MapPoint*> &spMatchedMPinOrigin, vector<MapPoint*> &vpMapPoints,
  77. vector<MapPoint*> &vpMatchedMapPoints);
  78. void SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap, vector<MapPoint*> &vpMapPoints);
  79. void SearchAndFuse(const vector<KeyFrame*> &vConectedKFs, vector<MapPoint*> &vpMapPoints);
  80. void CorrectLoop();
  81. void MergeLocal();
  82. void MergeLocal2();
  83. void CheckObservations(set<KeyFrame*> &spKFsMap1, set<KeyFrame*> &spKFsMap2);
  84. void printReprojectionError(set<KeyFrame*> &spLocalWindowKFs, KeyFrame* mpCurrentKF, string &name);
  85. void ResetIfRequested();
  86. bool mbResetRequested;
  87. bool mbResetActiveMapRequested;
  88. Map* mpMapToReset;
  89. std::mutex mMutexReset;
  90. bool CheckFinish();
  91. void SetFinish();
  92. bool mbFinishRequested;
  93. bool mbFinished;
  94. std::mutex mMutexFinish;
  95. Atlas* mpAtlas;
  96. Tracking* mpTracker;
  97. KeyFrameDatabase* mpKeyFrameDB;
  98. ORBVocabulary* mpORBVocabulary;
  99. LocalMapping *mpLocalMapper;
  100. std::list<KeyFrame*> mlpLoopKeyFrameQueue;
  101. std::mutex mMutexLoopQueue;
  102. // Loop detector parameters
  103. float mnCovisibilityConsistencyTh;
  104. // Loop detector variables
  105. KeyFrame* mpCurrentKF;
  106. KeyFrame* mpLastCurrentKF;
  107. KeyFrame* mpMatchedKF;
  108. std::vector<ConsistentGroup> mvConsistentGroups;
  109. std::vector<KeyFrame*> mvpEnoughConsistentCandidates;
  110. std::vector<KeyFrame*> mvpCurrentConnectedKFs;
  111. std::vector<MapPoint*> mvpCurrentMatchedPoints;
  112. std::vector<MapPoint*> mvpLoopMapPoints;
  113. cv::Mat mScw;
  114. g2o::Sim3 mg2oScw;
  115. //-------
  116. Map* mpLastMap;
  117. bool mbLoopDetected;
  118. int mnLoopNumCoincidences;
  119. int mnLoopNumNotFound;
  120. KeyFrame* mpLoopLastCurrentKF;
  121. g2o::Sim3 mg2oLoopSlw;
  122. g2o::Sim3 mg2oLoopScw;
  123. KeyFrame* mpLoopMatchedKF;
  124. std::vector<MapPoint*> mvpLoopMPs;
  125. std::vector<MapPoint*> mvpLoopMatchedMPs;
  126. bool mbMergeDetected;
  127. int mnMergeNumCoincidences;
  128. int mnMergeNumNotFound;
  129. KeyFrame* mpMergeLastCurrentKF;
  130. g2o::Sim3 mg2oMergeSlw;
  131. g2o::Sim3 mg2oMergeSmw;
  132. g2o::Sim3 mg2oMergeScw;
  133. KeyFrame* mpMergeMatchedKF;
  134. std::vector<MapPoint*> mvpMergeMPs;
  135. std::vector<MapPoint*> mvpMergeMatchedMPs;
  136. std::vector<KeyFrame*> mvpMergeConnectedKFs;
  137. g2o::Sim3 mSold_new;
  138. //-------
  139. long unsigned int mLastLoopKFid;
  140. // Variables related to Global Bundle Adjustment
  141. bool mbRunningGBA;
  142. bool mbFinishedGBA;
  143. bool mbStopGBA;
  144. std::mutex mMutexGBA;
  145. std::thread* mpThreadGBA;
  146. // Fix scale in the stereo/RGB-D case
  147. bool mbFixScale;
  148. bool mnFullBAIdx;
  149. vector<double> vdPR_CurrentTime;
  150. vector<double> vdPR_MatchedTime;
  151. vector<int> vnPR_TypeRecogn;
  152. };
  153. } //namespace ORB_SLAM
  154. #endif // LOOPCLOSING_H