MapPoint.h 7.6 KB

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