LocalMapping.h 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185
  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 LOCALMAPPING_H
  19. #define LOCALMAPPING_H
  20. #include "KeyFrame.h"
  21. #include "Atlas.h"
  22. #include "LoopClosing.h"
  23. #include "Tracking.h"
  24. #include "KeyFrameDatabase.h"
  25. #include "Initializer.h"
  26. #include <mutex>
  27. namespace ORB_SLAM3
  28. {
  29. class System;
  30. class Tracking;
  31. class LoopClosing;
  32. class Atlas;
  33. class LocalMapping
  34. {
  35. public:
  36. LocalMapping(System* pSys, Atlas* pAtlas, const float bMonocular, bool bInertial, const string &_strSeqName=std::string());
  37. void SetLoopCloser(LoopClosing* pLoopCloser);
  38. void SetTracker(Tracking* pTracker);
  39. // Main function
  40. void Run();
  41. void InsertKeyFrame(KeyFrame* pKF);
  42. void EmptyQueue();
  43. // Thread Synch
  44. void RequestStop();
  45. void RequestReset();
  46. void RequestResetActiveMap(Map* pMap);
  47. bool Stop();
  48. void Release();
  49. bool isStopped();
  50. bool stopRequested();
  51. bool AcceptKeyFrames();
  52. void SetAcceptKeyFrames(bool flag);
  53. bool SetNotStop(bool flag);
  54. void InterruptBA();
  55. void RequestFinish();
  56. bool isFinished();
  57. int KeyframesInQueue(){
  58. unique_lock<std::mutex> lock(mMutexNewKFs);
  59. return mlNewKeyFrames.size();
  60. }
  61. bool IsInitializing();
  62. double GetCurrKFTime();
  63. KeyFrame* GetCurrKF();
  64. std::mutex mMutexImuInit;
  65. Eigen::MatrixXd mcovInertial;
  66. Eigen::Matrix3d mRwg;
  67. Eigen::Vector3d mbg;
  68. Eigen::Vector3d mba;
  69. double mScale;
  70. double mInitTime;
  71. double mCostTime;
  72. bool mbNewInit;
  73. unsigned int mInitSect;
  74. unsigned int mIdxInit;
  75. unsigned int mnKFs;
  76. double mFirstTs;
  77. int mnMatchesInliers;
  78. // For debugging (erase in normal mode)
  79. int mInitFr;
  80. int mIdxIteration;
  81. string strSequence;
  82. bool mbNotBA1;
  83. bool mbNotBA2;
  84. bool mbBadImu;
  85. bool mbWriteStats;
  86. // not consider far points (clouds)
  87. bool mbFarPoints;
  88. float mThFarPoints;
  89. protected:
  90. bool CheckNewKeyFrames();
  91. void ProcessNewKeyFrame();
  92. void CreateNewMapPoints();
  93. void MapPointCulling();
  94. void SearchInNeighbors();
  95. void KeyFrameCulling();
  96. cv::Mat ComputeF12(KeyFrame* &pKF1, KeyFrame* &pKF2);
  97. cv::Mat SkewSymmetricMatrix(const cv::Mat &v);
  98. System *mpSystem;
  99. bool mbMonocular;
  100. bool mbInertial;
  101. void ResetIfRequested();
  102. bool mbResetRequested;
  103. bool mbResetRequestedActiveMap;
  104. Map* mpMapToReset;
  105. std::mutex mMutexReset;
  106. bool CheckFinish();
  107. void SetFinish();
  108. bool mbFinishRequested;
  109. bool mbFinished;
  110. std::mutex mMutexFinish;
  111. Atlas* mpAtlas;
  112. LoopClosing* mpLoopCloser;
  113. Tracking* mpTracker;
  114. std::list<KeyFrame*> mlNewKeyFrames;
  115. KeyFrame* mpCurrentKeyFrame;
  116. std::list<MapPoint*> mlpRecentAddedMapPoints;
  117. std::mutex mMutexNewKFs;
  118. bool mbAbortBA;
  119. bool mbStopped;
  120. bool mbStopRequested;
  121. bool mbNotStop;
  122. std::mutex mMutexStop;
  123. bool mbAcceptKeyFrames;
  124. std::mutex mMutexAccept;
  125. void InitializeIMU(float priorG = 1e2, float priorA = 1e6, bool bFirst = false);
  126. void ScaleRefinement();
  127. bool bInitializing;
  128. Eigen::MatrixXd infoInertial;
  129. int mNumLM;
  130. int mNumKFCulling;
  131. float mTinit;
  132. int countRefinement;
  133. //DEBUG
  134. ofstream f_lm;
  135. };
  136. } //namespace ORB_SLAM
  137. #endif // LOCALMAPPING_H