-
Notifications
You must be signed in to change notification settings - Fork 70
/
Frame.cc
3403 lines (2798 loc) · 124 KB
/
Frame.cc
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
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* This file is part of PLVS.
* Copyright (C) 2018-present Luigi Freda <luigifreda at gmail dot com>
*
* This program 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.
*
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* 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/>.
*/
#include "Frame.h"
#include "G2oTypes.h"
#include "MapPoint.h"
#include "KeyFrame.h"
#include "ORBextractor.h"
#include "Converter.h"
#include "ORBmatcher.h"
#include "GeometricCamera.h"
#include "MapLine.h"
#include "Utils.h"
#include "LineMatcher.h"
#include "Tracking.h"
#include "Geom2DUtils.h"
#include "Stopwatch.h"
#include "Utils.h"
#include "Geom2DUtils.h"
#if RERUN_ENABLED
#include "RerunSingleton.h"
#endif
#include <thread>
#include <include/CameraModels/Pinhole.h>
#include <include/CameraModels/KannalaBrandt8.h>
#define LOG_ASSIGN_FEATURES 0
#define CHECK_RGBD_ENDPOINTS_DEPTH_CONSISTENCY 1
#define USE_PARALLEL_POINTS_LINES_EXTRACTION 1
#define USE_UNFILTERED_PYRAMID_FOR_LINES 1 // N.B.: AT PRESENT TIME, it's better not to use the filtered pyramid! We prefer to use the unfiltered pyramid.
// This is because a Gaussian filter is added in keylines extraction when a pre-computed pyramid is set.
// In fact, the keypoint Gaussian filter is too strong for keyline extraction (it blurs the image too much!)
#define DISABLE_STATIC_LINE_TRIANGULATION 0 // Set this to 1 to check how local mapping is able to triangulate lines without using any static stereo line triangulation
#define KEEP_IMGAGES 0 // Clone the input images and keep them for debugging in the case of mono, stereo and rgbd. Note that, in the case of fisheye cameras, the images are kept by default
#define VISUALIZE_LINE_MATCHES 0 && RERUN_ENABLED
#if LOG_ASSIGN_FEATURES
#include "Logger.h"
static const string logFileName = "assign_feature.log";
static Logger logger(logFileName);
#endif
namespace PLVS2
{
long unsigned int Frame::nNextId=0;
bool Frame::mbInitialComputations=true;
bool Frame::mbUseFovCentersKfGenCriterion = false;
float Frame::cx, Frame::cy, Frame::fx, Frame::fy, Frame::invfx, Frame::invfy;
float Frame::mnMinX, Frame::mnMinY, Frame::mnMaxX, Frame::mnMaxY;
float Frame::mfGridElementWidthInv, Frame::mfGridElementHeightInv;
float Frame::mfLineGridElementThetaInv, Frame::mfLineGridElementDInv;
float Frame::mnMaxDiag;
const std::vector<size_t> Frame::kEmptyVecSizet = std::vector<size_t>();
const float Frame::kDeltaTheta = 10 * M_PI/180.f;// [rad] 10
const float Frame::kDeltaD = 100; //[pixels] 100
const float Frame::kTgViewZAngleMin = tan(30. *M_PI/180.f);
const float Frame::kCosViewZAngleMax = cos(30. *M_PI/180.f);
const float Frame::kDeltaZForCheckingViewZAngleMin = 0.02; // [m]
const float Frame::kDeltaZThresholdForRefiningEndPointsDepths = 0.0; // [m]
const float Frame::kLinePointsMaxMisalignment = 0.03; // [m]
const int Frame::kDeltaSizeForSearchingDepthMinMax = 1;
const float Frame::kMinStereoLineOverlap = 2; // [pixels] (for pure horizontal lines one has minimum = 1)
const float Frame::kLineNormalsDotProdThreshold = 0.005; // this a percentage over unitary modulus
const float Frame::kMinVerticalLineSpan = 2; // [pixels] should be startY-endY>kMinVerticalLineSpan in order to avoid line too close to an epipolar plane (degeneracy in line triangulation)
const int Frame::kMaxInt = std::numeric_limits<int>::max();
float Frame::skMinLineLength3D = 0.01; // [m]
//For stereo fisheye matching
cv::BFMatcher Frame::BFmatcher = cv::BFMatcher(cv::NORM_HAMMING);
Frame::Frame(): mpcpi(NULL), mpImuPreintegrated(NULL), mpPrevFrame(NULL), mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast<KeyFramePtr>(NULL)),
mbIsSet(false), mbImuPreintegrated(false), mbHasPose(false), mbHasVelocity(false)
{
#ifdef REGISTER_TIMES
mTimeStereoMatch = 0;
mTimeORB_Ext = 0;
#endif
}
//Copy Constructor
Frame::Frame(const Frame &frame)
:mpcpi(frame.mpcpi),
mpORBvocabulary(frame.mpORBvocabulary), mpORBextractorLeft(frame.mpORBextractorLeft), mpORBextractorRight(frame.mpORBextractorRight),
mTimeStamp(frame.mTimeStamp), mK(frame.mK.clone()), mK_(Converter::toMatrix3f(frame.mK)), mDistCoef(frame.mDistCoef.clone()),
mbf(frame.mbf), mbfInv(frame.mbfInv), mb(frame.mb), mThDepth(frame.mThDepth),
N(frame.N),
mvKeys(frame.mvKeys), mvKeysRight(frame.mvKeysRight), mvKeysUn(frame.mvKeysUn),
mvuRight(frame.mvuRight), mvDepth(frame.mvDepth),
mBowVec(frame.mBowVec), mFeatVec(frame.mFeatVec),
mDescriptors(frame.mDescriptors.clone()), mDescriptorsRight(frame.mDescriptorsRight.clone()), // clone point descriptors
mvpMapPoints(frame.mvpMapPoints), mvbOutlier(frame.mvbOutlier),
mImuCalib(frame.mImuCalib), mnCloseMPs(frame.mnCloseMPs),
mpImuPreintegrated(frame.mpImuPreintegrated), mpImuPreintegratedFrame(frame.mpImuPreintegratedFrame), mImuBias(frame.mImuBias),
mnId(frame.mnId),
Nlines(frame.Nlines),
mvKeyLines(frame.mvKeyLines), mvKeyLinesRight(frame.mvKeyLinesRight), mvKeyLinesUn(frame.mvKeyLinesUn), mvKeyLinesRightUn(frame.mvKeyLinesRightUn),
mvuRightLineStart(frame.mvuRightLineStart), mvDepthLineStart(frame.mvDepthLineStart), mvuRightLineEnd(frame.mvuRightLineEnd), mvDepthLineEnd(frame.mvDepthLineEnd),
mLineDescriptors(frame.mLineDescriptors.clone()), mLineDescriptorsRight(frame.mLineDescriptorsRight.clone()), // clone line descriptors
mvpMapLines(frame.mvpMapLines), mvbLineOutlier(frame.mvbLineOutlier), mvuNumLinePosOptFailures(frame.mvuNumLinePosOptFailures),
mpReferenceKF(frame.mpReferenceKF), mnScaleLevels(frame.mnScaleLevels),
mfScaleFactor(frame.mfScaleFactor), mfLogScaleFactor(frame.mfLogScaleFactor),
mvScaleFactors(frame.mvScaleFactors), mvInvScaleFactors(frame.mvInvScaleFactors),
mNameFile(frame.mNameFile), mnDataset(frame.mnDataset),
mvLevelSigma2(frame.mvLevelSigma2), mvInvLevelSigma2(frame.mvInvLevelSigma2),
mpPrevFrame(frame.mpPrevFrame), mpLastKeyFrame(frame.mpLastKeyFrame),
mbIsSet(frame.mbIsSet),
mbImuPreintegrated(frame.mbImuPreintegrated), mpMutexImu(frame.mpMutexImu),
mpCamera(frame.mpCamera), mpCamera2(frame.mpCamera2),
Nleft(frame.Nleft), Nright(frame.Nright),
monoLeft(frame.monoLeft), monoRight(frame.monoRight), mvLeftToRightMatch(frame.mvLeftToRightMatch),
mvRightToLeftMatch(frame.mvRightToLeftMatch), mvStereo3Dpoints(frame.mvStereo3Dpoints),
NlinesLeft(frame.NlinesLeft), NlinesRight(frame.NlinesRight),
monoLinesLeft(frame.monoLinesLeft), monoLinesRight(frame.monoLinesRight),
mvLeftToRightLinesMatch(frame.mvLeftToRightLinesMatch), mvRightToLeftLinesMatch(frame.mvRightToLeftLinesMatch),
mTlr(frame.mTlr), mRlr(frame.mRlr), mtlr(frame.mtlr), mTrl(frame.mTrl),
mTcw(frame.mTcw),
mnLineScaleLevels(frame.mnLineScaleLevels),
mfLineScaleFactor(frame.mfLineScaleFactor), mfLineLogScaleFactor(frame.mfLineLogScaleFactor),
mvLineScaleFactors(frame.mvLineScaleFactors),
mvLineLevelSigma2(frame.mvLineLevelSigma2), mvLineInvLevelSigma2(frame.mvLineInvLevelSigma2),
mMedianDepth(frame.mMedianDepth),
mbHasPose(false), mbHasVelocity(false)
{
for(int i=0;i<FRAME_GRID_COLS;i++)
for(int j=0; j<FRAME_GRID_ROWS; j++){
mGrid[i][j]=frame.mGrid[i][j];
if(frame.Nleft > 0){
mGridRight[i][j] = frame.mGridRight[i][j];
}
}
if(frame.mpLineExtractorLeft)
{
for(int i=0;i<LINE_D_GRID_COLS;i++)
for(int j=0; j<LINE_THETA_GRID_ROWS; j++) {
mLineGrid[i][j]=frame.mLineGrid[i][j];
if(frame.NlinesLeft > 0){
mLineGridRight[i][j] = frame.mLineGridRight[i][j];
}
}
}
if(frame.mbHasPose)
SetPose(frame.GetPose());
if(frame.HasVelocity())
{
SetVelocity(frame.GetVelocity());
}
// mmProjectPoints = frame.mmProjectPoints;
// mmMatchedInImage = frame.mmMatchedInImage;
// mmProjectLines = frame.mmProjectLines;
// mmMatchedLinesInImage = frame.mmMatchedLinesInImage;
#ifdef REGISTER_TIMES
mTimeStereoMatch = frame.mTimeStereoMatch;
mTimeORB_Ext = frame.mTimeORB_Ext;
#endif
}
/// < STEREO
Frame::Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp,
std::shared_ptr<LineExtractor>& lineExtractorLeft, std::shared_ptr<LineExtractor>& lineExtractorRight,
ORBextractor* extractorLeft, ORBextractor* extractorRight, ORBVocabulary* voc,
cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera, Frame* pPrevF, const IMU::Calib &ImuCalib)
:mpcpi(NULL), mpLineExtractorLeft(lineExtractorLeft),mpLineExtractorRight(lineExtractorRight),
mpORBvocabulary(voc),mpORBextractorLeft(extractorLeft),mpORBextractorRight(extractorRight), mTimeStamp(timeStamp), mK(K.clone()),
mK_(Converter::toMatrix3f(K)),
mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth),
mImuCalib(ImuCalib), mpImuPreintegrated(NULL), mpPrevFrame(pPrevF),mpImuPreintegratedFrame(NULL),
mpReferenceKF(static_cast<KeyFramePtr>(NULL)), Nlines(0),
mMedianDepth(KeyFrame::skFovCenterDistance),
mbIsSet(false), mbImuPreintegrated(false),
mpCamera(pCamera) ,mpCamera2(nullptr), mbHasPose(false), mbHasVelocity(false)
{
// Frame ID
mnId=nNextId++;
#if KEEP_IMGAGES
this->imgLeft = imLeft.clone();
this->imgRight = imRight.clone();
#endif
// Scale Level Info
mnScaleLevels = mpORBextractorLeft->GetLevels();
mfScaleFactor = mpORBextractorLeft->GetScaleFactor();
mfLogScaleFactor = log(mfScaleFactor);
mvScaleFactors = mpORBextractorLeft->GetScaleFactors();
mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors();
mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares();
mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares();
if(mpLineExtractorLeft)
{
mnLineScaleLevels = mpLineExtractorLeft->GetLevels();
mfLineScaleFactor = mpLineExtractorLeft->GetScaleFactor();
mfLineLogScaleFactor = log(mfLineScaleFactor);
mvLineScaleFactors = mpLineExtractorLeft->GetScaleFactors();
mvLineLevelSigma2 = mpLineExtractorLeft->GetScaleSigmaSquares();
mvLineInvLevelSigma2 = mpLineExtractorLeft->GetInverseScaleSigmaSquares();
}
// This is done only for the first Frame (or after a change in the calibration)
if(mbInitialComputations)
{
ComputeImageBounds(imLeft);
mfGridElementWidthInv=static_cast<float>(FRAME_GRID_COLS)/static_cast<float>(mnMaxX-mnMinX);
mfGridElementHeightInv=static_cast<float>(FRAME_GRID_ROWS)/static_cast<float>(mnMaxY-mnMinY);
mfLineGridElementThetaInv=static_cast<float>(LINE_THETA_GRID_ROWS)/static_cast<float>(LINE_THETA_SPAN);
mfLineGridElementDInv=static_cast<float>(LINE_D_GRID_COLS)/(2.0f*mnMaxDiag);
fx = K.at<float>(0,0);
fy = K.at<float>(1,1);
cx = K.at<float>(0,2);
cy = K.at<float>(1,2);
invfx = 1.0f/fx;
invfy = 1.0f/fy;
mbInitialComputations=false;
}
mb = mbf/fx;
mbfInv = 1.f/mbf;
if(pPrevF)
{
if(pPrevF->HasVelocity())
SetVelocity(pPrevF->GetVelocity());
}
else
{
mVw.setZero();
}
// Features extraction
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartExtORB = std::chrono::steady_clock::now();
#endif
if(mpLineExtractorLeft)
{
#ifndef USE_CUDA
if( Tracking::skUsePyramidPrecomputation )
{
// pre-compute Gaussian pyramid to be used for the extraction of both keypoints and keylines
std::thread threadGaussianLeft(&Frame::PrecomputeGaussianPyramid,this,0,imLeft);
std::thread threadGaussianRight(&Frame::PrecomputeGaussianPyramid,this,1,imRight);
threadGaussianLeft.join();
threadGaussianRight.join();
}
#else
if( Tracking::skUsePyramidPrecomputation )
{
std::cout << IoColor::Yellow() << "Can't use pyramid precomputation when CUDA is active!" << std::endl;
}
#endif
// ORB extraction
thread threadLeft(&Frame::ExtractORB,this,0,imLeft,0,0);
thread threadRight(&Frame::ExtractORB,this,1,imRight,0,0);
// Line extraction
std::thread threadLinesLeft(&Frame::ExtractLSD,this,0,imLeft);
std::thread threadLinesRight(&Frame::ExtractLSD,this,1,imRight);
threadLeft.join();
threadRight.join();
threadLinesLeft.join();
threadLinesRight.join();
}
else
{
// ORB extraction
thread threadLeft(&Frame::ExtractORB,this,0,imLeft,0,0);
thread threadRight(&Frame::ExtractORB,this,1,imRight,0,0);
threadLeft.join();
threadRight.join();
}
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndExtORB = std::chrono::steady_clock::now();
mTimeORB_Ext = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndExtORB - time_StartExtORB).count();
#endif
N = mvKeys.size();
if(mvKeys.empty())
return;
UndistortKeyPoints();
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartStereoMatches = std::chrono::steady_clock::now();
#endif
ComputeStereoMatches();
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndStereoMatches = std::chrono::steady_clock::now();
mTimeStereoMatch = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndStereoMatches - time_StartStereoMatches).count();
#endif
mvpMapPoints = vector<MapPointPtr>(N,static_cast<MapPointPtr>(NULL));
mvbOutlier = vector<bool>(N,false);
// mmProjectPoints.clear();
// mmMatchedInImage.clear();
// LSD line segments extraction
if(mpLineExtractorLeft)
{
Nlines = mvKeyLines.size();
if(mvKeyLines.empty())
{
std::cout << "frame " << mnId << " no lines dectected!" << std::endl;
}
else
{
UndistortKeyLines();
ComputeStereoLineMatches();
}
mvpMapLines = vector<MapLinePtr>(Nlines,static_cast<MapLinePtr>(NULL));
mvbLineOutlier = vector<bool>(Nlines,false);
mvuNumLinePosOptFailures = vector<unsigned int>(Nlines,0);
// mmProjectLines.clear();// = map<long unsigned int, LineEndPoints>(N, static_cast<LineEndPoints>(NULL));
// mmMatchedLinesInImage.clear();
}
mpMutexImu = new std::mutex();
//Set no stereo fisheye information
Nleft = -1;
Nright = -1;
mvLeftToRightMatch = vector<int>(0);
mvRightToLeftMatch = vector<int>(0);
mvStereo3Dpoints = vector<Eigen::Vector3f>(0);
monoLeft = -1;
monoRight = -1;
AssignFeaturesToGrid(); //NOTE: this must stay after having initialized Nleft and Nright
}
/// < RGBD
Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp,
std::shared_ptr<LineExtractor>& lineExtractor,
ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera,Frame* pPrevF, const IMU::Calib &ImuCalib)
:mpcpi(NULL),
mpLineExtractorLeft(lineExtractor),mpLineExtractorRight(0),
mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast<ORBextractor*>(NULL)),
mTimeStamp(timeStamp), mK(K.clone()), mK_(Converter::toMatrix3f(K)),
mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth),
Nlines(0),
mImuCalib(ImuCalib), mpImuPreintegrated(NULL), mpPrevFrame(pPrevF), mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast<KeyFramePtr>(NULL)),
mbIsSet(false), mbImuPreintegrated(false),
mpCamera(pCamera),mpCamera2(nullptr),
mMedianDepth(KeyFrame::skFovCenterDistance),
mbHasPose(false), mbHasVelocity(false)
{
// Frame ID
mnId=nNextId++;
#if KEEP_IMGAGES
this->imgLeft = imGray.clone(); // just needed for debugging and viz purposes
#endif
// Scale Level Info
mnScaleLevels = mpORBextractorLeft->GetLevels();
mfScaleFactor = mpORBextractorLeft->GetScaleFactor();
mfLogScaleFactor = log(mfScaleFactor);
mvScaleFactors = mpORBextractorLeft->GetScaleFactors();
mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors();
mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares();
mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares();
if(mpLineExtractorLeft)
{
mnLineScaleLevels = mpLineExtractorLeft->GetLevels();
mfLineScaleFactor = mpLineExtractorLeft->GetScaleFactor();
mfLineLogScaleFactor = log(mfLineScaleFactor);
mvLineScaleFactors = mpLineExtractorLeft->GetScaleFactors();
mvLineLevelSigma2 = mpLineExtractorLeft->GetScaleSigmaSquares();
mvLineInvLevelSigma2 = mpLineExtractorLeft->GetInverseScaleSigmaSquares();
}
// This is done only for the first Frame (or after a change in the calibration)
if(mbInitialComputations)
{
ComputeImageBounds(imGray);
mfGridElementWidthInv=static_cast<float>(FRAME_GRID_COLS)/static_cast<float>(mnMaxX-mnMinX);
mfGridElementHeightInv=static_cast<float>(FRAME_GRID_ROWS)/static_cast<float>(mnMaxY-mnMinY);
mfLineGridElementThetaInv=static_cast<float>(LINE_THETA_GRID_ROWS)/static_cast<float>(LINE_THETA_SPAN);
mfLineGridElementDInv=static_cast<float>(LINE_D_GRID_COLS)/(2.0f*mnMaxDiag);
fx = K.at<float>(0,0);
fy = K.at<float>(1,1);
cx = K.at<float>(0,2);
cy = K.at<float>(1,2);
invfx = 1.0f/fx;
invfy = 1.0f/fy;
mbInitialComputations=false;
}
mb = mbf/fx;
mbfInv = 1.f/mbf;
if(pPrevF){
if(pPrevF->HasVelocity())
SetVelocity(pPrevF->GetVelocity());
}
else{
mVw.setZero();
}
// Feature extraction
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartExtORB = std::chrono::steady_clock::now();
#endif
TICKTRACK("ExtractFeatures");
#ifndef USE_CUDA
if( Tracking::skUsePyramidPrecomputation )
{
// pre-compute Gaussian pyramid to be used for the extraction of both keypoints and keylines
TICKTRACK("PyramidPrecompute");
this->PrecomputeGaussianPyramid(0,imGray);
TOCKTRACK("PyramidPrecompute");
}
#else
if( Tracking::skUsePyramidPrecomputation )
{
std::cout << IoColor::Yellow() << "Can't use pyramid precomputation when CUDA is active!" << std::endl;
}
#endif
#if USE_PARALLEL_POINTS_LINES_EXTRACTION
if(mpLineExtractorLeft)
{
TICKTRACK("ExtractKeyPoints*");
std::thread threadPoints(&Frame::ExtractORB,this,0,imGray,0,0);
TICKTRACK("ExtractKeyLines-");
std::thread threadLines(&Frame::ExtractLSD,this,0,imGray);
threadPoints.join();
TOCKTRACK("ExtractKeyPoints*");
threadLines.join();
TOCKTRACK("ExtractKeyLines-");
}
else
{
TOCKTRACK("ExtractKeyPoints*");
// ORB extraction
ExtractORB(0,imGray,0,0);
TOCKTRACK("ExtractKeyLines-");
}
#else
TICKTRACK("ExtractKeyPoints*");
// ORB extraction
ExtractORB(0,imGray,0,0);
TOCKTRACK("ExtractKeyPoints*");
if(mpLineExtractorLeft)
{
TICKTRACK("ExtractKeyLines-");
ExtractLSD(0, imGray);
TOCKTRACK("ExtractKeyLines-");
}
#endif
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndExtORB = std::chrono::steady_clock::now();
mTimeORB_Ext = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndExtORB - time_StartExtORB).count();
#endif
N = mvKeys.size();
if(mvKeys.empty())
return;
UndistortKeyPoints();
ComputeStereoFromRGBD(imDepth);
mvpMapPoints = vector<MapPointPtr>(N,static_cast<MapPointPtr>(NULL));
// mmProjectPoints.clear();
// mmMatchedInImage.clear();
mvbOutlier = vector<bool>(N,false);
// LSD line segments extraction
if(mpLineExtractorLeft)
{
Nlines = mvKeyLines.size();
if(mvKeyLines.empty())
{
std::cout << "frame " << mnId << " no lines dectected!" << std::endl;
}
else
{
UndistortKeyLines();
//TICKTRACK("ComputeStereoLinesFromRGBD");
ComputeStereoLinesFromRGBD(imDepth);
//TOCKTRACK("ComputeStereoLinesFromRGBD");
}
mvpMapLines = vector<MapLinePtr>(Nlines,static_cast<MapLinePtr>(NULL));
mvbLineOutlier = vector<bool>(Nlines,false);
mvuNumLinePosOptFailures = vector<unsigned int>(Nlines,0);
// mmProjectLines.clear();// = map<long unsigned int, LineEndPoints>(N, static_cast<LineEndPoints>(NULL));
// mmMatchedLinesInImage.clear();
}
TOCKTRACK("ExtractFeatures");
mpMutexImu = new std::mutex();
//Set no stereo fisheye information
Nleft = -1;
Nright = -1;
mvLeftToRightMatch = vector<int>(0);
mvRightToLeftMatch = vector<int>(0);
mvStereo3Dpoints = vector<Eigen::Vector3f>(0);
monoLeft = -1;
monoRight = -1;
AssignFeaturesToGrid();
}
/// < MONOCULAR
Frame::Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, GeometricCamera* pCamera, cv::Mat &distCoef, const float &bf, const float &thDepth, Frame* pPrevF, const IMU::Calib &ImuCalib)
:mpcpi(NULL),mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast<ORBextractor*>(NULL)),
mTimeStamp(timeStamp), mK(pCamera->toLinearK()), mK_(pCamera->toLinearK_()),
mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth),
mImuCalib(ImuCalib), mpImuPreintegrated(NULL),mpPrevFrame(pPrevF),mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast<KeyFramePtr>(NULL)),
mbIsSet(false), mbImuPreintegrated(false), mpCamera(pCamera),
mpCamera2(nullptr), mbHasPose(false), mbHasVelocity(false)
{
// Frame ID
mnId=nNextId++;
#if KEEP_IMGAGES
this->imgLeft = imGray.clone();
#endif
// Scale Level Info
mnScaleLevels = mpORBextractorLeft->GetLevels();
mfScaleFactor = mpORBextractorLeft->GetScaleFactor();
mfLogScaleFactor = log(mfScaleFactor);
mvScaleFactors = mpORBextractorLeft->GetScaleFactors();
mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors();
mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares();
mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares();
// ORB extraction
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_StartExtORB = std::chrono::steady_clock::now();
#endif
ExtractORB(0,imGray,0,1000);
#ifdef REGISTER_TIMES
std::chrono::steady_clock::time_point time_EndExtORB = std::chrono::steady_clock::now();
mTimeORB_Ext = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndExtORB - time_StartExtORB).count();
#endif
N = mvKeys.size();
if(mvKeys.empty())
return;
UndistortKeyPoints();
// Set no stereo information
mvuRight = vector<float>(N,-1);
mvDepth = vector<float>(N,-1);
mnCloseMPs = 0;
mvpMapPoints = vector<MapPointPtr>(N,static_cast<MapPointPtr>(NULL));
// mmProjectPoints.clear();// = map<long unsigned int, cv::Point2f>(N, static_cast<cv::Point2f>(NULL));
// mmMatchedInImage.clear();
mvbOutlier = vector<bool>(N,false);
// This is done only for the first Frame (or after a change in the calibration)
if(mbInitialComputations)
{
ComputeImageBounds(imGray);
mfGridElementWidthInv=static_cast<float>(FRAME_GRID_COLS)/static_cast<float>(mnMaxX-mnMinX);
mfGridElementHeightInv=static_cast<float>(FRAME_GRID_ROWS)/static_cast<float>(mnMaxY-mnMinY);
mfLineGridElementThetaInv=static_cast<float>(LINE_THETA_GRID_ROWS)/static_cast<float>(LINE_THETA_SPAN);
mfLineGridElementDInv=static_cast<float>(LINE_D_GRID_COLS)/(2.0f*mnMaxDiag);
fx = mK.at<float>(0,0); //static_cast<Pinhole*>(mpCamera)->toK().at<float>(0,0);
fy = mK.at<float>(1,1); //static_cast<Pinhole*>(mpCamera)->toK().at<float>(1,1);
cx = mK.at<float>(0,2); //static_cast<Pinhole*>(mpCamera)->toK().at<float>(0,2);
cy = mK.at<float>(1,2); //static_cast<Pinhole*>(mpCamera)->toK().at<float>(1,2);
invfx = 1.0f/fx;
invfy = 1.0f/fy;
mbInitialComputations=false;
}
mb = mbf/fx;
mbfInv = 1.f/mbf;
//Set no stereo fisheye information
Nleft = -1;
Nright = -1;
mvLeftToRightMatch = vector<int>(0);
mvRightToLeftMatch = vector<int>(0);
mvStereo3Dpoints = vector<Eigen::Vector3f>(0);
monoLeft = -1;
monoRight = -1;
AssignFeaturesToGrid();
if(pPrevF)
{
if(pPrevF->HasVelocity())
{
SetVelocity(pPrevF->GetVelocity());
}
}
else
{
mVw.setZero();
}
if(mpLineExtractorLeft)
{
mvuRightLineStart = vector<float>(Nlines,-1);
mvDepthLineStart = vector<float>(Nlines,-1);
mvuRightLineEnd = vector<float>(Nlines,-1);
mvDepthLineEnd = vector<float>(Nlines,-1);
}
mpMutexImu = new std::mutex();
}
void Frame::AssignFeaturesToGrid()
{
// Fill matrix with points
const int nCells = FRAME_GRID_COLS*FRAME_GRID_ROWS;
int nReserve = 0.5f*N/(nCells);
for(unsigned int i=0; i<FRAME_GRID_COLS;i++)
for (unsigned int j=0; j<FRAME_GRID_ROWS;j++){
mGrid[i][j].reserve(nReserve);
if(Nleft != -1){
mGridRight[i][j].reserve(nReserve);
}
}
for(int i=0;i<N;i++)
{
const cv::KeyPoint &kp = (Nleft == -1) ? mvKeysUn[i]
: (i < Nleft) ? mvKeys[i]
: mvKeysRight[i - Nleft];
int nGridPosX, nGridPosY;
if(PosInGrid(kp,nGridPosX,nGridPosY)){
if(Nleft == -1 || i < Nleft)
mGrid[nGridPosX][nGridPosY].push_back(i);
else
mGridRight[nGridPosX][nGridPosY].push_back(i - Nleft);
}
}
if(mpLineExtractorLeft)
{
int nReserve = 0.5f*Nlines/(LINE_D_GRID_COLS*LINE_THETA_GRID_ROWS);
for(unsigned int i=0; i<LINE_D_GRID_COLS;i++)
for (unsigned int j=0; j<LINE_THETA_GRID_ROWS;j++){
mLineGrid[i][j].reserve(nReserve);
if(NlinesLeft != -1){
mLineGridRight[i][j].reserve(nReserve);
}
}
for(int i=0;i<Nlines;i++)
{
//const cv::line_descriptor_c::KeyLine& kl = mvKeyLinesUn[i];
const cv::line_descriptor_c::KeyLine& kl = (NlinesLeft == -1) ? mvKeyLinesUn[i] :
(i < NlinesLeft) ? mvKeyLinesUn[i]
: mvKeyLinesRightUn[i - NlinesLeft];
int nGridPosX, nGridPosY;
if(PosLineInGrid(kl,nGridPosX,nGridPosY))
{
if(NlinesLeft == -1 || i < NlinesLeft)
{
mLineGrid[nGridPosX][nGridPosY].push_back(i);
}
else
{
mLineGridRight[nGridPosX][nGridPosY].push_back(i - NlinesLeft);
}
}
}
#if LOG_ASSIGN_FEATURES
logger << "================================================================" << std::endl;
logger << "frame: " << mnId << std::endl;
for(int nGridPosX=0; nGridPosX < LINE_D_GRID_COLS; nGridPosX++)
for(int nGridPosY=0; nGridPosY < LINE_THETA_GRID_ROWS; nGridPosY++)
{
std::vector<std::size_t>& vec = mLineGrid[nGridPosX][nGridPosY];
for(int kk=0; kk<vec.size(); kk++)
{
const cv::line_descriptor_c::KeyLine& kl = mvKeyLinesUn[vec[kk]];
const float &xs = kl.startPointX;
const float &ys = kl.startPointY;
const float &xe = kl.endPointX;
const float &ye = kl.endPointY;
Line2DRepresentation lineRepresentation;
Geom2DUtils::GetLine2dRepresentation(xs, ys, xe, ye, lineRepresentation);
logger << "line " << vec[kk] << ", theta: " << lineRepresentation.theta*180/M_PI << ", d: " << lineRepresentation.d << ", posX: " << nGridPosX <<", posY: " << nGridPosY << std::endl;
}
}
#endif
}
}
void Frame::ExtractORB(int flag, const cv::Mat &im, const int x0, const int x1)
{
vector<int> vLapping = {x0,x1};
if(flag==0)
monoLeft = (*mpORBextractorLeft)(im,cv::Mat(),mvKeys,mDescriptors,vLapping);
else
monoRight = (*mpORBextractorRight)(im,cv::Mat(),mvKeysRight,mDescriptorsRight,vLapping);
}
void Frame::ExtractLSD(int flag, const cv::Mat &im)
{
if(flag==0)
{
if(mpLineExtractorLeft)
{
(*mpLineExtractorLeft)(im,mvKeyLines,mLineDescriptors);
monoLinesLeft = 0; // TODO Luigi
}
}
else
{
if(mpLineExtractorRight)
{
(*mpLineExtractorRight)(im,mvKeyLinesRight,mLineDescriptorsRight);
monoLinesRight = 0; // TODO Luigi
}
}
}
static void clonePyramid(const std::vector<cv::Mat>& imgsIn, std::vector<cv::Mat>& imgsClone)
{
imgsClone.resize(imgsIn.size());
for(size_t ii=0;ii<imgsIn.size();ii++) imgsClone[ii] = imgsIn[ii].clone();
}
void Frame::PrecomputeGaussianPyramid(int flag, const cv::Mat &im)
{
if(flag==0)
{
mpORBextractorLeft->PrecomputeGaussianPyramid(im);
#ifndef USE_CUDA
#if USE_UNFILTERED_PYRAMID_FOR_LINES
if(mpLineExtractorLeft) mpLineExtractorLeft->SetGaussianPyramid(mpORBextractorLeft->mvImagePyramid, mpLineExtractorLeft->GetLevels(), mpORBextractorLeft->GetScaleFactor());
#else
if(mpLineExtractorLeft) mpLineExtractorLeft->SetGaussianPyramid(mpORBextractorLeft->mvImagePyramidFiltered, mpLineExtractorLeft->GetLevels(), mpORBextractorLeft->GetScaleFactor());
#endif
#endif
}
else
{
mpORBextractorRight->PrecomputeGaussianPyramid(im);
#ifndef USE_CUDA
#if USE_UNFILTERED_PYRAMID_FOR_LINES
if(mpLineExtractorRight) mpLineExtractorRight->SetGaussianPyramid(mpORBextractorRight->mvImagePyramid, mpLineExtractorRight->GetLevels(), mpORBextractorRight->GetScaleFactor());
#else
if(mpLineExtractorRight) mpLineExtractorRight->SetGaussianPyramid(mpORBextractorRight->mvImagePyramidFiltered, mpLineExtractorRight->GetLevels(), mpORBextractorRight->GetScaleFactor());
#endif
#endif
}
}
bool Frame::isSet() const {
return mbIsSet;
}
void Frame::SetPose(const Sophus::SE3<float> &Tcw) {
mTcw = Tcw;
UpdatePoseMatrices();
mbIsSet = true;
mbHasPose = true;
}
void Frame::SetNewBias(const IMU::Bias &b)
{
mImuBias = b;
if(mpImuPreintegrated)
mpImuPreintegrated->SetNewBias(b);
}
void Frame::SetVelocity(Eigen::Vector3f Vwb)
{
mVw = Vwb;
mbHasVelocity = true;
}
Eigen::Vector3f Frame::GetVelocity() const
{
return mVw;
}
void Frame::SetImuPoseVelocity(const Eigen::Matrix3f &Rwb, const Eigen::Vector3f &twb, const Eigen::Vector3f &Vwb)
{
mVw = Vwb;
mbHasVelocity = true;
Sophus::SE3f Twb(Rwb, twb);
Sophus::SE3f Tbw = Twb.inverse();
mTcw = mImuCalib.mTcb * Tbw;
UpdatePoseMatrices();
mbIsSet = true;
mbHasPose = true;
}
void Frame::UpdatePoseMatrices()
{
Sophus::SE3<float> Twc = mTcw.inverse();
mRwc = Twc.rotationMatrix();
mOw = Twc.translation();
mRcw = mTcw.rotationMatrix();
mtcw = mTcw.translation();
//fovCw = Ow + Twc.rowRange(0,3).col(2) * skFovCenterDistance;
fovCw = mOw + mRwc.col(2) * mMedianDepth;
}
Eigen::Matrix<float,3,1> Frame::GetImuPosition() const {
return mRwc * mImuCalib.mTcb.translation() + mOw;
}
Eigen::Matrix<float,3,3> Frame::GetImuRotation() {
return mRwc * mImuCalib.mTcb.rotationMatrix();
}
Sophus::SE3<float> Frame::GetImuPose() {
return mTcw.inverse() * mImuCalib.mTcb;
}
Sophus::SE3f Frame::GetRelativePoseTrl()
{
return mTrl;
}
Sophus::SE3f Frame::GetRelativePoseTlr()
{
return mTlr;
}
Eigen::Matrix3f Frame::GetRelativePoseTlr_rotation(){
return mTlr.rotationMatrix();
}
Eigen::Vector3f Frame::GetRelativePoseTlr_translation() {
return mTlr.translation();
}
bool Frame::isInFrustum(MapPointPtr& pMP, float viewingCosLimit)
{
if(Nleft == -1){
pMP->mbTrackInView = false;
pMP->mTrackProjX = -1;
pMP->mTrackProjY = -1;
// 3D in absolute coordinates
Eigen::Matrix<float,3,1> P = pMP->GetWorldPos();
// 3D in camera coordinates
const Eigen::Matrix<float,3,1> Pc = mRcw * P + mtcw;
const float Pc_dist = Pc.norm();
// Check positive depth
const float &PcZ = Pc(2);
const float invz = 1.0f/PcZ;
if(PcZ<0.0f)
return false;
const Eigen::Vector2f uv = mpCamera->project(Pc);
if(uv(0)<mnMinX || uv(0)>mnMaxX)
return false;
if(uv(1)<mnMinY || uv(1)>mnMaxY)
return false;
pMP->mTrackProjX = uv(0);
pMP->mTrackProjY = uv(1);
// Check distance is in the scale invariance region of the MapPoint
const float maxDistance = pMP->GetMaxDistanceInvariance();
const float minDistance = pMP->GetMinDistanceInvariance();
const Eigen::Vector3f PO = P - mOw;
const float dist = PO.norm();
if(dist<minDistance || dist>maxDistance)
return false;
// Check viewing angle
Eigen::Vector3f Pn = pMP->GetNormal();
const float viewCos = PO.dot(Pn)/dist;
if(viewCos<viewingCosLimit)
return false;