Map.h 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165
  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 GeometricCamera;
  33. class Map
  34. {
  35. public:
  36. Map();
  37. Map(int initKFid);
  38. ~Map();
  39. void AddKeyFrame(KeyFrame* pKF);
  40. void AddMapPoint(MapPoint* pMP);
  41. void EraseMapPoint(MapPoint* pMP);
  42. void EraseKeyFrame(KeyFrame* pKF);
  43. void SetReferenceMapPoints(const std::vector<MapPoint*> &vpMPs);
  44. void InformNewBigChange();
  45. int GetLastBigChangeIdx();
  46. std::vector<KeyFrame*> GetAllKeyFrames();
  47. std::vector<MapPoint*> GetAllMapPoints();
  48. std::vector<MapPoint*> GetReferenceMapPoints();
  49. long unsigned int MapPointsInMap();
  50. long unsigned KeyFramesInMap();
  51. long unsigned int GetId();
  52. long unsigned int GetInitKFid();
  53. void SetInitKFid(long unsigned int initKFif);
  54. long unsigned int GetMaxKFid();
  55. KeyFrame* GetOriginKF();
  56. void SetCurrentMap();
  57. void SetStoredMap();
  58. bool HasThumbnail();
  59. bool IsInUse();
  60. void SetBad();
  61. bool IsBad();
  62. void clear();
  63. int GetMapChangeIndex();
  64. void IncreaseChangeIndex();
  65. int GetLastMapChange();
  66. void SetLastMapChange(int currentChangeId);
  67. void SetImuInitialized();
  68. bool isImuInitialized();
  69. void RotateMap(const cv::Mat &R);
  70. 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));
  71. void SetInertialSensor();
  72. bool IsInertial();
  73. void SetIniertialBA1();
  74. void SetIniertialBA2();
  75. bool GetIniertialBA1();
  76. bool GetIniertialBA2();
  77. void PrintEssentialGraph();
  78. bool CheckEssentialGraph();
  79. void ChangeId(long unsigned int nId);
  80. unsigned int GetLowerKFID();
  81. vector<KeyFrame*> mvpKeyFrameOrigins;
  82. vector<unsigned long int> mvBackupKeyFrameOriginsId;
  83. KeyFrame* mpFirstRegionKF;
  84. std::mutex mMutexMapUpdate;
  85. // This avoid that two points are created simultaneously in separate threads (id conflict)
  86. std::mutex mMutexPointCreation;
  87. bool mbFail;
  88. // Size of the thumbnail (always in power of 2)
  89. static const int THUMB_WIDTH = 512;
  90. static const int THUMB_HEIGHT = 512;
  91. static long unsigned int nNextId;
  92. protected:
  93. long unsigned int mnId;
  94. std::set<MapPoint*> mspMapPoints;
  95. std::set<KeyFrame*> mspKeyFrames;
  96. KeyFrame* mpKFinitial;
  97. KeyFrame* mpKFlowerID;
  98. std::vector<MapPoint*> mvpReferenceMapPoints;
  99. bool mbImuInitialized;
  100. int mnMapChange;
  101. int mnMapChangeNotified;
  102. long unsigned int mnInitKFid;
  103. long unsigned int mnMaxKFid;
  104. long unsigned int mnLastLoopKFid;
  105. // Index related to a big change in the map (loop closure, global BA)
  106. int mnBigChangeIdx;
  107. // View of the map in aerial sight (for the AtlasViewer)
  108. GLubyte* mThumbnail;
  109. bool mIsInUse;
  110. bool mHasTumbnail;
  111. bool mbBad = false;
  112. bool mbIsInertial;
  113. bool mbIMU_BA1;
  114. bool mbIMU_BA2;
  115. std::mutex mMutexMap;
  116. };
  117. } //namespace ORB_SLAM3
  118. #endif // MAP_H