LocalMapping.h 3.5 KB

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