LoopClosing.h 6.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226
  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 "Config.h"
  26. #include "KeyFrameDatabase.h"
  27. #include <boost/algorithm/string.hpp>
  28. #include <thread>
  29. #include <mutex>
  30. #include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h"
  31. namespace ORB_SLAM3
  32. {
  33. class Tracking;
  34. class LocalMapping;
  35. class KeyFrameDatabase;
  36. class Map;
  37. class LoopClosing
  38. {
  39. public:
  40. typedef pair<set<KeyFrame*>,int> ConsistentGroup;
  41. typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>,
  42. Eigen::aligned_allocator<std::pair<KeyFrame* const, g2o::Sim3> > > KeyFrameAndPose;
  43. public:
  44. LoopClosing(Atlas* pAtlas, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale);
  45. void SetTracker(Tracking* pTracker);
  46. void SetLocalMapper(LocalMapping* pLocalMapper);
  47. // Main function
  48. void Run();
  49. void InsertKeyFrame(KeyFrame *pKF);
  50. void RequestReset();
  51. void RequestResetActiveMap(Map* pMap);
  52. // This function will run in a separate thread
  53. void RunGlobalBundleAdjustment(Map* pActiveMap, unsigned long nLoopKF);
  54. bool isRunningGBA(){
  55. unique_lock<std::mutex> lock(mMutexGBA);
  56. return mbRunningGBA;
  57. }
  58. bool isFinishedGBA(){
  59. unique_lock<std::mutex> lock(mMutexGBA);
  60. return mbFinishedGBA;
  61. }
  62. void RequestFinish();
  63. bool isFinished();
  64. Viewer* mpViewer;
  65. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  66. #ifdef REGISTER_TIMES
  67. double timeDetectBoW;
  68. std::vector<double> vTimeBoW_ms;
  69. std::vector<double> vTimeSE3_ms;
  70. std::vector<double> vTimePRTotal_ms;
  71. std::vector<double> vTimeLoopFusion_ms;
  72. std::vector<double> vTimeLoopEssent_ms;
  73. std::vector<double> vTimeLoopTotal_ms;
  74. std::vector<double> vTimeMergeFusion_ms;
  75. std::vector<double> vTimeMergeBA_ms;
  76. std::vector<double> vTimeMergeTotal_ms;
  77. std::vector<double> vTimeFullGBA_ms;
  78. std::vector<double> vTimeMapUpdate_ms;
  79. std::vector<double> vTimeGBATotal_ms;
  80. #endif
  81. protected:
  82. bool CheckNewKeyFrames();
  83. //Methods to implement the new place recognition algorithm
  84. bool NewDetectCommonRegions();
  85. bool DetectAndReffineSim3FromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches,
  86. std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs);
  87. bool DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand, KeyFrame* &pMatchedKF, KeyFrame* &pLastCurrentKF, g2o::Sim3 &g2oScw,
  88. int &nNumCoincidences, std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs);
  89. bool DetectCommonRegionsFromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches,
  90. std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs);
  91. int FindMatchesByProjection(KeyFrame* pCurrentKF, KeyFrame* pMatchedKFw, g2o::Sim3 &g2oScw,
  92. set<MapPoint*> &spMatchedMPinOrigin, vector<MapPoint*> &vpMapPoints,
  93. vector<MapPoint*> &vpMatchedMapPoints);
  94. void SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap, vector<MapPoint*> &vpMapPoints);
  95. void SearchAndFuse(const vector<KeyFrame*> &vConectedKFs, vector<MapPoint*> &vpMapPoints);
  96. void CorrectLoop();
  97. void MergeLocal();
  98. void MergeLocal2();
  99. void ResetIfRequested();
  100. bool mbResetRequested;
  101. bool mbResetActiveMapRequested;
  102. Map* mpMapToReset;
  103. std::mutex mMutexReset;
  104. bool CheckFinish();
  105. void SetFinish();
  106. bool mbFinishRequested;
  107. bool mbFinished;
  108. std::mutex mMutexFinish;
  109. Atlas* mpAtlas;
  110. Tracking* mpTracker;
  111. KeyFrameDatabase* mpKeyFrameDB;
  112. ORBVocabulary* mpORBVocabulary;
  113. LocalMapping *mpLocalMapper;
  114. std::list<KeyFrame*> mlpLoopKeyFrameQueue;
  115. std::mutex mMutexLoopQueue;
  116. // Loop detector parameters
  117. float mnCovisibilityConsistencyTh;
  118. // Loop detector variables
  119. KeyFrame* mpCurrentKF;
  120. KeyFrame* mpLastCurrentKF;
  121. KeyFrame* mpMatchedKF;
  122. std::vector<ConsistentGroup> mvConsistentGroups;
  123. std::vector<KeyFrame*> mvpEnoughConsistentCandidates;
  124. std::vector<KeyFrame*> mvpCurrentConnectedKFs;
  125. std::vector<MapPoint*> mvpCurrentMatchedPoints;
  126. std::vector<MapPoint*> mvpLoopMapPoints;
  127. cv::Mat mScw;
  128. g2o::Sim3 mg2oScw;
  129. //-------
  130. Map* mpLastMap;
  131. bool mbLoopDetected;
  132. int mnLoopNumCoincidences;
  133. int mnLoopNumNotFound;
  134. KeyFrame* mpLoopLastCurrentKF;
  135. g2o::Sim3 mg2oLoopSlw;
  136. g2o::Sim3 mg2oLoopScw;
  137. KeyFrame* mpLoopMatchedKF;
  138. std::vector<MapPoint*> mvpLoopMPs;
  139. std::vector<MapPoint*> mvpLoopMatchedMPs;
  140. bool mbMergeDetected;
  141. int mnMergeNumCoincidences;
  142. int mnMergeNumNotFound;
  143. KeyFrame* mpMergeLastCurrentKF;
  144. g2o::Sim3 mg2oMergeSlw;
  145. g2o::Sim3 mg2oMergeSmw;
  146. g2o::Sim3 mg2oMergeScw;
  147. KeyFrame* mpMergeMatchedKF;
  148. std::vector<MapPoint*> mvpMergeMPs;
  149. std::vector<MapPoint*> mvpMergeMatchedMPs;
  150. std::vector<KeyFrame*> mvpMergeConnectedKFs;
  151. g2o::Sim3 mSold_new;
  152. //-------
  153. long unsigned int mLastLoopKFid;
  154. // Variables related to Global Bundle Adjustment
  155. bool mbRunningGBA;
  156. bool mbFinishedGBA;
  157. bool mbStopGBA;
  158. std::mutex mMutexGBA;
  159. std::thread* mpThreadGBA;
  160. // Fix scale in the stereo/RGB-D case
  161. bool mbFixScale;
  162. bool mnFullBAIdx;
  163. vector<double> vdPR_CurrentTime;
  164. vector<double> vdPR_MatchedTime;
  165. vector<int> vnPR_TypeRecogn;
  166. };
  167. } //namespace ORB_SLAM
  168. #endif // LOOPCLOSING_H