100 lines
3.0 KiB
C++
100 lines
3.0 KiB
C++
/**
|
|
* This file is part of ORB-SLAM2.
|
|
*
|
|
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
|
|
* For more information see <https://github.com/raulmur/ORB_SLAM2>
|
|
*
|
|
* ORB-SLAM2 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-SLAM2 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-SLAM2. If not, see <http://www.gnu.org/licenses/>.
|
|
*/
|
|
|
|
#ifndef MAP_H
|
|
#define MAP_H
|
|
|
|
#include "MapPoint.h"
|
|
#include "KeyFrame.h"
|
|
#include "MapObject.h"
|
|
|
|
#include <set>
|
|
|
|
#include <mutex>
|
|
|
|
namespace ORB_SLAM2
|
|
{
|
|
class MapObject;
|
|
class MapPoint;
|
|
class KeyFrame;
|
|
|
|
class Map
|
|
{
|
|
public:
|
|
Map();
|
|
|
|
void AddKeyFrame(KeyFrame *pKF);
|
|
void AddMapPoint(MapPoint *pMP);
|
|
void AddMapObject(MapObject *pMO); // 向地图中插入物体
|
|
|
|
void EraseMapPoint(MapPoint *pMP);
|
|
void EraseMapObject(MapObject *pMO); // 删除地图中的某个物体
|
|
|
|
void EraseKeyFrame(KeyFrame *pKF);
|
|
void SetReferenceMapPoints(const std::vector<MapPoint *> &vpMPs);
|
|
void SetReferenceMapObjects(const std::vector<MapObject *> &vpMOs);
|
|
|
|
void InformNewBigChange();
|
|
int GetLastBigChangeIdx();
|
|
|
|
std::vector<KeyFrame *> GetAllKeyFrames();
|
|
std::vector<MapPoint *> GetAllMapPoints();
|
|
std::vector<MapObject *> GetAllMapObjects();
|
|
std::vector<MapPoint *> GetReferenceMapPoints();
|
|
std::vector<MapObject *> GetReferenceMapObjects();
|
|
|
|
long unsigned int MapPointsInMap();
|
|
long unsigned int MapObjectsInMap();
|
|
long unsigned KeyFramesInMap();
|
|
|
|
long unsigned int GetMaxKFid();
|
|
|
|
void clear();
|
|
|
|
std::vector<KeyFrame *> mvpKeyFrameOrigins;
|
|
|
|
std::mutex mMutexMapUpdate;
|
|
|
|
// This avoid that two points are created simultaneously in separate threads (id conflict)
|
|
std::mutex mMutexPointCreation;
|
|
|
|
// This avoid that two objects are created simultaneously in separate threads (id conflict)
|
|
std::mutex mMutexObjectCreation;
|
|
|
|
protected:
|
|
std::set<MapPoint *> mspMapPoints;
|
|
std::set<KeyFrame *> mspKeyFrames;
|
|
std::set<MapObject *> mspMapObjects; // 存放物体
|
|
|
|
std::vector<MapPoint *> mvpReferenceMapPoints;
|
|
std::vector<MapObject *> mvpReferenceMapObjects; // 设置参考物体,可用于画图
|
|
|
|
long unsigned int mnMaxKFid;
|
|
|
|
// Index related to a big change in the map (loop closure, global BA)
|
|
int mnBigChangeIdx;
|
|
|
|
std::mutex mMutexMap;
|
|
};
|
|
|
|
} // namespace ORB_SLAM
|
|
|
|
#endif // MAP_H
|