Map.h 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205
  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 MAP_H
  19. #define MAP_H
  20. #include "MapPoint.h"
  21. #include "KeyFrame.h"
  22. #include <set>
  23. #include <pangolin/pangolin.h>
  24. #include <mutex>
  25. #include <boost/serialization/base_object.hpp>
  26. namespace ORB_SLAM3
  27. {
  28. class MapPoint;
  29. class KeyFrame;
  30. class Atlas;
  31. class KeyFrameDatabase;
  32. class Map
  33. {
  34. friend class boost::serialization::access;
  35. template<class Archive>
  36. void serialize(Archive &ar, const unsigned int version)
  37. {
  38. ar & mnId;
  39. ar & mnInitKFid;
  40. ar & mnMaxKFid;
  41. ar & mnBigChangeIdx;
  42. // Set of KeyFrames and MapPoints, in this version the set serializator is not working
  43. //ar & mspKeyFrames;
  44. //ar & mspMapPoints;
  45. ar & mvpBackupKeyFrames;
  46. ar & mvpBackupMapPoints;
  47. ar & mvBackupKeyFrameOriginsId;
  48. ar & mnBackupKFinitialID;
  49. ar & mnBackupKFlowerID;
  50. ar & mbImuInitialized;
  51. ar & mbIsInertial;
  52. ar & mbIMU_BA1;
  53. ar & mbIMU_BA2;
  54. ar & mnInitKFid;
  55. ar & mnMaxKFid;
  56. ar & mnLastLoopKFid;
  57. }
  58. public:
  59. Map();
  60. Map(int initKFid);
  61. ~Map();
  62. void AddKeyFrame(KeyFrame* pKF);
  63. void AddMapPoint(MapPoint* pMP);
  64. void EraseMapPoint(MapPoint* pMP);
  65. void EraseKeyFrame(KeyFrame* pKF);
  66. void SetReferenceMapPoints(const std::vector<MapPoint*> &vpMPs);
  67. void InformNewBigChange();
  68. int GetLastBigChangeIdx();
  69. std::vector<KeyFrame*> GetAllKeyFrames();
  70. std::vector<MapPoint*> GetAllMapPoints();
  71. std::vector<MapPoint*> GetReferenceMapPoints();
  72. long unsigned int MapPointsInMap();
  73. long unsigned KeyFramesInMap();
  74. long unsigned int GetId();
  75. long unsigned int GetInitKFid();
  76. void SetInitKFid(long unsigned int initKFif);
  77. long unsigned int GetMaxKFid();
  78. KeyFrame* GetOriginKF();
  79. void SetCurrentMap();
  80. void SetStoredMap();
  81. bool HasThumbnail();
  82. bool IsInUse();
  83. void SetBad();
  84. bool IsBad();
  85. void clear();
  86. int GetMapChangeIndex();
  87. void IncreaseChangeIndex();
  88. int GetLastMapChange();
  89. void SetLastMapChange(int currentChangeId);
  90. void SetImuInitialized();
  91. bool isImuInitialized();
  92. void RotateMap(const cv::Mat &R);
  93. void ApplyScaledRotation(const cv::Mat &R, const float s, const bool bScaledVel=false, const cv::Mat t=cv::Mat::zeros(cv::Size(1,3),CV_32F));
  94. void SetInertialSensor();
  95. bool IsInertial();
  96. void SetIniertialBA1();
  97. void SetIniertialBA2();
  98. bool GetIniertialBA1();
  99. bool GetIniertialBA2();
  100. void PrintEssentialGraph();
  101. bool CheckEssentialGraph();
  102. void ChangeId(long unsigned int nId);
  103. unsigned int GetLowerKFID();
  104. void PreSave(std::set<GeometricCamera*> &spCams);
  105. void PostLoad(KeyFrameDatabase* pKFDB, ORBVocabulary* pORBVoc, map<long unsigned int, KeyFrame*>& mpKeyFrameId, map<unsigned int, GeometricCamera*> &mpCams);
  106. void printReprojectionError(list<KeyFrame*> &lpLocalWindowKFs, KeyFrame* mpCurrentKF, string &name, string &name_folder);
  107. vector<KeyFrame*> mvpKeyFrameOrigins;
  108. vector<unsigned long int> mvBackupKeyFrameOriginsId;
  109. KeyFrame* mpFirstRegionKF;
  110. std::mutex mMutexMapUpdate;
  111. // This avoid that two points are created simultaneously in separate threads (id conflict)
  112. std::mutex mMutexPointCreation;
  113. bool mbFail;
  114. // Size of the thumbnail (always in power of 2)
  115. static const int THUMB_WIDTH = 512;
  116. static const int THUMB_HEIGHT = 512;
  117. static long unsigned int nNextId;
  118. protected:
  119. long unsigned int mnId;
  120. std::set<MapPoint*> mspMapPoints;
  121. std::set<KeyFrame*> mspKeyFrames;
  122. std::vector<MapPoint*> mvpBackupMapPoints;
  123. std::vector<KeyFrame*> mvpBackupKeyFrames;
  124. KeyFrame* mpKFinitial;
  125. KeyFrame* mpKFlowerID;
  126. unsigned long int mnBackupKFinitialID;
  127. unsigned long int mnBackupKFlowerID;
  128. std::vector<MapPoint*> mvpReferenceMapPoints;
  129. bool mbImuInitialized;
  130. int mnMapChange;
  131. int mnMapChangeNotified;
  132. long unsigned int mnInitKFid;
  133. long unsigned int mnMaxKFid;
  134. long unsigned int mnLastLoopKFid;
  135. // Index related to a big change in the map (loop closure, global BA)
  136. int mnBigChangeIdx;
  137. // View of the map in aerial sight (for the AtlasViewer)
  138. GLubyte* mThumbnail;
  139. bool mIsInUse;
  140. bool mHasTumbnail;
  141. bool mbBad = false;
  142. bool mbIsInertial;
  143. bool mbIMU_BA1;
  144. bool mbIMU_BA2;
  145. std::mutex mMutexMap;
  146. };
  147. } //namespace ORB_SLAM3
  148. #endif // MAP_H