/** * This file is part of ORB-SLAM3 * * 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. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. * * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public * License as published by the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License along with ORB-SLAM3. * If not, see . */ #ifndef ATLAS_H #define ATLAS_H #include "Map.h" #include "MapPoint.h" #include "KeyFrame.h" #include "GeometricCamera.h" #include "Pinhole.h" #include "KannalaBrandt8.h" #include #include #include #include namespace ORB_SLAM3 { class Viewer; class Map; class MapPoint; class KeyFrame; class KeyFrameDatabase; class Frame; class KannalaBrandt8; class Pinhole; //BOOST_CLASS_EXPORT_GUID(Pinhole, "Pinhole") //BOOST_CLASS_EXPORT_GUID(KannalaBrandt8, "KannalaBrandt8") class Atlas { // 1. 对boost声明友元,boost就能调用Atlas的serialize了 friend class boost::serialization::access; // 保存读取都用这个 template void serialize(Archive &ar, const unsigned int version) { // 由于保存相机是基类,但是实际使用是派生类,所以声明一下 ar.template register_type(); ar.template register_type(); // Save/load a set structure, the set structure is broken in libboost 1.58 for ubuntu 16.04, a vector is serializated //ar & mspMaps; // 基础类型不用管,但是自定义的类里面要进一步写serialize函数,确定保存内容 ar & mvpBackupMaps; ar & mvpCameras; // Need to save/load the static Id from Frame, KeyFrame, MapPoint and Map ar & Map::nNextId; ar & Frame::nNextId; ar & KeyFrame::nNextId; ar & MapPoint::nNextId; ar & GeometricCamera::nNextId; ar & mnLastInitKFidMap; } public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW Atlas(); Atlas(int initKFid); // When its initialization the first map is created ~Atlas(); void CreateNewMap(); void ChangeMap(Map* pMap); unsigned long int GetLastInitKFid(); void SetViewer(Viewer* pViewer); // Method for change components in the current map void AddKeyFrame(KeyFrame* pKF); void AddMapPoint(MapPoint* pMP); //void EraseMapPoint(MapPoint* pMP); //void EraseKeyFrame(KeyFrame* pKF); GeometricCamera* AddCamera(GeometricCamera* pCam); std::vector GetAllCameras(); /* All methods without Map pointer work on current map */ void SetReferenceMapPoints(const std::vector &vpMPs); void InformNewBigChange(); int GetLastBigChangeIdx(); long unsigned int MapPointsInMap(); long unsigned KeyFramesInMap(); // Method for get data in current map std::vector GetAllKeyFrames(); std::vector GetAllMapPoints(); std::vector GetReferenceMapPoints(); vector GetAllMaps(); int CountMaps(); void clearMap(); void clearAtlas(); Map* GetCurrentMap(); void SetMapBad(Map* pMap); void RemoveBadMaps(); bool isInertial(); void SetInertialSensor(); void SetImuInitialized(); bool isImuInitialized(); // Function for garantee the correction of serialization of this object void PreSave(); void PostLoad(); map GetAtlasKeyframes(); void SetKeyFrameDababase(KeyFrameDatabase* pKFDB); KeyFrameDatabase* GetKeyFrameDatabase(); void SetORBVocabulary(ORBVocabulary* pORBVoc); ORBVocabulary* GetORBVocabulary(); long unsigned int GetNumLivedKF(); long unsigned int GetNumLivedMP(); protected: std::set mspMaps; std::set mspBadMaps; // Its necessary change the container from set to vector because libboost 1.58 and Ubuntu 16.04 have an error with this cointainer std::vector mvpBackupMaps; Map* mpCurrentMap; std::vector mvpCameras; unsigned long int mnLastInitKFidMap; Viewer* mpViewer; bool mHasViewer; // Class references for the map reconstruction from the save file KeyFrameDatabase* mpKeyFrameDB; ORBVocabulary* mpORBVocabulary; // Mutex std::mutex mMutexAtlas; }; // class Atlas } // namespace orb_slam3 #endif // ATLAS_H