SLProject  4.2.000
A platform independent 3D computer graphics framework for desktop OS, Android, iOS and online in web browsers
WAIMap.h
Go to the documentation of this file.
1 /**
2  * \file SLCVMap.h
3  * \authors Michael Goettlicher
4  * \date October 2017
5 // Codestyle: https://github.com/cpvrlab/SLProject/wiki/Coding-Style-Guidelines
6  * \authors Marcus Hudritsch
7  * \copyright http://opensource.org/licenses/GPL-3.0
8 */
9 
10 /**
11  * This file is part of ORB-SLAM2.
12  *
13  * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
14  * For more information see <https://github.com/raulmur/ORB_SLAM2>
15  *
16  * ORB-SLAM2 is free software: you can redistribute it and/or modify
17  * it under the terms of the GNU General Public License as published by
18  * the Free Software Foundation, either version 3 of the License, or
19  * (at your option) any later version.
20  *
21  * ORB-SLAM2 is distributed in the hope that it will be useful,
22  * but WITHOUT ANY WARRANTY; without even the implied warranty of
23  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
24  * GNU General Public License for more details.
25  *
26  * You should have received a copy of the GNU General Public License
27  * along with ORB-SLAM2. If not, see <http://www.gnu.org/licenses/>.
28  */
29 
30 #ifndef WAIMAP_H
31 #define WAIMAP_H
32 
33 #include <vector>
34 #include <string>
35 #include <mutex>
36 #include <set>
37 
38 #include <opencv2/core.hpp>
39 
40 #include <WAIMapPoint.h>
41 #include <WAIKeyFrameDB.h>
42 #include <WAIKeyFrame.h>
43 #include <WAIHelper.h>
44 
45 using namespace std;
46 
47 //-----------------------------------------------------------------------------
48 //!
49 /*!
50  */
52 {
53 public:
55  {
56  ROT_X = 0,
62  SCALE
63  };
64 
65  WAIMap(WAIKeyFrameDB* kfDB);
66  ~WAIMap();
67 
68  void AddKeyFrame(WAIKeyFrame* pKF);
69  void AddMapPoint(WAIMapPoint* pMP);
70  void EraseMapPoint(WAIMapPoint* pMP);
71  void EraseKeyFrame(WAIKeyFrame* pKF);
72  void SetReferenceMapPoints(const std::vector<WAIMapPoint*>& vpMPs);
73  void InformNewBigChange();
74  int GetLastBigChangeIdx();
75 
76  std::vector<WAIKeyFrame*> GetAllKeyFrames();
77  std::vector<WAIMapPoint*> GetAllMapPoints();
78  WAIKeyFrameDB* GetKeyFrameDB() { return mKfDB; }
79 
80  long unsigned int MapPointsInMap();
81  long unsigned int KeyFramesInMap();
82 
83  long unsigned int GetMaxKFid();
84 
85  float GetSize();
86  void clear();
87 
88  vector<WAIKeyFrame*> mvpKeyFrameOrigins;
89 
90  std::mutex mMutexMapUpdate;
91 
92  // This avoid that two points are created simultaneously in separate threads (id conflict)
93  std::mutex mMutexPointCreation;
94 
95  //transformation functions
96  void transform(cv::Mat transform);
97  void rotate(float degVal, int type);
98  void translate(float value, int type);
99  void scale(float value);
100  void applyTransformation(double value, TransformType type);
101  cv::Mat buildTransMat(float& val, int type);
102  cv::Mat buildRotMat(float& valDeg, int type);
103 
104  size_t getSizeOf();
105 
106  bool isKeyFrameInMap(WAIKeyFrame* pKF);
107 
108  void incNumLoopClosings();
109  void setNumLoopClosings(int n);
110  int getNumLoopClosings();
111 
112 protected:
113  std::set<WAIMapPoint*> mspMapPoints;
114  std::set<WAIKeyFrame*> mspKeyFrames;
115  std::vector<WAIKeyFrame*> _deletedKeyFrames;
116  WAIKeyFrameDB* mKfDB{nullptr};
117 
118  std::vector<WAIMapPoint*> mvpReferenceMapPoints;
119 
120  long unsigned int mnMaxKFid;
121 
122  // Index related to a big change in the map (loop closure, global BA)
124 
125  std::mutex mMutexMap;
126 
127  std::mutex _mutexLoopClosings;
128  int _numberOfLoopClosings = 0;
130 };
131 
132 #endif // !WAIMAP_H
#define WAI_API
Definition: WAIHelper.h:36
AR Keyframe database class.
Definition: WAIKeyFrameDB.h:46
AR Keyframe node class.
Definition: WAIKeyFrame.h:60
Definition: WAIMap.h:52
vector< WAIKeyFrame * > mvpKeyFrameOrigins
Definition: WAIMap.h:88
int mnBigChangeIdx
Definition: WAIMap.h:123
std::vector< WAIKeyFrame * > _deletedKeyFrames
Definition: WAIMap.h:115
std::vector< WAIMapPoint * > mvpReferenceMapPoints
Definition: WAIMap.h:118
long unsigned int mnMaxKFid
Definition: WAIMap.h:120
std::set< WAIMapPoint * > mspMapPoints
Definition: WAIMap.h:113
std::mutex mMutexMapUpdate
Definition: WAIMap.h:90
TransformType
Definition: WAIMap.h:55
@ TRANS_Z
Definition: WAIMap.h:61
@ ROT_Y
Definition: WAIMap.h:57
@ ROT_Z
Definition: WAIMap.h:58
@ TRANS_X
Definition: WAIMap.h:59
@ TRANS_Y
Definition: WAIMap.h:60
std::mutex mMutexMap
Definition: WAIMap.h:125
std::mutex mMutexPointCreation
Definition: WAIMap.h:93
WAIKeyFrameDB * GetKeyFrameDB()
Definition: WAIMap.h:78
int _numOfKeyframes
Definition: WAIMap.h:129
std::mutex _mutexLoopClosings
Definition: WAIMap.h:127
std::set< WAIKeyFrame * > mspKeyFrames
Definition: WAIMap.h:114
void clear(std::string path)
Definition: SLIOMemory.cpp:34