123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165 |
- /**
- * This file is part of ORB-SLAM3
- *
- * 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.
- * 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 <http://www.gnu.org/licenses/>.
- */
- #ifndef MAP_H
- #define MAP_H
- #include "MapPoint.h"
- #include "KeyFrame.h"
- #include <set>
- #include <pangolin/pangolin.h>
- #include <mutex>
- #include <boost/serialization/base_object.hpp>
- namespace ORB_SLAM3
- {
- class MapPoint;
- class KeyFrame;
- class Atlas;
- class KeyFrameDatabase;
- class GeometricCamera;
- class Map
- {
- public:
- Map();
- Map(int initKFid);
- ~Map();
- void AddKeyFrame(KeyFrame* pKF);
- void AddMapPoint(MapPoint* pMP);
- void EraseMapPoint(MapPoint* pMP);
- void EraseKeyFrame(KeyFrame* pKF);
- void SetReferenceMapPoints(const std::vector<MapPoint*> &vpMPs);
- void InformNewBigChange();
- int GetLastBigChangeIdx();
- std::vector<KeyFrame*> GetAllKeyFrames();
- std::vector<MapPoint*> GetAllMapPoints();
- std::vector<MapPoint*> GetReferenceMapPoints();
- long unsigned int MapPointsInMap();
- long unsigned KeyFramesInMap();
- long unsigned int GetId();
- long unsigned int GetInitKFid();
- void SetInitKFid(long unsigned int initKFif);
- long unsigned int GetMaxKFid();
- KeyFrame* GetOriginKF();
- void SetCurrentMap();
- void SetStoredMap();
- bool HasThumbnail();
- bool IsInUse();
- void SetBad();
- bool IsBad();
- void clear();
- int GetMapChangeIndex();
- void IncreaseChangeIndex();
- int GetLastMapChange();
- void SetLastMapChange(int currentChangeId);
- void SetImuInitialized();
- bool isImuInitialized();
- void RotateMap(const cv::Mat &R);
- 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));
- void SetInertialSensor();
- bool IsInertial();
- void SetIniertialBA1();
- void SetIniertialBA2();
- bool GetIniertialBA1();
- bool GetIniertialBA2();
- void PrintEssentialGraph();
- bool CheckEssentialGraph();
- void ChangeId(long unsigned int nId);
- unsigned int GetLowerKFID();
- vector<KeyFrame*> mvpKeyFrameOrigins;
- vector<unsigned long int> mvBackupKeyFrameOriginsId;
- KeyFrame* mpFirstRegionKF;
- std::mutex mMutexMapUpdate;
- // This avoid that two points are created simultaneously in separate threads (id conflict)
- std::mutex mMutexPointCreation;
- bool mbFail;
- // Size of the thumbnail (always in power of 2)
- static const int THUMB_WIDTH = 512;
- static const int THUMB_HEIGHT = 512;
- static long unsigned int nNextId;
- protected:
- long unsigned int mnId;
- std::set<MapPoint*> mspMapPoints;
- std::set<KeyFrame*> mspKeyFrames;
- KeyFrame* mpKFinitial;
- KeyFrame* mpKFlowerID;
- std::vector<MapPoint*> mvpReferenceMapPoints;
- bool mbImuInitialized;
- int mnMapChange;
- int mnMapChangeNotified;
- long unsigned int mnInitKFid;
- long unsigned int mnMaxKFid;
- long unsigned int mnLastLoopKFid;
- // Index related to a big change in the map (loop closure, global BA)
- int mnBigChangeIdx;
- // View of the map in aerial sight (for the AtlasViewer)
- GLubyte* mThumbnail;
- bool mIsInUse;
- bool mHasTumbnail;
- bool mbBad = false;
- bool mbIsInertial;
- bool mbIMU_BA1;
- bool mbIMU_BA2;
- std::mutex mMutexMap;
- };
- } //namespace ORB_SLAM3
- #endif // MAP_H
|