forked from UZ-SLAMLab/ORB_SLAM3
-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathKeyFrame.h
544 lines (441 loc) · 16.3 KB
/
KeyFrame.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 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-SLAM3 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-SLAM3.
* If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef KEYFRAME_H
#define KEYFRAME_H
#include "MapPoint.h"
#include "Thirdparty/DBoW2/DBoW2/BowVector.h"
#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
#include "ORBVocabulary.h"
#include "ORBextractor.h"
#include "Frame.h"
#include "KeyFrameDatabase.h"
#include "ImuTypes.h"
#include "GeometricCamera.h"
#include "SerializationUtils.h"
#include <mutex>
#include <boost/serialization/base_object.hpp>
#include <boost/serialization/vector.hpp>
#include <boost/serialization/map.hpp>
namespace ORB_SLAM3
{
class Map;
class MapPoint;
class Frame;
class KeyFrameDatabase;
class GeometricCamera;
class KeyFrame
{
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive& ar, const unsigned int version)
{
ar & mnId;
ar & const_cast<long unsigned int&>(mnFrameId);
ar & const_cast<double&>(mTimeStamp);
// Grid
ar & const_cast<int&>(mnGridCols);
ar & const_cast<int&>(mnGridRows);
ar & const_cast<float&>(mfGridElementWidthInv);
ar & const_cast<float&>(mfGridElementHeightInv);
// Variables of tracking
//ar & mnTrackReferenceForFrame;
//ar & mnFuseTargetForKF;
// Variables of local mapping
//ar & mnBALocalForKF;
//ar & mnBAFixedForKF;
//ar & mnNumberOfOpt;
// Variables used by KeyFrameDatabase
//ar & mnLoopQuery;
//ar & mnLoopWords;
//ar & mLoopScore;
//ar & mnRelocQuery;
//ar & mnRelocWords;
//ar & mRelocScore;
//ar & mnMergeQuery;
//ar & mnMergeWords;
//ar & mMergeScore;
//ar & mnPlaceRecognitionQuery;
//ar & mnPlaceRecognitionWords;
//ar & mPlaceRecognitionScore;
//ar & mbCurrentPlaceRecognition;
// Variables of loop closing
//serializeMatrix(ar,mTcwGBA,version);
//serializeMatrix(ar,mTcwBefGBA,version);
//serializeMatrix(ar,mVwbGBA,version);
//serializeMatrix(ar,mVwbBefGBA,version);
//ar & mBiasGBA;
//ar & mnBAGlobalForKF;
// Variables of Merging
//serializeMatrix(ar,mTcwMerge,version);
//serializeMatrix(ar,mTcwBefMerge,version);
//serializeMatrix(ar,mTwcBefMerge,version);
//serializeMatrix(ar,mVwbMerge,version);
//serializeMatrix(ar,mVwbBefMerge,version);
//ar & mBiasMerge;
//ar & mnMergeCorrectedForKF;
//ar & mnMergeForKF;
//ar & mfScaleMerge;
//ar & mnBALocalForMerge;
// Scale
ar & mfScale;
// Calibration parameters
ar & const_cast<float&>(fx);
ar & const_cast<float&>(fy);
ar & const_cast<float&>(invfx);
ar & const_cast<float&>(invfy);
ar & const_cast<float&>(cx);
ar & const_cast<float&>(cy);
ar & const_cast<float&>(mbf);
ar & const_cast<float&>(mb);
ar & const_cast<float&>(mThDepth);
serializeMatrix(ar, mDistCoef, version);
// Number of Keypoints
ar & const_cast<int&>(N);
// KeyPoints
serializeVectorKeyPoints<Archive>(ar, mvKeys, version);
serializeVectorKeyPoints<Archive>(ar, mvKeysUn, version);
ar & const_cast<vector<float>& >(mvuRight);
ar & const_cast<vector<float>& >(mvDepth);
serializeMatrix<Archive>(ar,mDescriptors,version);
// BOW
ar & mBowVec;
ar & mFeatVec;
// Pose relative to parent
serializeSophusSE3<Archive>(ar, mTcp, version);
// Scale
ar & const_cast<int&>(mnScaleLevels);
ar & const_cast<float&>(mfScaleFactor);
ar & const_cast<float&>(mfLogScaleFactor);
ar & const_cast<vector<float>& >(mvScaleFactors);
ar & const_cast<vector<float>& >(mvLevelSigma2);
ar & const_cast<vector<float>& >(mvInvLevelSigma2);
// Image bounds and calibration
ar & const_cast<int&>(mnMinX);
ar & const_cast<int&>(mnMinY);
ar & const_cast<int&>(mnMaxX);
ar & const_cast<int&>(mnMaxY);
ar & boost::serialization::make_array(mK_.data(), mK_.size());
// Pose
serializeSophusSE3<Archive>(ar, mTcw, version);
// MapPointsId associated to keypoints
ar & mvBackupMapPointsId;
// Grid
ar & mGrid;
// Connected KeyFrameWeight
ar & mBackupConnectedKeyFrameIdWeights;
// Spanning Tree and Loop Edges
ar & mbFirstConnection;
ar & mBackupParentId;
ar & mvBackupChildrensId;
ar & mvBackupLoopEdgesId;
ar & mvBackupMergeEdgesId;
// Bad flags
ar & mbNotErase;
ar & mbToBeErased;
ar & mbBad;
ar & mHalfBaseline;
ar & mnOriginMapId;
// Camera variables
ar & mnBackupIdCamera;
ar & mnBackupIdCamera2;
// Fisheye variables
ar & mvLeftToRightMatch;
ar & mvRightToLeftMatch;
ar & const_cast<int&>(NLeft);
ar & const_cast<int&>(NRight);
serializeSophusSE3<Archive>(ar, mTlr, version);
serializeVectorKeyPoints<Archive>(ar, mvKeysRight, version);
ar & mGridRight;
// Inertial variables
ar & mImuBias;
ar & mBackupImuPreintegrated;
ar & mImuCalib;
ar & mBackupPrevKFId;
ar & mBackupNextKFId;
ar & bImu;
ar & boost::serialization::make_array(mVw.data(), mVw.size());
ar & boost::serialization::make_array(mOwb.data(), mOwb.size());
ar & mbHasVelocity;
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
KeyFrame();
KeyFrame(Frame &F, Map* pMap, KeyFrameDatabase* pKFDB);
// Pose functions
void SetPose(const Sophus::SE3f &Tcw);
void SetVelocity(const Eigen::Vector3f &Vw_);
Sophus::SE3f GetPose();
Sophus::SE3f GetPoseInverse();
Eigen::Vector3f GetCameraCenter();
Eigen::Vector3f GetImuPosition();
Eigen::Matrix3f GetImuRotation();
Sophus::SE3f GetImuPose();
Eigen::Matrix3f GetRotation();
Eigen::Vector3f GetTranslation();
Eigen::Vector3f GetVelocity();
bool isVelocitySet();
// Bag of Words Representation
void ComputeBoW();
// Covisibility graph functions
void AddConnection(KeyFrame* pKF, const int &weight);
void EraseConnection(KeyFrame* pKF);
void UpdateConnections(bool upParent=true);
void UpdateBestCovisibles();
std::set<KeyFrame *> GetConnectedKeyFrames();
std::vector<KeyFrame* > GetVectorCovisibleKeyFrames();
std::vector<KeyFrame*> GetBestCovisibilityKeyFrames(const int &N);
std::vector<KeyFrame*> GetCovisiblesByWeight(const int &w);
int GetWeight(KeyFrame* pKF);
// Spanning tree functions
void AddChild(KeyFrame* pKF);
void EraseChild(KeyFrame* pKF);
void ChangeParent(KeyFrame* pKF);
std::set<KeyFrame*> GetChilds();
KeyFrame* GetParent();
bool hasChild(KeyFrame* pKF);
void SetFirstConnection(bool bFirst);
// Loop Edges
void AddLoopEdge(KeyFrame* pKF);
std::set<KeyFrame*> GetLoopEdges();
// Merge Edges
void AddMergeEdge(KeyFrame* pKF);
set<KeyFrame*> GetMergeEdges();
// MapPoint observation functions
int GetNumberMPs();
void AddMapPoint(MapPoint* pMP, const size_t &idx);
void EraseMapPointMatch(const int &idx);
void EraseMapPointMatch(MapPoint* pMP);
void ReplaceMapPointMatch(const int &idx, MapPoint* pMP);
std::set<MapPoint*> GetMapPoints();
std::vector<MapPoint*> GetMapPointMatches();
int TrackedMapPoints(const int &minObs);
MapPoint* GetMapPoint(const size_t &idx);
// KeyPoint functions
std::vector<size_t> GetFeaturesInArea(const float &x, const float &y, const float &r, const bool bRight = false) const;
bool UnprojectStereo(int i, Eigen::Vector3f &x3D);
// Image
bool IsInImage(const float &x, const float &y) const;
// Enable/Disable bad flag changes
void SetNotErase();
void SetErase();
// Set/check bad flag
void SetBadFlag();
bool isBad();
// Compute Scene Depth (q=2 median). Used in monocular.
float ComputeSceneMedianDepth(const int q);
static bool weightComp( int a, int b){
return a>b;
}
static bool lId(KeyFrame* pKF1, KeyFrame* pKF2){
return pKF1->mnId<pKF2->mnId;
}
Map* GetMap();
void UpdateMap(Map* pMap);
void SetNewBias(const IMU::Bias &b);
Eigen::Vector3f GetGyroBias();
Eigen::Vector3f GetAccBias();
IMU::Bias GetImuBias();
bool ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
bool ProjectPointUnDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
void PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP, set<GeometricCamera*>& spCam);
void PostLoad(map<long unsigned int, KeyFrame*>& mpKFid, map<long unsigned int, MapPoint*>& mpMPid, map<unsigned int, GeometricCamera*>& mpCamId);
void SetORBVocabulary(ORBVocabulary* pORBVoc);
void SetKeyFrameDatabase(KeyFrameDatabase* pKFDB);
bool bImu;
// The following variables are accesed from only 1 thread or never change (no mutex needed).
public:
static long unsigned int nNextId;
long unsigned int mnId;
const long unsigned int mnFrameId;
const double mTimeStamp;
// Grid (to speed up feature matching)
const int mnGridCols;
const int mnGridRows;
const float mfGridElementWidthInv;
const float mfGridElementHeightInv;
// Variables used by the tracking
long unsigned int mnTrackReferenceForFrame;
long unsigned int mnFuseTargetForKF;
// Variables used by the local mapping
long unsigned int mnBALocalForKF;
long unsigned int mnBAFixedForKF;
//Number of optimizations by BA(amount of iterations in BA)
long unsigned int mnNumberOfOpt;
// Variables used by the keyframe database
long unsigned int mnLoopQuery;
int mnLoopWords;
float mLoopScore;
long unsigned int mnRelocQuery;
int mnRelocWords;
float mRelocScore;
long unsigned int mnMergeQuery;
int mnMergeWords;
float mMergeScore;
long unsigned int mnPlaceRecognitionQuery;
int mnPlaceRecognitionWords;
float mPlaceRecognitionScore;
bool mbCurrentPlaceRecognition;
// Variables used by loop closing
Sophus::SE3f mTcwGBA;
Sophus::SE3f mTcwBefGBA;
Eigen::Vector3f mVwbGBA;
Eigen::Vector3f mVwbBefGBA;
IMU::Bias mBiasGBA;
long unsigned int mnBAGlobalForKF;
// Variables used by merging
Sophus::SE3f mTcwMerge;
Sophus::SE3f mTcwBefMerge;
Sophus::SE3f mTwcBefMerge;
Eigen::Vector3f mVwbMerge;
Eigen::Vector3f mVwbBefMerge;
IMU::Bias mBiasMerge;
long unsigned int mnMergeCorrectedForKF;
long unsigned int mnMergeForKF;
float mfScaleMerge;
long unsigned int mnBALocalForMerge;
float mfScale;
// Calibration parameters
const float fx, fy, cx, cy, invfx, invfy, mbf, mb, mThDepth;
cv::Mat mDistCoef;
// Number of KeyPoints
const int N;
// KeyPoints, stereo coordinate and descriptors (all associated by an index)
const std::vector<cv::KeyPoint> mvKeys;
const std::vector<cv::KeyPoint> mvKeysUn;
const std::vector<float> mvuRight; // negative value for monocular points
const std::vector<float> mvDepth; // negative value for monocular points
const cv::Mat mDescriptors;
//BoW
DBoW2::BowVector mBowVec;
DBoW2::FeatureVector mFeatVec;
// Pose relative to parent (this is computed when bad flag is activated)
Sophus::SE3f mTcp;
// Scale
const int mnScaleLevels;
const float mfScaleFactor;
const float mfLogScaleFactor;
const std::vector<float> mvScaleFactors;
const std::vector<float> mvLevelSigma2;
const std::vector<float> mvInvLevelSigma2;
// Image bounds and calibration
const int mnMinX;
const int mnMinY;
const int mnMaxX;
const int mnMaxY;
// Preintegrated IMU measurements from previous keyframe
KeyFrame* mPrevKF;
KeyFrame* mNextKF;
IMU::Preintegrated* mpImuPreintegrated;
IMU::Calib mImuCalib;
unsigned int mnOriginMapId;
string mNameFile;
int mnDataset;
std::vector <KeyFrame*> mvpLoopCandKFs;
std::vector <KeyFrame*> mvpMergeCandKFs;
//bool mbHasHessian;
//cv::Mat mHessianPose;
// The following variables need to be accessed trough a mutex to be thread safe.
protected:
// sophus poses
Sophus::SE3<float> mTcw;
Eigen::Matrix3f mRcw;
Sophus::SE3<float> mTwc;
Eigen::Matrix3f mRwc;
// IMU position
Eigen::Vector3f mOwb;
// Velocity (Only used for inertial SLAM)
Eigen::Vector3f mVw;
bool mbHasVelocity;
//Transformation matrix between cameras in stereo fisheye
Sophus::SE3<float> mTlr;
Sophus::SE3<float> mTrl;
// Imu bias
IMU::Bias mImuBias;
// MapPoints associated to keypoints
std::vector<MapPoint*> mvpMapPoints;
// For save relation without pointer, this is necessary for save/load function
std::vector<long long int> mvBackupMapPointsId;
// BoW
KeyFrameDatabase* mpKeyFrameDB;
ORBVocabulary* mpORBvocabulary;
// Grid over the image to speed up feature matching
std::vector< std::vector <std::vector<size_t> > > mGrid;
std::map<KeyFrame*,int> mConnectedKeyFrameWeights;
std::vector<KeyFrame*> mvpOrderedConnectedKeyFrames;
std::vector<int> mvOrderedWeights;
// For save relation without pointer, this is necessary for save/load function
std::map<long unsigned int, int> mBackupConnectedKeyFrameIdWeights;
// Spanning Tree and Loop Edges
bool mbFirstConnection;
KeyFrame* mpParent;
std::set<KeyFrame*> mspChildrens;
std::set<KeyFrame*> mspLoopEdges;
std::set<KeyFrame*> mspMergeEdges;
// For save relation without pointer, this is necessary for save/load function
long long int mBackupParentId;
std::vector<long unsigned int> mvBackupChildrensId;
std::vector<long unsigned int> mvBackupLoopEdgesId;
std::vector<long unsigned int> mvBackupMergeEdgesId;
// Bad flags
bool mbNotErase;
bool mbToBeErased;
bool mbBad;
float mHalfBaseline; // Only for visualization
Map* mpMap;
// Backup variables for inertial
long long int mBackupPrevKFId;
long long int mBackupNextKFId;
IMU::Preintegrated mBackupImuPreintegrated;
// Backup for Cameras
unsigned int mnBackupIdCamera, mnBackupIdCamera2;
// Calibration
Eigen::Matrix3f mK_;
// Mutex
std::mutex mMutexPose; // for pose, velocity and biases
std::mutex mMutexConnections;
std::mutex mMutexFeatures;
std::mutex mMutexMap;
public:
GeometricCamera* mpCamera, *mpCamera2;
//Indexes of stereo observations correspondences
std::vector<int> mvLeftToRightMatch, mvRightToLeftMatch;
Sophus::SE3f GetRelativePoseTrl();
Sophus::SE3f GetRelativePoseTlr();
//KeyPoints in the right image (for stereo fisheye, coordinates are needed)
const std::vector<cv::KeyPoint> mvKeysRight;
const int NLeft, NRight;
std::vector< std::vector <std::vector<size_t> > > mGridRight;
Sophus::SE3<float> GetRightPose();
Sophus::SE3<float> GetRightPoseInverse();
Eigen::Vector3f GetRightCameraCenter();
Eigen::Matrix<float,3,3> GetRightRotation();
Eigen::Vector3f GetRightTranslation();
void PrintPointDistribution(){
int left = 0, right = 0;
int Nlim = (NLeft != -1) ? NLeft : N;
for(int i = 0; i < N; i++){
if(mvpMapPoints[i]){
if(i < Nlim) left++;
else right++;
}
}
cout << "Point distribution in KeyFrame: left-> " << left << " --- right-> " << right << endl;
}
};
} //namespace ORB_SLAM
#endif // KEYFRAME_H