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


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05