Atlas.h 3.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134
  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 ATLAS_H
  19. #define ATLAS_H
  20. #include "Map.h"
  21. #include "MapPoint.h"
  22. #include "KeyFrame.h"
  23. #include "GeometricCamera.h"
  24. #include "Pinhole.h"
  25. #include "KannalaBrandt8.h"
  26. #include <set>
  27. #include <mutex>
  28. #include <boost/serialization/vector.hpp>
  29. #include <boost/serialization/export.hpp>
  30. namespace ORB_SLAM3
  31. {
  32. class Viewer;
  33. class Map;
  34. class MapPoint;
  35. class KeyFrame;
  36. class KeyFrameDatabase;
  37. class Frame;
  38. class KannalaBrandt8;
  39. class Pinhole;
  40. class Atlas
  41. {
  42. public:
  43. Atlas();
  44. Atlas(int initKFid); // When its initialization the first map is created
  45. ~Atlas();
  46. void CreateNewMap();
  47. void ChangeMap(Map* pMap);
  48. unsigned long int GetLastInitKFid();
  49. void SetViewer(Viewer* pViewer);
  50. // Method for change components in the current map
  51. void AddKeyFrame(KeyFrame* pKF);
  52. void AddMapPoint(MapPoint* pMP);
  53. void AddCamera(GeometricCamera* pCam);
  54. /* All methods without Map pointer work on current map */
  55. void SetReferenceMapPoints(const std::vector<MapPoint*> &vpMPs);
  56. void InformNewBigChange();
  57. int GetLastBigChangeIdx();
  58. long unsigned int MapPointsInMap();
  59. long unsigned KeyFramesInMap();
  60. // Method for get data in current map
  61. std::vector<KeyFrame*> GetAllKeyFrames();
  62. std::vector<MapPoint*> GetAllMapPoints();
  63. std::vector<MapPoint*> GetReferenceMapPoints();
  64. vector<Map*> GetAllMaps();
  65. int CountMaps();
  66. void clearMap();
  67. void clearAtlas();
  68. Map* GetCurrentMap();
  69. void SetMapBad(Map* pMap);
  70. void RemoveBadMaps();
  71. bool isInertial();
  72. void SetInertialSensor();
  73. void SetImuInitialized();
  74. bool isImuInitialized();
  75. void SetKeyFrameDababase(KeyFrameDatabase* pKFDB);
  76. KeyFrameDatabase* GetKeyFrameDatabase();
  77. void SetORBVocabulary(ORBVocabulary* pORBVoc);
  78. ORBVocabulary* GetORBVocabulary();
  79. long unsigned int GetNumLivedKF();
  80. long unsigned int GetNumLivedMP();
  81. protected:
  82. std::set<Map*> mspMaps;
  83. std::set<Map*> mspBadMaps;
  84. Map* mpCurrentMap;
  85. std::vector<GeometricCamera*> mvpCameras;
  86. std::vector<KannalaBrandt8*> mvpBackupCamKan;
  87. std::vector<Pinhole*> mvpBackupCamPin;
  88. std::mutex mMutexAtlas;
  89. unsigned long int mnLastInitKFidMap;
  90. Viewer* mpViewer;
  91. bool mHasViewer;
  92. // Class references for the map reconstruction from the save file
  93. KeyFrameDatabase* mpKeyFrameDB;
  94. ORBVocabulary* mpORBVocabulary;
  95. }; // class Atlas
  96. } // namespace ORB_SLAM3
  97. #endif // ATLAS_H