forked from jingpang/LearnVIORB
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Tracking.cc
2155 lines (1785 loc) · 67.9 KB
/
Tracking.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 ORB-SLAM2.
*
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <https://github.com/raulmur/ORB_SLAM2>
*
* ORB-SLAM2 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-SLAM2 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-SLAM2. If not, see <http://www.gnu.org/licenses/>.
*/
#include "Tracking.h"
#include<opencv2/core/core.hpp>
#include<opencv2/features2d/features2d.hpp>
#include"ORBmatcher.h"
#include"FrameDrawer.h"
#include"Converter.h"
#include"Map.h"
#include"Initializer.h"
#include"Optimizer.h"
#include"PnPsolver.h"
#include<iostream>
#include<mutex>
#define TRACK_WITH_IMU
using namespace std;
namespace ORB_SLAM2
{
//-------------------------------------------------------------------------------------------
//-------------------------------------------------------------------------------------------
//-------------------------------------------------------------------------------------------
void Tracking::RecomputeIMUBiasAndCurrentNavstate(NavState& nscur)
{
size_t N = mv20FramesReloc.size();
//Test log
if(N!=20) cerr<<"Frame vector size not 20 to compute bias after reloc??? size: "<<mv20FramesReloc.size()<<endl;
// Estimate gyr bias
Vector3d bg = Optimizer::OptimizeInitialGyroBias(mv20FramesReloc);
// Update gyr bias of Frames
for(size_t i=0; i<N; i++)
{
Frame& frame = mv20FramesReloc[i];
//Test log
if(frame.GetNavState().Get_BiasGyr().norm()!=0 || frame.GetNavState().Get_dBias_Gyr().norm()!=0)
cerr<<"Frame "<<frame.mnId<<" gyr bias or delta bias not zero???"<<endl;
frame.SetNavStateBiasGyr(bg);
}
// Re-compute IMU pre-integration
vector<IMUPreintegrator> v19IMUPreint;
v19IMUPreint.reserve(20-1);
for(size_t i=0; i<N; i++)
{
if(i==0)
continue;
const Frame& Fi = mv20FramesReloc[i-1];
const Frame& Fj = mv20FramesReloc[i];
IMUPreintegrator imupreint;
Fj.ComputeIMUPreIntSinceLastFrame(&Fi,imupreint);
v19IMUPreint.push_back(imupreint);
}
// Construct [A1;A2;...;AN] * ba = [B1;B2;.../BN], solve ba
cv::Mat A = cv::Mat::zeros(3*(N-2),3,CV_32F);
cv::Mat B = cv::Mat::zeros(3*(N-2),1,CV_32F);
const cv::Mat& gw = mpLocalMapper->GetGravityVec();
const cv::Mat& Tcb = ConfigParam::GetMatT_cb();
for(int i=0; i<N-2; i++)
{
const Frame& F1 = mv20FramesReloc[i];
const Frame& F2 = mv20FramesReloc[i+1];
const Frame& F3 = mv20FramesReloc[i+2];
const IMUPreintegrator& PreInt12 = v19IMUPreint[i];
const IMUPreintegrator& PreInt23 = v19IMUPreint[i+1];
// Delta time between frames
double dt12 = PreInt12.getDeltaTime();
double dt23 = PreInt23.getDeltaTime();
// Pre-integrated measurements
cv::Mat dp12 = Converter::toCvMat(PreInt12.getDeltaP());
cv::Mat dv12 = Converter::toCvMat(PreInt12.getDeltaV());
cv::Mat dp23 = Converter::toCvMat(PreInt23.getDeltaP());
cv::Mat Jpba12 = Converter::toCvMat(PreInt12.getJPBiasa());
cv::Mat Jvba12 = Converter::toCvMat(PreInt12.getJVBiasa());
cv::Mat Jpba23 = Converter::toCvMat(PreInt23.getJPBiasa());
// Pose of body in world frame
cv::Mat Twb1 = Converter::toCvMatInverse(F1.mTcw)*Tcb;
cv::Mat Twb2 = Converter::toCvMatInverse(F2.mTcw)*Tcb;
cv::Mat Twb3 = Converter::toCvMatInverse(F3.mTcw)*Tcb;
// Position of body, Pwb
cv::Mat pb1 = Twb1.rowRange(0,3).col(3);
cv::Mat pb2 = Twb2.rowRange(0,3).col(3);
cv::Mat pb3 = Twb3.rowRange(0,3).col(3);
// Rotation of body, Rwb
cv::Mat Rb1 = Twb1.rowRange(0,3).colRange(0,3);
cv::Mat Rb2 = Twb2.rowRange(0,3).colRange(0,3);
//cv::Mat Rb3 = Twb3.rowRange(0,3).colRange(0,3);
// Stack to A/B matrix
// Ai * ba = Bi
cv::Mat Ai = Rb1*Jpba12*dt23 - Rb2*Jpba23*dt12 - Rb1*Jvba12*dt12*dt23;
cv::Mat Bi = (pb2-pb3)*dt12 + (pb2-pb1)*dt23 + Rb2*dp23*dt12 - Rb1*dp12*dt23 + Rb1*dv12*dt12*dt23 + 0.5*gw*(dt12*dt12*dt23+dt12*dt23*dt23);
Ai.copyTo(A.rowRange(3*i+0,3*i+3));
Bi.copyTo(B.rowRange(3*i+0,3*i+3));
//Test log
if(fabs(F2.mTimeStamp-F1.mTimeStamp-dt12)>1e-6 || fabs(F3.mTimeStamp-F2.mTimeStamp-dt23)>1e-6) cerr<<"delta time not right."<<endl;
// // lambda*s + phi*dthetaxy + zeta*ba = psi
// cv::Mat lambda = (pc2-pc1)*dt23 + (pc2-pc3)*dt12;
// cv::Mat phi = - 0.5*(dt12*dt12*dt23 + dt12*dt23*dt23)*Rwi*SkewSymmetricMatrix(GI); // note: this has a '-', different to paper
// cv::Mat zeta = Rc2*Rcb*Jpba23*dt12 + Rc1*Rcb*Jvba12*dt12*dt23 - Rc1*Rcb*Jpba12*dt23;
// cv::Mat psi = (Rc1-Rc2)*pcb*dt23 + Rc1*Rcb*dp12*dt23 - (Rc2-Rc3)*pcb*dt12
// - Rc2*Rcb*dp23*dt12 - Rc1*Rcb*dv12*dt23*dt12 - 0.5*Rwi*GI*(dt12*dt12*dt23 + dt12*dt23*dt23); // note: - paper
// lambda.copyTo(C.rowRange(3*i+0,3*i+3).col(0));
// phi.colRange(0,2).copyTo(C.rowRange(3*i+0,3*i+3).colRange(1,3)); //only the first 2 columns, third term in dtheta is zero, here compute dthetaxy 2x1.
// zeta.copyTo(C.rowRange(3*i+0,3*i+3).colRange(3,6));
// psi.copyTo(D.rowRange(3*i+0,3*i+3));
}
// Use svd to compute A*x=B, x=ba 3x1 vector
// A = u*w*vt, u*w*vt*x=B
// Then x = vt'*winv*u'*B
cv::Mat w2,u2,vt2;
// Note w2 is 3x1 vector by SVDecomp()
// A is changed in SVDecomp() with cv::SVD::MODIFY_A for speed
cv::SVDecomp(A,w2,u2,vt2,cv::SVD::MODIFY_A);
// Compute winv
cv::Mat w2inv=cv::Mat::eye(3,3,CV_32F);
for(int i=0;i<3;i++)
{
if(fabs(w2.at<float>(i))<1e-10)
{
w2.at<float>(i) += 1e-10;
// Test log
cerr<<"w2(i) < 1e-10, w="<<endl<<w2<<endl;
}
w2inv.at<float>(i,i) = 1./w2.at<float>(i);
}
// Then y = vt'*winv*u'*B
cv::Mat ba_cv = vt2.t()*w2inv*u2.t()*B;
Vector3d ba = Converter::toVector3d(ba_cv);
// Update acc bias
for(size_t i=0; i<N; i++)
{
Frame& frame = mv20FramesReloc[i];
//Test log
if(frame.GetNavState().Get_BiasAcc().norm()!=0 || frame.GetNavState().Get_dBias_Gyr().norm()!=0 || frame.GetNavState().Get_dBias_Acc().norm()!=0)
cerr<<"Frame "<<frame.mnId<<" acc bias or delta bias not zero???"<<endl;
frame.SetNavStateBiasAcc(ba);
}
// Compute Velocity of the last 2 Frames
Vector3d Pcur;
Vector3d Vcur;
Matrix3d Rcur;
{
Frame& F1 = mv20FramesReloc[N-2];
Frame& F2 = mv20FramesReloc[N-1];
const IMUPreintegrator& imupreint = v19IMUPreint.back();
const double dt12 = imupreint.getDeltaTime();
const Vector3d dp12 = imupreint.getDeltaP();
const Vector3d gweig = Converter::toVector3d(gw);
const Matrix3d Jpba12 = imupreint.getJPBiasa();
const Vector3d dv12 = imupreint.getDeltaV();
const Matrix3d Jvba12 = imupreint.getJVBiasa();
// Velocity of Previous Frame
// P2 = P1 + V1*dt12 + 0.5*gw*dt12*dt12 + R1*(dP12 + Jpba*ba + Jpbg*0)
cv::Mat Twb1 = Converter::toCvMatInverse(F1.mTcw)*Tcb;
cv::Mat Twb2 = Converter::toCvMatInverse(F2.mTcw)*Tcb;
Vector3d P1 = Converter::toVector3d(Twb1.rowRange(0,3).col(3));
/*Vector3d */Pcur = Converter::toVector3d(Twb2.rowRange(0,3).col(3));
Matrix3d R1 = Converter::toMatrix3d(Twb1.rowRange(0,3).colRange(0,3));
/*Matrix3d */Rcur = Converter::toMatrix3d(Twb2.rowRange(0,3).colRange(0,3));
Vector3d V1 = 1./dt12*( Pcur - P1 - 0.5*gweig*dt12*dt12 - R1*(dp12 + Jpba12*ba) );
// Velocity of Current Frame
Vcur = V1 + gweig*dt12 + R1*( dv12 + Jvba12*ba );
// Test log
if(F2.mnId != mCurrentFrame.mnId) cerr<<"framecur.mnId != mCurrentFrame.mnId. why??"<<endl;
if(fabs(F2.mTimeStamp-F1.mTimeStamp-dt12)>1e-6) cerr<<"timestamp not right?? in compute vel"<<endl;
}
// Set NavState of Current Frame, P/V/R/bg/ba/dbg/dba
nscur.Set_Pos(Pcur);
nscur.Set_Vel(Vcur);
nscur.Set_Rot(Rcur);
nscur.Set_BiasGyr(bg);
nscur.Set_BiasAcc(ba);
nscur.Set_DeltaBiasGyr(Vector3d::Zero());
nscur.Set_DeltaBiasAcc(Vector3d::Zero());
//mv20FramesReloc
}
bool Tracking::TrackLocalMapWithIMU(bool bMapUpdated)
{
// We have an estimation of the camera pose and some map points tracked in the frame.
// We retrieve the local map and try to find matches to points in the local map.
UpdateLocalMap();
SearchLocalPoints();
// Map updated, optimize with last KeyFrame
if(mpLocalMapper->GetFirstVINSInited() || bMapUpdated)
{
// Get initial pose from Last KeyFrame
IMUPreintegrator imupreint = GetIMUPreIntSinceLastKF(&mCurrentFrame, mpLastKeyFrame, mvIMUSinceLastKF);
// Test log
//if(mpLocalMapper->GetFirstVINSInited() && !bMapUpdated) cerr<<"1-FirstVinsInit, but not bMapUpdated. shouldn't"<<endl;
if(mCurrentFrame.GetNavState().Get_dBias_Acc().norm() > 1e-6) cerr<<"TrackLocalMapWithIMU current Frame dBias acc not zero"<<endl;
if(mCurrentFrame.GetNavState().Get_dBias_Gyr().norm() > 1e-6) cerr<<"TrackLocalMapWithIMU current Frame dBias gyr not zero"<<endl;
//
Optimizer::PoseOptimization(&mCurrentFrame,mpLastKeyFrame,imupreint,mpLocalMapper->GetGravityVec(),true);
}
// Map not updated, optimize with last Frame
else
{
// Get initial pose from Last Frame
IMUPreintegrator imupreint = GetIMUPreIntSinceLastFrame(&mCurrentFrame, &mLastFrame);
Optimizer::PoseOptimization(&mCurrentFrame,&mLastFrame,imupreint,mpLocalMapper->GetGravityVec(),true);
}
mnMatchesInliers = 0;
// Update MapPoints Statistics
for(int i=0; i<mCurrentFrame.N; i++)
{
if(mCurrentFrame.mvpMapPoints[i])
{
if(!mCurrentFrame.mvbOutlier[i])
{
mCurrentFrame.mvpMapPoints[i]->IncreaseFound();
if(!mbOnlyTracking)
{
if(mCurrentFrame.mvpMapPoints[i]->Observations()>0)
mnMatchesInliers++;
}
else
mnMatchesInliers++;
}
else if(mSensor==System::STEREO)
mCurrentFrame.mvpMapPoints[i] = static_cast<MapPoint*>(NULL);
}
}
// Decide if the tracking was succesful
// More restrictive if there was a relocalization recently
if(mCurrentFrame.mnId<mnLastRelocFrameId+mMaxFrames && mnMatchesInliers<50)
return false;
if(mnMatchesInliers<6/*30*/)
return false;
else
return true;
}
void Tracking::PredictNavStateByIMU(bool bMapUpdated)
{
if(!mpLocalMapper->GetVINSInited()) cerr<<"mpLocalMapper->GetVINSInited() not, shouldn't in PredictNavStateByIMU"<<endl;
// Map updated, optimize with last KeyFrame
if(mpLocalMapper->GetFirstVINSInited() || bMapUpdated)
{
//if(mpLocalMapper->GetFirstVINSInited() && !bMapUpdated) cerr<<"2-FirstVinsInit, but not bMapUpdated. shouldn't"<<endl;
// Compute IMU Pre-integration
mIMUPreIntInTrack = GetIMUPreIntSinceLastKF(&mCurrentFrame, mpLastKeyFrame, mvIMUSinceLastKF);
// Get initial NavState&pose from Last KeyFrame
mCurrentFrame.SetInitialNavStateAndBias(mpLastKeyFrame->GetNavState());
mCurrentFrame.UpdateNavState(mIMUPreIntInTrack,Converter::toVector3d(mpLocalMapper->GetGravityVec()));
mCurrentFrame.UpdatePoseFromNS(ConfigParam::GetMatTbc());
// Test log
// Updated KF by Local Mapping. Should be the same as mpLastKeyFrame
if(mCurrentFrame.GetNavState().Get_dBias_Acc().norm() > 1e-6) cerr<<"PredictNavStateByIMU1 current Frame dBias acc not zero"<<endl;
if(mCurrentFrame.GetNavState().Get_dBias_Gyr().norm() > 1e-6) cerr<<"PredictNavStateByIMU1 current Frame dBias gyr not zero"<<endl;
}
// Map not updated, optimize with last Frame
else
{
// Compute IMU Pre-integration
mIMUPreIntInTrack = GetIMUPreIntSinceLastFrame(&mCurrentFrame, &mLastFrame);
// Get initial pose from Last Frame
mCurrentFrame.SetInitialNavStateAndBias(mLastFrame.GetNavState());
mCurrentFrame.UpdateNavState(mIMUPreIntInTrack,Converter::toVector3d(mpLocalMapper->GetGravityVec()));
mCurrentFrame.UpdatePoseFromNS(ConfigParam::GetMatTbc());
// Test log
if(mCurrentFrame.GetNavState().Get_dBias_Acc().norm() > 1e-6) cerr<<"PredictNavStateByIMU2 current Frame dBias acc not zero"<<endl;
if(mCurrentFrame.GetNavState().Get_dBias_Gyr().norm() > 1e-6) cerr<<"PredictNavStateByIMU2 current Frame dBias gyr not zero"<<endl;
}
}
bool Tracking::TrackWithIMU(bool bMapUpdated)
{
ORBmatcher matcher(0.9,true);
// VINS has been inited in this function
if(!mpLocalMapper->GetVINSInited()) cerr<<"local mapping VINS not inited. why call TrackWithIMU?"<<endl;
// Predict NavState&Pose by IMU
// And compute the IMU pre-integration for PoseOptimization
PredictNavStateByIMU(bMapUpdated);
fill(mCurrentFrame.mvpMapPoints.begin(),mCurrentFrame.mvpMapPoints.end(),static_cast<MapPoint*>(NULL));
// Project points seen in previous frame
int th;
if(mSensor!=System::STEREO)
th=15;
else
th=7;
int nmatches = matcher.SearchByProjection(mCurrentFrame,mLastFrame,th,mSensor==System::MONOCULAR);
// If few matches, uses a wider window search
if(nmatches<20)
{
fill(mCurrentFrame.mvpMapPoints.begin(),mCurrentFrame.mvpMapPoints.end(),static_cast<MapPoint*>(NULL));
nmatches = matcher.SearchByProjection(mCurrentFrame,mLastFrame,2*th,mSensor==System::MONOCULAR);
}
if(nmatches</*20*/10)
return false;
// Pose optimization. false: no need to compute marginalized for current Frame
if(mpLocalMapper->GetFirstVINSInited() || bMapUpdated)
{
Optimizer::PoseOptimization(&mCurrentFrame,mpLastKeyFrame,mIMUPreIntInTrack,mpLocalMapper->GetGravityVec(),false);
}
else
{
Optimizer::PoseOptimization(&mCurrentFrame,&mLastFrame,mIMUPreIntInTrack,mpLocalMapper->GetGravityVec(),false);
}
// Discard outliers
int nmatchesMap = 0;
for(int i =0; i<mCurrentFrame.N; i++)
{
if(mCurrentFrame.mvpMapPoints[i])
{
if(mCurrentFrame.mvbOutlier[i])
{
MapPoint* pMP = mCurrentFrame.mvpMapPoints[i];
mCurrentFrame.mvpMapPoints[i]=static_cast<MapPoint*>(NULL);
mCurrentFrame.mvbOutlier[i]=false;
pMP->mbTrackInView = false;
pMP->mnLastFrameSeen = mCurrentFrame.mnId;
nmatches--;
}
else if(mCurrentFrame.mvpMapPoints[i]->Observations()>0)
nmatchesMap++;
}
}
if(mbOnlyTracking)
{
mbVO = nmatchesMap<10;
return nmatches>20;
}
return nmatchesMap>=/*10*/6;
}
IMUPreintegrator Tracking::GetIMUPreIntSinceLastKF(Frame* pCurF, KeyFrame* pLastKF, const std::vector<IMUData>& vIMUSInceLastKF)
{
// Reset pre-integrator first
IMUPreintegrator IMUPreInt;
IMUPreInt.reset();
Vector3d bg = pLastKF->GetNavState().Get_BiasGyr();
Vector3d ba = pLastKF->GetNavState().Get_BiasAcc();
// remember to consider the gap between the last KF and the first IMU
{
const IMUData& imu = vIMUSInceLastKF.front();
double dt = imu._t - pLastKF->mTimeStamp;
IMUPreInt.update(imu._g - bg, imu._a - ba, dt);
// Test log
if(dt < 0)
{
cerr<<std::fixed<<std::setprecision(3)<<"dt = "<<dt<<", this KF vs last imu time: "<<pLastKF->mTimeStamp<<" vs "<<imu._t<<endl;
std::cerr.unsetf ( std::ios::showbase ); // deactivate showbase
}
}
// integrate each imu
for(size_t i=0; i<vIMUSInceLastKF.size(); i++)
{
const IMUData& imu = vIMUSInceLastKF[i];
double nextt;
if(i==vIMUSInceLastKF.size()-1)
nextt = pCurF->mTimeStamp; // last IMU, next is this KeyFrame
else
nextt = vIMUSInceLastKF[i+1]._t; // regular condition, next is imu data
// delta time
double dt = nextt - imu._t;
// update pre-integrator
IMUPreInt.update(imu._g - bg, imu._a - ba, dt);
// Test log
if(dt <= 0)
{
cerr<<std::fixed<<std::setprecision(3)<<"dt = "<<dt<<", this vs next time: "<<imu._t<<" vs "<<nextt<<endl;
std::cerr.unsetf ( std::ios::showbase ); // deactivate showbase
}
}
return IMUPreInt;
}
IMUPreintegrator Tracking::GetIMUPreIntSinceLastFrame(Frame* pCurF, Frame* pLastF)
{
// Reset pre-integrator first
IMUPreintegrator IMUPreInt;
IMUPreInt.reset();
pCurF->ComputeIMUPreIntSinceLastFrame(pLastF,IMUPreInt);
return IMUPreInt;
}
cv::Mat Tracking::GrabImageMonoVI(const cv::Mat &im, const std::vector<IMUData> &vimu, const double ×tamp)
{
mvIMUSinceLastKF.insert(mvIMUSinceLastKF.end(), vimu.begin(),vimu.end());
mImGray = im;
if(mImGray.channels()==3)
{
if(mbRGB)
cvtColor(mImGray,mImGray,CV_RGB2GRAY);
else
cvtColor(mImGray,mImGray,CV_BGR2GRAY);
}
else if(mImGray.channels()==4)
{
if(mbRGB)
cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
else
cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
}
if(mState==NOT_INITIALIZED || mState==NO_IMAGES_YET)
mCurrentFrame = Frame(mImGray,timestamp,vimu,mpIniORBextractor,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
else
mCurrentFrame = Frame(mImGray,timestamp,vimu,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth,mpLastKeyFrame);
Track();
return mCurrentFrame.mTcw.clone();
}
//-------------------------------------------------------------------------------------------
//-------------------------------------------------------------------------------------------
//-------------------------------------------------------------------------------------------
Tracking::Tracking(System *pSys, ORBVocabulary* pVoc, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer,
Map *pMap, KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor,ConfigParam* pParams):
mState(NO_IMAGES_YET), mSensor(sensor), mbOnlyTracking(false), mbVO(false), mpORBVocabulary(pVoc),
mpKeyFrameDB(pKFDB), mpInitializer(static_cast<Initializer*>(NULL)), mpSystem(pSys),
mpFrameDrawer(pFrameDrawer), mpMapDrawer(pMapDrawer), mpMap(pMap), mnLastRelocFrameId(0)
{
mbCreateNewKFAfterReloc = false;
mbRelocBiasPrepare = false;
mpParams = pParams;
// Load camera parameters from settings file
cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);
float fx = fSettings["Camera.fx"];
float fy = fSettings["Camera.fy"];
float cx = fSettings["Camera.cx"];
float cy = fSettings["Camera.cy"];
cv::Mat K = cv::Mat::eye(3,3,CV_32F);
K.at<float>(0,0) = fx;
K.at<float>(1,1) = fy;
K.at<float>(0,2) = cx;
K.at<float>(1,2) = cy;
K.copyTo(mK);
cv::Mat DistCoef(4,1,CV_32F);
DistCoef.at<float>(0) = fSettings["Camera.k1"];
DistCoef.at<float>(1) = fSettings["Camera.k2"];
DistCoef.at<float>(2) = fSettings["Camera.p1"];
DistCoef.at<float>(3) = fSettings["Camera.p2"];
const float k3 = fSettings["Camera.k3"];
if(k3!=0)
{
DistCoef.resize(5);
DistCoef.at<float>(4) = k3;
}
DistCoef.copyTo(mDistCoef);
mbf = fSettings["Camera.bf"];
float fps = fSettings["Camera.fps"];
if(fps==0)
fps=30;
// Max/Min Frames to insert keyframes and to check relocalisation
mMinFrames = 0;
mMaxFrames = fps;
cout << endl << "Camera Parameters: " << endl;
cout << "- fx: " << fx << endl;
cout << "- fy: " << fy << endl;
cout << "- cx: " << cx << endl;
cout << "- cy: " << cy << endl;
cout << "- k1: " << DistCoef.at<float>(0) << endl;
cout << "- k2: " << DistCoef.at<float>(1) << endl;
if(DistCoef.rows==5)
cout << "- k3: " << DistCoef.at<float>(4) << endl;
cout << "- p1: " << DistCoef.at<float>(2) << endl;
cout << "- p2: " << DistCoef.at<float>(3) << endl;
cout << "- fps: " << fps << endl;
int nRGB = fSettings["Camera.RGB"];
mbRGB = nRGB;
if(mbRGB)
cout << "- color order: RGB (ignored if grayscale)" << endl;
else
cout << "- color order: BGR (ignored if grayscale)" << endl;
// Load ORB parameters
int nFeatures = fSettings["ORBextractor.nFeatures"];
float fScaleFactor = fSettings["ORBextractor.scaleFactor"];
int nLevels = fSettings["ORBextractor.nLevels"];
int fIniThFAST = fSettings["ORBextractor.iniThFAST"];
int fMinThFAST = fSettings["ORBextractor.minThFAST"];
mpORBextractorLeft = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);
if(sensor==System::STEREO)
mpORBextractorRight = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);
if(sensor==System::MONOCULAR)
mpIniORBextractor = new ORBextractor(2*nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);
cout << endl << "ORB Extractor Parameters: " << endl;
cout << "- Number of Features: " << nFeatures << endl;
cout << "- Scale Levels: " << nLevels << endl;
cout << "- Scale Factor: " << fScaleFactor << endl;
cout << "- Initial Fast Threshold: " << fIniThFAST << endl;
cout << "- Minimum Fast Threshold: " << fMinThFAST << endl;
if(sensor==System::STEREO || sensor==System::RGBD)
{
mThDepth = mbf*(float)fSettings["ThDepth"]/fx;
cout << endl << "Depth Threshold (Close/Far Points): " << mThDepth << endl;
}
if(sensor==System::RGBD)
{
mDepthMapFactor = fSettings["DepthMapFactor"];
if(fabs(mDepthMapFactor)<1e-5)
mDepthMapFactor=1;
else
mDepthMapFactor = 1.0f/mDepthMapFactor;
}
}
void Tracking::SetLocalMapper(LocalMapping *pLocalMapper)
{
mpLocalMapper=pLocalMapper;
}
void Tracking::SetLoopClosing(LoopClosing *pLoopClosing)
{
mpLoopClosing=pLoopClosing;
}
void Tracking::SetViewer(Viewer *pViewer)
{
mpViewer=pViewer;
}
cv::Mat Tracking::GrabImageStereo(const cv::Mat &imRectLeft, const cv::Mat &imRectRight, const double ×tamp)
{
mImGray = imRectLeft;
cv::Mat imGrayRight = imRectRight;
if(mImGray.channels()==3)
{
if(mbRGB)
{
cvtColor(mImGray,mImGray,CV_RGB2GRAY);
cvtColor(imGrayRight,imGrayRight,CV_RGB2GRAY);
}
else
{
cvtColor(mImGray,mImGray,CV_BGR2GRAY);
cvtColor(imGrayRight,imGrayRight,CV_BGR2GRAY);
}
}
else if(mImGray.channels()==4)
{
if(mbRGB)
{
cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
cvtColor(imGrayRight,imGrayRight,CV_RGBA2GRAY);
}
else
{
cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
cvtColor(imGrayRight,imGrayRight,CV_BGRA2GRAY);
}
}
mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
Track();
return mCurrentFrame.mTcw.clone();
}
cv::Mat Tracking::GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double ×tamp)
{
mImGray = imRGB;
cv::Mat imDepth = imD;
if(mImGray.channels()==3)
{
if(mbRGB)
cvtColor(mImGray,mImGray,CV_RGB2GRAY);
else
cvtColor(mImGray,mImGray,CV_BGR2GRAY);
}
else if(mImGray.channels()==4)
{
if(mbRGB)
cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
else
cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
}
if((fabs(mDepthMapFactor-1.0f)>1e-5) || imDepth.type()!=CV_32F)
imDepth.convertTo(imDepth,CV_32F,mDepthMapFactor);
mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
Track();
return mCurrentFrame.mTcw.clone();
}
cv::Mat Tracking::GrabImageMonocular(const cv::Mat &im, const double ×tamp)
{
mImGray = im;
if(mImGray.channels()==3)
{
if(mbRGB)
cvtColor(mImGray,mImGray,CV_RGB2GRAY);
else
cvtColor(mImGray,mImGray,CV_BGR2GRAY);
}
else if(mImGray.channels()==4)
{
if(mbRGB)
cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
else
cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
}
if(mState==NOT_INITIALIZED || mState==NO_IMAGES_YET)
mCurrentFrame = Frame(mImGray,timestamp,mpIniORBextractor,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
else
mCurrentFrame = Frame(mImGray,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
Track();
return mCurrentFrame.mTcw.clone();
}
void Tracking::Track()
{
if(mState==NO_IMAGES_YET)
{
mState = NOT_INITIALIZED;
}
mLastProcessedState=mState;
// Get Map Mutex -> Map cannot be changed
unique_lock<mutex> lock(mpMap->mMutexMapUpdate);
// Different operation, according to whether the map is updated
bool bMapUpdated = false;
if(mpLocalMapper->GetMapUpdateFlagForTracking())
{
bMapUpdated = true;
mpLocalMapper->SetMapUpdateFlagInTracking(false);
}
if(mpLoopClosing->GetMapUpdateFlagForTracking())
{
bMapUpdated = true;
mpLoopClosing->SetMapUpdateFlagInTracking(false);
}
if(mCurrentFrame.mnId == mnLastRelocFrameId + 20)
{
bMapUpdated = true;
}
if(mState==NOT_INITIALIZED)
{
if(mSensor==System::STEREO || mSensor==System::RGBD)
StereoInitialization();
else
MonocularInitialization();
mpFrameDrawer->Update(this);
if(mState!=OK)
return;
}
else
{
// System is initialized. Track Frame.
bool bOK;
// Initial camera pose estimation using motion model or relocalization (if tracking is lost)
if(!mbOnlyTracking)
{
// Local Mapping is activated. This is the normal behaviour, unless
// you explicitly activate the "only tracking" mode.
if(mState==OK)
{
// Local Mapping might have changed some MapPoints tracked in last frame
CheckReplacedInLastFrame();
#ifdef TRACK_WITH_IMU
// If Visual-Inertial is initialized
if(mpLocalMapper->GetVINSInited())
{
// 20 Frames after reloc, track with only vision
if(mbRelocBiasPrepare)
{
bOK = TrackReferenceKeyFrame();
}
else
{
bOK = TrackWithIMU(bMapUpdated);
if(!bOK)
bOK = TrackReferenceKeyFrame();
}
}
// If Visual-Inertial not initialized, keep the same as pure-vslam
else
#endif
{
if(mVelocity.empty() || mCurrentFrame.mnId<mnLastRelocFrameId+2)
{
bOK = TrackReferenceKeyFrame();
}
else
{
bOK = TrackWithMotionModel();
if(!bOK)
bOK = TrackReferenceKeyFrame();
}
}
}
else
{
bOK = Relocalization();
if(bOK) cout<<"Relocalized. id: "<<mCurrentFrame.mnId<<endl;
}
}
else
{
// Localization Mode: Local Mapping is deactivated
cerr<<"Localization mode not supported yet"<<endl;
}
mCurrentFrame.mpReferenceKF = mpReferenceKF;
// If we have an initial estimation of the camera pose and matching. Track the local map.
if(!mbOnlyTracking)
{
if(bOK)
{
#ifndef TRACK_WITH_IMU
bOK = TrackLocalMap();
#else
if(!mpLocalMapper->GetVINSInited())
bOK = TrackLocalMap();
else
{
if(mbRelocBiasPrepare)
{
// 20 Frames after reloc, track with only vision
bOK = TrackLocalMap();
}
else
{
bOK = TrackLocalMapWithIMU(bMapUpdated);
}
}
#endif
}
}
else
{
// Localization Mode: Local Mapping is deactivated
cerr<<"Localization mode not supported yet"<<endl;
}
if(bOK)
{
mState = OK;
// Add Frames to re-compute IMU bias after reloc
if(mbRelocBiasPrepare)
{
mv20FramesReloc.push_back(mCurrentFrame);
// Before creating new keyframe
// Use 20 consecutive frames to re-compute IMU bias
if(mCurrentFrame.mnId == mnLastRelocFrameId+20-1)
{
NavState nscur;
RecomputeIMUBiasAndCurrentNavstate(nscur);
// Update NavState of CurrentFrame
mCurrentFrame.SetNavState(nscur);
// Clear flag and Frame buffer
mbRelocBiasPrepare = false;
mv20FramesReloc.clear();
// Release LocalMapping. To ensure to insert new keyframe.
mpLocalMapper->Release();
// Create new KeyFrame
mbCreateNewKFAfterReloc = true;
//Debug log
cout<<"NavState recomputed."<<endl;
cout<<"V:"<<mCurrentFrame.GetNavState().Get_V().transpose()<<endl;
cout<<"bg:"<<mCurrentFrame.GetNavState().Get_BiasGyr().transpose()<<endl;
cout<<"ba:"<<mCurrentFrame.GetNavState().Get_BiasAcc().transpose()<<endl;
cout<<"dbg:"<<mCurrentFrame.GetNavState().Get_dBias_Gyr().transpose()<<endl;
cout<<"dba:"<<mCurrentFrame.GetNavState().Get_dBias_Acc().transpose()<<endl;
}
}
}
else
{
mState=LOST;
// Clear Frame vectors for reloc bias computation
if(mv20FramesReloc.size()>0)
mv20FramesReloc.clear();
}
// Update drawer
mpFrameDrawer->Update(this);
// If tracking were good, check if we insert a keyframe
if(bOK)
{
// Update motion model
if(!mLastFrame.mTcw.empty())
{
cv::Mat LastTwc = cv::Mat::eye(4,4,CV_32F);
mLastFrame.GetRotationInverse().copyTo(LastTwc.rowRange(0,3).colRange(0,3));
mLastFrame.GetCameraCenter().copyTo(LastTwc.rowRange(0,3).col(3));
mVelocity = mCurrentFrame.mTcw*LastTwc;
}
else
mVelocity = cv::Mat();
mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw);
// Clean VO matches
for(int i=0; i<mCurrentFrame.N; i++)
{
MapPoint* pMP = mCurrentFrame.mvpMapPoints[i];
if(pMP)
if(pMP->Observations()<1)
{
mCurrentFrame.mvbOutlier[i] = false;
mCurrentFrame.mvpMapPoints[i]=static_cast<MapPoint*>(NULL);
}
}
// Delete temporal MapPoints
for(list<MapPoint*>::iterator lit = mlpTemporalPoints.begin(), lend = mlpTemporalPoints.end(); lit!=lend; lit++)
{
MapPoint* pMP = *lit;
delete pMP;
}
mlpTemporalPoints.clear();
// Check if we need to insert a new keyframe
if(NeedNewKeyFrame() || mbCreateNewKFAfterReloc)
CreateNewKeyFrame();
// Clear flag
if(mbCreateNewKFAfterReloc)
mbCreateNewKFAfterReloc = false;
// We allow points with high innovation (considererd outliers by the Huber Function)
// pass to the new keyframe, so that bundle adjustment will finally decide
// if they are outliers or not. We don't want next frame to estimate its position
// with those points so we discard them in the frame.
for(int i=0; i<mCurrentFrame.N;i++)
{
if(mCurrentFrame.mvpMapPoints[i] && mCurrentFrame.mvbOutlier[i])
mCurrentFrame.mvpMapPoints[i]=static_cast<MapPoint*>(NULL);
}
// Clear First-Init flag
if(mpLocalMapper->GetFirstVINSInited())
{
mpLocalMapper->SetFirstVINSInited(false);
}
}
// Reset if the camera get lost soon after initialization
if(mState==LOST)
{
//if(mpMap->KeyFramesInMap()<=5)
if(!mpLocalMapper->GetVINSInited())
{
cout << "Track lost soon after initialisation, reseting..." << endl;
mpSystem->Reset();
return;
}
}
if(!mCurrentFrame.mpReferenceKF)
mCurrentFrame.mpReferenceKF = mpReferenceKF;
mLastFrame = Frame(mCurrentFrame);
}
// Store frame pose information to retrieve the complete camera trajectory afterwards.
if(!mCurrentFrame.mTcw.empty())
{
cv::Mat Tcr = mCurrentFrame.mTcw*mCurrentFrame.mpReferenceKF->GetPoseInverse();
mlRelativeFramePoses.push_back(Tcr);
mlpReferences.push_back(mpReferenceKF);
mlFrameTimes.push_back(mCurrentFrame.mTimeStamp);
mlbLost.push_back(mState==LOST);
}
else
{
// This can happen if tracking is lost
mlRelativeFramePoses.push_back(mlRelativeFramePoses.back());
mlpReferences.push_back(mlpReferences.back());
mlFrameTimes.push_back(mlFrameTimes.back());