ORB SLA2
KeyFrame.h
1 
21 #ifndef KEYFRAME_H
22 #define KEYFRAME_H
23 
24 #include "MapPoint.h"
25 #include "Thirdparty/DBoW2/DBoW2/BowVector.h"
26 #include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
27 #include "ORBVocabulary.h"
28 #include "ORBextractor.h"
29 #include "Frame.h"
30 #include "KeyFrameDatabase.h"
31 
32 #include <mutex>
33 
34 
35 namespace ORB_SLAM2
36 {
37 
38 class Map;
39 class MapPoint;
40 class Frame;
41 class KeyFrameDatabase;
42 
43 class KeyFrame
44 {
45 public:
46  KeyFrame(Frame &F, Map* pMap, KeyFrameDatabase* pKFDB);
47 
48  // Pose functions
49  void SetPose(const cv::Mat &Tcw);
50  cv::Mat GetPose();
51  cv::Mat GetPoseInverse();
52  cv::Mat GetCameraCenter();
53  cv::Mat GetStereoCenter();
54  cv::Mat GetRotation();
55  cv::Mat GetTranslation();
56 
57  // Bag of Words Representation
58  void ComputeBoW();
59 
60  // Covisibility graph functions
61  void AddConnection(KeyFrame* pKF, const int &weight);
62  void EraseConnection(KeyFrame* pKF);
63  void UpdateConnections();
64  void UpdateBestCovisibles();
65  std::set<KeyFrame *> GetConnectedKeyFrames();
66  std::vector<KeyFrame* > GetVectorCovisibleKeyFrames();
67  std::vector<KeyFrame*> GetBestCovisibilityKeyFrames(const int &N);
68  std::vector<KeyFrame*> GetCovisiblesByWeight(const int &w);
69  int GetWeight(KeyFrame* pKF);
70 
71  // Spanning tree functions
72  void AddChild(KeyFrame* pKF);
73  void EraseChild(KeyFrame* pKF);
74  void ChangeParent(KeyFrame* pKF);
75  std::set<KeyFrame*> GetChilds();
76  KeyFrame* GetParent();
77  bool hasChild(KeyFrame* pKF);
78 
79  // Loop Edges
80  void AddLoopEdge(KeyFrame* pKF);
81  std::set<KeyFrame*> GetLoopEdges();
82 
83  // MapPoint observation functions
84  void AddMapPoint(MapPoint* pMP, const size_t &idx);
85  void EraseMapPointMatch(const size_t &idx);
86  void EraseMapPointMatch(MapPoint* pMP);
87  void ReplaceMapPointMatch(const size_t &idx, MapPoint* pMP);
88  std::set<MapPoint*> GetMapPoints();
89  std::vector<MapPoint*> GetMapPointMatches();
90  int TrackedMapPoints(const int &minObs);
91  MapPoint* GetMapPoint(const size_t &idx);
92 
93  // KeyPoint functions
94  std::vector<size_t> GetFeaturesInArea(const float &x, const float &y, const float &r) const;
95  cv::Mat UnprojectStereo(int i);
96 
97  // Image
98  bool IsInImage(const float &x, const float &y) const;
99 
100  // Enable/Disable bad flag changes
101  void SetNotErase();
102  void SetErase();
103 
104  // Set/check bad flag
105  void SetBadFlag();
106  bool isBad();
107 
108  // Compute Scene Depth (q=2 median). Used in monocular.
109  float ComputeSceneMedianDepth(const int q);
110 
111  static bool weightComp( int a, int b){
112  return a>b;
113  }
114 
115  static bool lId(KeyFrame* pKF1, KeyFrame* pKF2){
116  return pKF1->mnId<pKF2->mnId;
117  }
118 
119 
120  // The following variables are accesed from only 1 thread or never change (no mutex needed).
121 public:
122 
123  static long unsigned int nNextId;
124  long unsigned int mnId;
125  const long unsigned int mnFrameId;
126 
127  const double mTimeStamp;
128 
129  // Grid (to speed up feature matching)
130  const int mnGridCols;
131  const int mnGridRows;
132  const float mfGridElementWidthInv;
133  const float mfGridElementHeightInv;
134 
135  // Variables used by the tracking
136  long unsigned int mnTrackReferenceForFrame;
137  long unsigned int mnFuseTargetForKF;
138 
139  // Variables used by the local mapping
140  long unsigned int mnBALocalForKF;
141  long unsigned int mnBAFixedForKF;
142 
143  // Variables used by the keyframe database
144  long unsigned int mnLoopQuery;
145  int mnLoopWords;
146  float mLoopScore;
147  long unsigned int mnRelocQuery;
148  int mnRelocWords;
149  float mRelocScore;
150 
151  // Variables used by loop closing
152  cv::Mat mTcwGBA;
153  cv::Mat mTcwBefGBA;
154  long unsigned int mnBAGlobalForKF;
155 
156  // Calibration parameters
157  const float fx, fy, cx, cy, invfx, invfy, mbf, mb, mThDepth;
158 
159  // Number of KeyPoints
160  const int N;
161 
162  // KeyPoints, stereo coordinate and descriptors (all associated by an index)
163  const std::vector<cv::KeyPoint> mvKeys;
164  const std::vector<cv::KeyPoint> mvKeysUn;
165  const std::vector<float> mvuRight; // negative value for monocular points
166  const std::vector<float> mvDepth; // negative value for monocular points
167  const cv::Mat mDescriptors;
168 
169  //BoW
170  DBoW2::BowVector mBowVec;
171  DBoW2::FeatureVector mFeatVec;
172 
173  // Pose relative to parent (this is computed when bad flag is activated)
174  cv::Mat mTcp;
175 
176  // Scale
177  const int mnScaleLevels;
178  const float mfScaleFactor;
179  const float mfLogScaleFactor;
180  const std::vector<float> mvScaleFactors;
181  const std::vector<float> mvLevelSigma2;
182  const std::vector<float> mvInvLevelSigma2;
183 
184  // Image bounds and calibration
185  const int mnMinX;
186  const int mnMinY;
187  const int mnMaxX;
188  const int mnMaxY;
189  const cv::Mat mK;
190 
191 
192  // The following variables need to be accessed trough a mutex to be thread safe.
193 protected:
194 
195  // SE3 Pose and camera center
196  cv::Mat Tcw;
197  cv::Mat Twc;
198  cv::Mat Ow;
199 
200  cv::Mat Cw; // Stereo middel point. Only for visualization
201 
202  // MapPoints associated to keypoints
203  std::vector<MapPoint*> mvpMapPoints;
204 
205  // BoW
206  KeyFrameDatabase* mpKeyFrameDB;
207  ORBVocabulary* mpORBvocabulary;
208 
209  // Grid over the image to speed up feature matching
210  std::vector< std::vector <std::vector<size_t> > > mGrid;
211 
212  std::map<KeyFrame*,int> mConnectedKeyFrameWeights;
213  std::vector<KeyFrame*> mvpOrderedConnectedKeyFrames;
214  std::vector<int> mvOrderedWeights;
215 
216  // Spanning Tree and Loop Edges
217  bool mbFirstConnection;
218  KeyFrame* mpParent;
219  std::set<KeyFrame*> mspChildrens;
220  std::set<KeyFrame*> mspLoopEdges;
221 
222  // Bad flags
223  bool mbNotErase;
224  bool mbToBeErased;
225  bool mbBad;
226 
227  float mHalfBaseline; // Only for visualization
228 
229  Map* mpMap;
230 
231  std::mutex mMutexPose;
232  std::mutex mMutexConnections;
233  std::mutex mMutexFeatures;
234 };
235 
236 } //namespace ORB_SLAM
237 
238 #endif // KEYFRAME_H
Definition: KeyFrame.h:43
Definition: KeyFrameDatabase.h:42
Definition: Frame.h:43
Definition: Converter.cpp:24
Definition: MapPoint.h:39
Definition: Map.h:38