MapPoint.h 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187
  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 MAPPOINT_H
  19. #define MAPPOINT_H
  20. #include"KeyFrame.h"
  21. #include"Frame.h"
  22. #include"Map.h"
  23. #include<opencv2/core/core.hpp>
  24. #include<mutex>
  25. #include <boost/serialization/serialization.hpp>
  26. #include <boost/serialization/array.hpp>
  27. #include <boost/serialization/map.hpp>
  28. namespace ORB_SLAM3
  29. {
  30. class KeyFrame;
  31. class Map;
  32. class Frame;
  33. class MapPoint
  34. {
  35. public:
  36. MapPoint();
  37. MapPoint(const cv::Mat &Pos, KeyFrame* pRefKF, Map* pMap);
  38. MapPoint(const double invDepth, cv::Point2f uv_init, KeyFrame* pRefKF, KeyFrame* pHostKF, Map* pMap);
  39. MapPoint(const cv::Mat &Pos, Map* pMap, Frame* pFrame, const int &idxF);
  40. void SetWorldPos(const cv::Mat &Pos);
  41. cv::Mat GetWorldPos();
  42. cv::Mat GetNormal();
  43. cv::Matx31f GetWorldPos2();
  44. cv::Matx31f GetNormal2();
  45. KeyFrame* GetReferenceKeyFrame();
  46. std::map<KeyFrame*,std::tuple<int,int>> GetObservations();
  47. int Observations();
  48. void AddObservation(KeyFrame* pKF,int idx);
  49. void EraseObservation(KeyFrame* pKF);
  50. std::tuple<int,int> GetIndexInKeyFrame(KeyFrame* pKF);
  51. bool IsInKeyFrame(KeyFrame* pKF);
  52. void SetBadFlag();
  53. bool isBad();
  54. void Replace(MapPoint* pMP);
  55. MapPoint* GetReplaced();
  56. void IncreaseVisible(int n=1);
  57. void IncreaseFound(int n=1);
  58. float GetFoundRatio();
  59. inline int GetFound(){
  60. return mnFound;
  61. }
  62. void ComputeDistinctiveDescriptors();
  63. cv::Mat GetDescriptor();
  64. void UpdateNormalAndDepth();
  65. void SetNormalVector(cv::Mat& normal);
  66. float GetMinDistanceInvariance();
  67. float GetMaxDistanceInvariance();
  68. int PredictScale(const float &currentDist, KeyFrame*pKF);
  69. int PredictScale(const float &currentDist, Frame* pF);
  70. Map* GetMap();
  71. void UpdateMap(Map* pMap);
  72. public:
  73. long unsigned int mnId;
  74. static long unsigned int nNextId;
  75. long int mnFirstKFid;
  76. long int mnFirstFrame;
  77. int nObs;
  78. // Variables used by the tracking
  79. float mTrackProjX;
  80. float mTrackProjY;
  81. float mTrackDepth;
  82. float mTrackDepthR;
  83. float mTrackProjXR;
  84. float mTrackProjYR;
  85. bool mbTrackInView, mbTrackInViewR;
  86. int mnTrackScaleLevel, mnTrackScaleLevelR;
  87. float mTrackViewCos, mTrackViewCosR;
  88. long unsigned int mnTrackReferenceForFrame;
  89. long unsigned int mnLastFrameSeen;
  90. // Variables used by local mapping
  91. long unsigned int mnBALocalForKF;
  92. long unsigned int mnFuseCandidateForKF;
  93. // Variables used by loop closing
  94. long unsigned int mnLoopPointForKF;
  95. long unsigned int mnCorrectedByKF;
  96. long unsigned int mnCorrectedReference;
  97. cv::Mat mPosGBA;
  98. long unsigned int mnBAGlobalForKF;
  99. long unsigned int mnBALocalForMerge;
  100. // Variable used by merging
  101. cv::Mat mPosMerge;
  102. cv::Mat mNormalVectorMerge;
  103. // Fopr inverse depth optimization
  104. double mInvDepth;
  105. double mInitU;
  106. double mInitV;
  107. KeyFrame* mpHostKF;
  108. static std::mutex mGlobalMutex;
  109. unsigned int mnOriginMapId;
  110. protected:
  111. // Position in absolute coordinates
  112. cv::Mat mWorldPos;
  113. cv::Matx31f mWorldPosx;
  114. // Keyframes observing the point and associated index in keyframe
  115. std::map<KeyFrame*,std::tuple<int,int> > mObservations;
  116. // Mean viewing direction
  117. cv::Mat mNormalVector;
  118. cv::Matx31f mNormalVectorx;
  119. // Best descriptor to fast matching
  120. cv::Mat mDescriptor;
  121. // Reference KeyFrame
  122. KeyFrame* mpRefKF;
  123. // Tracking counters
  124. int mnVisible;
  125. int mnFound;
  126. // Bad flag (we do not currently erase MapPoint from memory)
  127. bool mbBad;
  128. MapPoint* mpReplaced;
  129. // Scale invariance distances
  130. float mfMinDistance;
  131. float mfMaxDistance;
  132. Map* mpMap;
  133. std::mutex mMutexPos;
  134. std::mutex mMutexFeatures;
  135. std::mutex mMutexMap;
  136. };
  137. } //namespace ORB_SLAM
  138. #endif // MAPPOINT_H