MapPoint.h 7.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2021 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 "Converter.h"
  24. #include "SerializationUtils.h"
  25. #include <opencv2/core/core.hpp>
  26. #include <mutex>
  27. #include <boost/serialization/serialization.hpp>
  28. #include <boost/serialization/array.hpp>
  29. #include <boost/serialization/map.hpp>
  30. namespace ORB_SLAM3
  31. {
  32. class KeyFrame;
  33. class Map;
  34. class Frame;
  35. class MapPoint
  36. {
  37. friend class boost::serialization::access;
  38. template<class Archive>
  39. void serialize(Archive & ar, const unsigned int version)
  40. {
  41. ar & mnId;
  42. ar & mnFirstKFid;
  43. ar & mnFirstFrame;
  44. ar & nObs;
  45. // Variables used by the tracking
  46. //ar & mTrackProjX;
  47. //ar & mTrackProjY;
  48. //ar & mTrackDepth;
  49. //ar & mTrackDepthR;
  50. //ar & mTrackProjXR;
  51. //ar & mTrackProjYR;
  52. //ar & mbTrackInView;
  53. //ar & mbTrackInViewR;
  54. //ar & mnTrackScaleLevel;
  55. //ar & mnTrackScaleLevelR;
  56. //ar & mTrackViewCos;
  57. //ar & mTrackViewCosR;
  58. //ar & mnTrackReferenceForFrame;
  59. //ar & mnLastFrameSeen;
  60. // Variables used by local mapping
  61. //ar & mnBALocalForKF;
  62. //ar & mnFuseCandidateForKF;
  63. // Variables used by loop closing and merging
  64. //ar & mnLoopPointForKF;
  65. //ar & mnCorrectedByKF;
  66. //ar & mnCorrectedReference;
  67. //serializeMatrix(ar,mPosGBA,version);
  68. //ar & mnBAGlobalForKF;
  69. //ar & mnBALocalForMerge;
  70. //serializeMatrix(ar,mPosMerge,version);
  71. //serializeMatrix(ar,mNormalVectorMerge,version);
  72. // Protected variables
  73. ar & boost::serialization::make_array(mWorldPos.data(), mWorldPos.size());
  74. ar & boost::serialization::make_array(mNormalVector.data(), mNormalVector.size());
  75. //ar & BOOST_SERIALIZATION_NVP(mBackupObservationsId);
  76. //ar & mObservations;
  77. ar & mBackupObservationsId1;
  78. ar & mBackupObservationsId2;
  79. serializeMatrix(ar,mDescriptor,version);
  80. ar & mBackupRefKFId;
  81. //ar & mnVisible;
  82. //ar & mnFound;
  83. ar & mbBad;
  84. ar & mBackupReplacedId;
  85. ar & mfMinDistance;
  86. ar & mfMaxDistance;
  87. }
  88. public:
  89. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  90. MapPoint();
  91. MapPoint(const Eigen::Vector3f &Pos, KeyFrame* pRefKF, Map* pMap);
  92. MapPoint(const double invDepth, cv::Point2f uv_init, KeyFrame* pRefKF, KeyFrame* pHostKF, Map* pMap);
  93. MapPoint(const Eigen::Vector3f &Pos, Map* pMap, Frame* pFrame, const int &idxF);
  94. void SetWorldPos(const Eigen::Vector3f &Pos);
  95. Eigen::Vector3f GetWorldPos();
  96. Eigen::Vector3f GetNormal();
  97. void SetNormalVector(const Eigen::Vector3f& normal);
  98. KeyFrame* GetReferenceKeyFrame();
  99. std::map<KeyFrame*,std::tuple<int,int>> GetObservations();
  100. int Observations();
  101. void AddObservation(KeyFrame* pKF,int idx);
  102. void EraseObservation(KeyFrame* pKF);
  103. std::tuple<int,int> GetIndexInKeyFrame(KeyFrame* pKF);
  104. bool IsInKeyFrame(KeyFrame* pKF);
  105. void SetBadFlag();
  106. bool isBad();
  107. void Replace(MapPoint* pMP);
  108. MapPoint* GetReplaced();
  109. void IncreaseVisible(int n=1);
  110. void IncreaseFound(int n=1);
  111. float GetFoundRatio();
  112. inline int GetFound(){
  113. return mnFound;
  114. }
  115. void ComputeDistinctiveDescriptors();
  116. cv::Mat GetDescriptor();
  117. void UpdateNormalAndDepth();
  118. float GetMinDistanceInvariance();
  119. float GetMaxDistanceInvariance();
  120. int PredictScale(const float &currentDist, KeyFrame*pKF);
  121. int PredictScale(const float &currentDist, Frame* pF);
  122. Map* GetMap();
  123. void UpdateMap(Map* pMap);
  124. void PrintObservations();
  125. void PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP);
  126. void PostLoad(map<long unsigned int, KeyFrame*>& mpKFid, map<long unsigned int, MapPoint*>& mpMPid);
  127. public:
  128. long unsigned int mnId;
  129. static long unsigned int nNextId;
  130. long int mnFirstKFid;
  131. long int mnFirstFrame;
  132. int nObs;
  133. // Variables used by the tracking
  134. float mTrackProjX;
  135. float mTrackProjY;
  136. float mTrackDepth;
  137. float mTrackDepthR;
  138. float mTrackProjXR;
  139. float mTrackProjYR;
  140. bool mbTrackInView, mbTrackInViewR;
  141. int mnTrackScaleLevel, mnTrackScaleLevelR;
  142. float mTrackViewCos, mTrackViewCosR;
  143. long unsigned int mnTrackReferenceForFrame;
  144. long unsigned int mnLastFrameSeen;
  145. // Variables used by local mapping
  146. long unsigned int mnBALocalForKF;
  147. long unsigned int mnFuseCandidateForKF;
  148. // Variables used by loop closing
  149. long unsigned int mnLoopPointForKF;
  150. long unsigned int mnCorrectedByKF;
  151. long unsigned int mnCorrectedReference;
  152. Eigen::Vector3f mPosGBA;
  153. long unsigned int mnBAGlobalForKF;
  154. long unsigned int mnBALocalForMerge;
  155. // Variable used by merging
  156. Eigen::Vector3f mPosMerge;
  157. Eigen::Vector3f mNormalVectorMerge;
  158. // Fopr inverse depth optimization
  159. double mInvDepth;
  160. double mInitU;
  161. double mInitV;
  162. KeyFrame* mpHostKF;
  163. static std::mutex mGlobalMutex;
  164. unsigned int mnOriginMapId;
  165. protected:
  166. // Position in absolute coordinates
  167. Eigen::Vector3f mWorldPos;
  168. // Keyframes observing the point and associated index in keyframe
  169. std::map<KeyFrame*,std::tuple<int,int> > mObservations;
  170. // For save relation without pointer, this is necessary for save/load function
  171. std::map<long unsigned int, int> mBackupObservationsId1;
  172. std::map<long unsigned int, int> mBackupObservationsId2;
  173. // Mean viewing direction
  174. Eigen::Vector3f mNormalVector;
  175. // Best descriptor to fast matching
  176. cv::Mat mDescriptor;
  177. // Reference KeyFrame
  178. KeyFrame* mpRefKF;
  179. long unsigned int mBackupRefKFId;
  180. // Tracking counters
  181. int mnVisible;
  182. int mnFound;
  183. // Bad flag (we do not currently erase MapPoint from memory)
  184. bool mbBad;
  185. MapPoint* mpReplaced;
  186. // For save relation without pointer, this is necessary for save/load function
  187. long long int mBackupReplacedId;
  188. // Scale invariance distances
  189. float mfMinDistance;
  190. float mfMaxDistance;
  191. Map* mpMap;
  192. // Mutex
  193. std::mutex mMutexPos;
  194. std::mutex mMutexFeatures;
  195. std::mutex mMutexMap;
  196. };
  197. } //namespace ORB_SLAM
  198. #endif // MAPPOINT_H