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


orb_slam2_with_maps_odom
Author(s): teng zhang
autogenerated on Fri Sep 25 2020 03:24:47