-
Notifications
You must be signed in to change notification settings - Fork 1
/
MapMaker.cc
1404 lines (1175 loc) · 43.1 KB
/
MapMaker.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
// Copyright 2008 Isis Innovation Limited
#include "MapMaker.h"
#include "MapPoint.h"
#include "Bundle.h"
#include "PatchFinder.h"
#include "SmallMatrixOpts.h"
#include "HelperFunctions.h"
#include "constants.h"
#include <cvd/vector_image_ref.h>
#include <cvd/vision.h>
#include <cvd/image_interpolate.h>
#include <cvd/utility.h>
#include <cvd/gl_helpers.h>
#include <cvd/fast_corner.h>
#include <TooN/SVD.h>
#include <TooN/SymEigen.h>
#include <gvars3/instances.h>
#include <fstream>
#include <algorithm>
#ifdef WIN32
#define WIN32_LEAN_AND_MEAN
#include <windows.h>
#endif
using namespace CVD;
using namespace std;
using namespace GVars3;
// Constructor sets up internal reference variable to Map.
// Most of the intialisation is done by Reset()..
MapMaker::MapMaker(Map& m, const StereoCamera &cam)
: mMap(m), mCamera(cam)
{
mbResetRequested = false;
Reset();
start();
GUI.RegisterCommand("SaveMap", GUICommandCallBack, this);
};
void MapMaker::Reset()
{
mMap.Reset();
mvFailureQueue.clear();
while(!mqNewQueue.empty()) mqNewQueue.pop();
mMap.vpKeyFrames.clear();
mvpKeyFrameQueue.clear();
mbBundleRunning = false;
mbBundleConverged_Full = true;
mbBundleConverged_Recent = true;
mbResetDone = true;
mbResetRequested = false;
mbBundleAbortRequested = false;
}
#define CHECK_RESET if(mbResetRequested) {Reset(); continue;};
void MapMaker::run()
{
#ifdef WIN32
SetThreadPriority(GetCurrentThread(), THREAD_PRIORITY_LOWEST);
#endif
while(!shouldStop())
{
CHECK_RESET;
sleep(5);
CHECK_RESET;
while(!mvQueuedCommands.empty())
{
GUICommandHandler(mvQueuedCommands.begin()->sCommand, mvQueuedCommands.begin()->sParams);
mvQueuedCommands.erase(mvQueuedCommands.begin());
}
if(!mMap.IsGood())
continue;
CHECK_RESET;
if(!mbBundleConverged_Recent && QueueSize() == 0)
BundleAdjustRecent();
CHECK_RESET;
if(mbBundleConverged_Recent && QueueSize() == 0)
ReFindNewlyMade();
CHECK_RESET;
if(mbBundleConverged_Recent && !mbBundleConverged_Full && QueueSize() == 0)
BundleAdjustAll();
CHECK_RESET;
if(mbBundleConverged_Recent && mbBundleConverged_Full && rand()%20 == 0 && QueueSize() == 0)
ReFindFromFailureQueue();
CHECK_RESET;
HandleBadPoints();
CHECK_RESET;
if(QueueSize() > 0)
AddKeyFrameFromTopOfQueue();
}
}
void MapMaker::RequestReset()
{
mbResetDone = false;
mbResetRequested = true;
}
bool MapMaker::ResetDone()
{
return mbResetDone;
}
void MapMaker::HandleBadPoints()
{
for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
{
MapPoint &p = *mMap.vpPoints[i];
if(p.nMEstimatorOutlierCount > 20 && p.nMEstimatorOutlierCount > p.nMEstimatorInlierCount)
p.bBad = true;
}
for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
if(mMap.vpPoints[i]->bBad)
{
MapPoint *p = mMap.vpPoints[i];
for(unsigned int j=0; j<mMap.vpKeyFrames.size(); j++)
{
KeyFrame &k = *mMap.vpKeyFrames[j];
if(k.mMeasurements.count(p))
k.mMeasurements.erase(p);
}
}
mMap.MoveBadPointsToTrash();
}
MapMaker::~MapMaker()
{
mbBundleAbortRequested = true;
stop();
cout << "Waiting for mapmaker to die.." << endl;
join();
cout << " .. mapmaker has died." << endl;
}
Vector<3> MapMaker::ReprojectPoint(SE3<> se3AfromB, const Vector<2> &v2A, const Vector<2> &v2B)
{
Matrix<3,4> PDash;
PDash.slice<0,0,3,3>() = se3AfromB.get_rotation().get_matrix();
PDash.slice<0,3,3,1>() = se3AfromB.get_translation().as_col();
Matrix<4> A;
A[0][0] = -1.0; A[0][1] = 0.0; A[0][2] = v2B[0]; A[0][3] = 0.0;
A[1][0] = 0.0; A[1][1] = -1.0; A[1][2] = v2B[1]; A[1][3] = 0.0;
A[2] = v2A[0] * PDash[2] - PDash[0];
A[3] = v2A[1] * PDash[2] - PDash[1];
SVD<4,4> svd(A);
Vector<4> v4Smallest = svd.get_VT()[3];
if(v4Smallest[3] == 0.0)
v4Smallest[3] = 0.00001;
return project(v4Smallest);
}
/* Triangulate point in a rectified camera rig */
Vector<3> MapMaker::TriangulatePoint(const Vector<2> &v2A, const Vector<2> &v2B){
Vector<4> point;
point.slice(0,2) = v2A;
point[2] = (mCamera.Left().getPrincipalPoint(0)-v2A[0]) - (mCamera.Right().getPrincipalPoint(0)-v2B[0]);
point[3] = 1;
Vector<4> projected = ReProjectionMatrix*point;
normalizeLast(projected);
return projected.slice(0,3);
}
// InitFromStereo() generates the initial match from single keyframes and two views
// and a vector of image correspondences.
bool MapMaker::InitFromStereo(KeyFrame &kF,
vector<pair<ImageRef, ImageRef> > &vTrailMatches,SE3<> &se3TrackerPose)
{
mCamera.Left().SetImageSize(kF.aCamLeftLevels[0].im.size());
mCamera.Right().SetImageSize(kF.aCamRightLevels[0].im.size());
//create the first keyframe in the MapMaker
KeyFrame *pkFirst = new KeyFrame();
*pkFirst = kF;
pkFirst->bFixed = true;
pkFirst->se3LeftCfromW = SE3<>();
pkFirst->se3RightCfromW = mCamera.GetRelativePose();
// Construct map from the stereo matches.
// PatchFinder is used for sub-pixel iteration here as we
// already have screen coords
PatchFinder finder;
for(unsigned int i=0; i<vTrailMatches.size(); i++)
{
MapPoint *p = new MapPoint();
// Patch source stuff:
p->pPatchSourceKF = pkFirst;
p->nSourceLevel = 0;
p->v3Normal_NC = makeVector( 0,0,-1);
p->irLeftFrameCenter = vTrailMatches[i].first;
p->irRightFrameCenter = vTrailMatches[i].second;
//set the vectors for patch warping for the left frameview
p->v3LeftFrameCenter_NC = unproject(mCamera.Left().UnProject(p->irLeftFrameCenter));
p->v3OneDownFromLeftFrameCenter_NC = unproject(mCamera.Left().UnProject(p->irLeftFrameCenter + ImageRef(0,1)));
p->v3OneRightFromLeftFrameCenter_NC = unproject(mCamera.Left().UnProject(p->irLeftFrameCenter + ImageRef(1,0)));
normalize(p->v3LeftFrameCenter_NC);
normalize(p->v3OneDownFromLeftFrameCenter_NC);
normalize(p->v3OneRightFromLeftFrameCenter_NC);
//set the vectors for patch warping for right frameview - not really necessary
p->v3RightFrameCenter_NC = unproject(mCamera.Right().UnProject(p->irRightFrameCenter));
p->v3OneDownFromRightFrameCenter_NC = unproject(mCamera.Right().UnProject(p->irRightFrameCenter + ImageRef(0,1)));
p->v3OneRightFromRightFrameCenter_NC = unproject(mCamera.Right().UnProject(p->irRightFrameCenter + ImageRef(1,0)));
normalize(p->v3RightFrameCenter_NC);
normalize(p->v3OneDownFromRightFrameCenter_NC);
normalize(p->v3OneRightFromRightFrameCenter_NC);
p->RefreshPixelVectors();
// Do sub-pixel alignment on the second image of stereo pair
finder.MakeTemplateCoarseNoWarp(*p);
finder.MakeSubPixTemplate();
finder.SetSubPixPos(vec(vTrailMatches[i].second));
bool bGood = finder.IterateSubPixToConvergence((*pkFirst).aCamRightLevels,10);
if(!bGood)
{
delete p; continue;
}
// Triangulate point:
// Get the sub pixel matching of the first point
Vector<2> v2SecondPos = finder.GetSubPixPos();
// unproject to world using stereo pair
p->v3WorldPos = mCamera.UnProjectToWorld(mCamera.UnProjectToLeft(vTrailMatches[i].first),mCamera.UnProjectToRight(vTrailMatches[i].second), pkFirst->se3LeftCfromW);
if(p->v3WorldPos[2] < 0.0)
{
cout << "z less than zero for points "<< endl << vTrailMatches[i].first << "," << vTrailMatches[i].second << endl;
delete p; continue;
}
p->pMMData = new MapMakerData();
mMap.vpPoints.push_back(p);
// add both pixel locations to stereo match
Measurement mFirst;
mFirst.nLevel = 0;
mFirst.Source = Measurement::SRC_ROOT;
mFirst.v2RootPos = vec(vTrailMatches[i].first);
mFirst.v2CorrespondingPos = finder.GetSubPixPos();
mFirst.bSubPix = true;
pkFirst->mMeasurements[p] = mFirst;
p->pMMData->sMeasurementKFs.insert(pkFirst);
}
//add the first keyframe
mMap.vpKeyFrames.push_back(pkFirst);
pkFirst->MakeKeyFrame_Rest();
RefreshSceneDepth(pkFirst);
mdBaseLine = mCamera.Left().getStereoBaseline();
mdBaseLineOverSceneDepth = mCamera.Left().getStereoBaseline()/pkFirst->dSceneDepthMean;
cout << "estimated scene depth is " << pkFirst->dSceneDepthMean << endl;
cout << "current size of map is " << mMap.vpPoints.size() << " points before InitAddMapPoint" << endl;
// add map points by true epipolar search
InitAddMapPoints(0);
InitAddMapPoints(3);
InitAddMapPoints(1);
InitAddMapPoints(2);
mbBundleConverged_Full = true;
mbBundleConverged_Recent = true;
ApplyGlobalTransformationToMap(CalcPlaneAligner());
mMap.bGood = true;
se3TrackerPose = pkFirst->se3LeftCfromW;
cout << " MapMaker: made initial map with " << mMap.vpPoints.size() << " points." << endl;
return true;
}
// ThinCandidates() Thins out a key-frame's candidate list.
void MapMaker::ThinCandidates(KeyFrame &k, Level &l, int nLevel)
{
vector<Candidate> &vCSrc = l.vCandidates;
vector<Candidate> vCGood;
vector<ImageRef> irBusyLevelPos;
for(meas_it it = k.mMeasurements.begin(); it!=k.mMeasurements.end(); it++)
{
if(!(it->second.nLevel == nLevel || it->second.nLevel == nLevel + 1))
continue;
irBusyLevelPos.push_back(ir_rounded(it->second.v2RootPos / LevelScale(nLevel)));
}
unsigned int nMinMagSquared = 10*10;
for(unsigned int i=0; i<vCSrc.size(); i++)
{
ImageRef irC = vCSrc[i].irLevelPos;
bool bGood = true;
for(unsigned int j=0; j<irBusyLevelPos.size(); j++)
{
ImageRef irB = irBusyLevelPos[j];
if((irB - irC).mag_squared() < nMinMagSquared)
{
bGood = false;
break;
}
}
if(bGood)
vCGood.push_back(vCSrc[i]);
}
vCSrc = vCGood;
}
// Add map points by epipolar search to the last-added key-frame, at a single
// specified pyramid level.
void MapMaker::InitAddMapPoints(int nLevel){
KeyFrame &kf = (*mMap.vpKeyFrames.front());
Level *l_l = kf.aCamLeftLevels;
ThinCandidates(kf,l_l[nLevel], nLevel);
//generate the map points from candidates
for(unsigned int n = 0; n<l_l[nLevel].vCandidates.size();n++)
InitAddPointEpipolar(kf,nLevel,(int)n);
}
void MapMaker::AddSomeMapPoints(int nLevel)
{
KeyFrame &kSrc = *(mMap.vpKeyFrames[mMap.vpKeyFrames.size() - 1]);
KeyFrame &kTarget = *(ClosestKeyFrame(kSrc));
Level &l = kSrc.aCamLeftLevels[nLevel];
ThinCandidates(kSrc, l, nLevel);
// if scene depth is huge- use the false stereo pair
if(kSrc.dSceneDepthMean/mdBaseLine > BASELINE_SCENE_DEPTH){
for(unsigned int i = 0; i<l.vCandidates.size(); i++)
AddPointEpipolar(kSrc, kTarget, nLevel, i);
}else{ // else use the good real stereo pair
for(unsigned int i=0; i<l.vCandidates.size(); i++)
InitAddPointEpipolar(kSrc,nLevel,(int)i);
}
}
void MapMaker::ApplyGlobalTransformationToMap(SE3<> se3NewFromOld)
{
for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++){
mMap.vpKeyFrames[i]->se3LeftCfromW = mMap.vpKeyFrames[i]->se3LeftCfromW * se3NewFromOld.inverse();
mMap.vpKeyFrames[i]->se3RightCfromW = mMap.vpKeyFrames[i]->se3RightCfromW * se3NewFromOld.inverse();
}
SO3<> so3Rot = se3NewFromOld.get_rotation();
for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
{
mMap.vpPoints[i]->v3WorldPos =
se3NewFromOld * mMap.vpPoints[i]->v3WorldPos;
mMap.vpPoints[i]->RefreshPixelVectors();
}
}
void MapMaker::ApplyGlobalScaleToMap(double dScale)
{
for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++){
mMap.vpKeyFrames[i]->se3LeftCfromW.get_translation() *= dScale;
mMap.vpKeyFrames[i]->se3RightCfromW.get_translation() *= dScale;
}
for(unsigned int i=0; i<mMap.vpPoints.size(); i++)
{
(*mMap.vpPoints[i]).v3WorldPos *= dScale;
(*mMap.vpPoints[i]).v3LeftFramePixelRight_W *= dScale;
(*mMap.vpPoints[i]).v3LeftFramePixelDown_W *= dScale;
(*mMap.vpPoints[i]).v3RightFramePixelRight_W *= dScale;
(*mMap.vpPoints[i]).v3RightFramePixelDown_W *= dScale;
(*mMap.vpPoints[i]).RefreshPixelVectors();
}
}
void MapMaker::AddKeyFrame(KeyFrame &k)
{
KeyFrame *pK = new KeyFrame;
*pK = k;
pK->pSBI = NULL;
mvpKeyFrameQueue.push_back(pK);
if(mbBundleRunning)
mbBundleAbortRequested = true;
}
void MapMaker::AddKeyFrameFromTopOfQueue()
{
if(mvpKeyFrameQueue.size() == 0)
return;
KeyFrame *pK = mvpKeyFrameQueue[0];
mvpKeyFrameQueue.erase(mvpKeyFrameQueue.begin());
pK->MakeKeyFrame_Rest();
mMap.vpKeyFrames.push_back(pK);
for(meas_it it = pK->mMeasurements.begin();
it!=pK->mMeasurements.end();
it++)
{
it->first->pMMData->sMeasurementKFs.insert(pK);
it->second.Source = Measurement::SRC_TRACKER;
}
ReFindInSingleKeyFrame(*pK);
AddSomeMapPoints(3);
AddSomeMapPoints(0);
AddSomeMapPoints(1);
AddSomeMapPoints(2);
mbBundleConverged_Full = false;
mbBundleConverged_Recent = false;
}
// add points from a single keyframe using an epipolar search across the two frames
bool MapMaker::InitAddPointEpipolar(KeyFrame &first,
int nLevel,
int nCandidate){
// get a candidate
Candidate &candidate = first.aCamLeftLevels[nLevel].vCandidates[nCandidate];
ImageRef irLeftFramePos = candidate.irLevelPos;
Vector<2> v2RootLeftPos = LevelZeroPos(irLeftFramePos,nLevel);
PatchFinder Finder;
// make a unwarped template of the nth level of the left image
// at the position of the candidate in that level
Finder.MakeTemplateCoarseNoWarp(first.aCamLeftLevels, nLevel, irLeftFramePos);
if(Finder.TemplateBad())
return false;
//all the corners in the right image to search for matches
vector<ImageRef> &vIR =first.aCamRightLevels[nLevel].vCorners;
int nBest = -1;
int nBestZMSSD = Finder.mnMaxSSD + 1;
int nLevelScale = LevelScale(nLevel);
// set a maximum distance to search in pixels (taking into account image res)
int SearchDistMag = (200 + nLevelScale -1)/nLevelScale;
/* for level 0 search x = 100
for level 0 search y = 15
for level 1 search x = 50
for level 1 search y = 10
for level 2 search x = 25
for level 2 search y = 5
for level 3 search x = 13
for level 3 search y = 3
*/
// get the epipolar line
Vector<3> EpipolarLine = mCamera.GetEpipolarLine(irLeftFramePos);
// seach all corners and compare to epipolar line
for(int i=0;i<(int)first.aCamRightLevels[nLevel].vCorners.size();i++){
ImageRef irMatch = vIR[i];
if(unproject(vec(irMatch))*EpipolarLine > /*0.05 0.1*/0.01*nLevelScale ||
sqrt( (vec(irMatch)-vec(irLeftFramePos))* (vec(irMatch)-vec(irLeftFramePos))) > SearchDistMag ||
irMatch.x < irLeftFramePos.x) continue;
// attempt to match if on epipolar line
int nZMSSD = Finder.ZMSSDAtPoint(first.aCamRightLevels[nLevel].im,irMatch);
if(nZMSSD < nBestZMSSD){
nBest = i;
nBestZMSSD = nZMSSD;
}
}
ImageRef irRightFramePos;
// if we missed a point, try along the line - not on fast corners
if(nBest == -1){
Vector<3> NormEpipolar = EpipolarLine;
normalize(NormEpipolar);
ImageRef irBest(-1,-1);
for(int x = irLeftFramePos.x;x<irLeftFramePos.x+SearchDistMag;x++) {
ImageRef OnLine(x,((-EpipolarLine[0]/EpipolarLine[1])*x)-(EpipolarLine[2]/EpipolarLine[1]));
int nZMSSD = Finder.ZMSSDAtPoint(first.aCamRightLevels[nLevel].im,OnLine);
if(nZMSSD < nBestZMSSD){
irBest = OnLine;
nBestZMSSD = nZMSSD;
}
}
if(irBest.x == -1)
return false;
irRightFramePos = irBest;
}else{
irRightFramePos = vIR[nBest];
}
// now finder has found a matching point, try to
// sub-pixel match it in the image level
Finder.MakeSubPixTemplate();
Finder.SetSubPixPos(LevelZeroPos(/*vIR[nBest]*/irRightFramePos,nLevel));
bool bSubPixConverges = Finder.IterateSubPixToConvergence(first.aCamRightLevels,10);
if(!bSubPixConverges)
return false;
Vector <2> v2RootRightPos = Finder.GetSubPixPos();
// Triangulate this 3D point
Vector<3> v3WorldPos = mCamera.UnProjectToWorldFromPixels(v2RootLeftPos,v2RootRightPos,first.se3LeftCfromW);
MapPoint *pNew = new MapPoint;
pNew->v3WorldPos = v3WorldPos;
pNew->pMMData = new MapMakerData();
// Set position of point in keyframe and level found
pNew->pPatchSourceKF = &first;
pNew->nSourceLevel = nLevel;
pNew->v3Normal_NC = makeVector(0,0,-1);
pNew->irLeftFrameCenter = irLeftFramePos;
pNew->irRightFrameCenter = /*vIR[nBest]*/irRightFramePos;
// Calcuate vectors used for warping patch in left image
pNew->v3LeftFrameCenter_NC = unproject(mCamera.UnProjectToLeft(v2RootLeftPos));
pNew->v3OneRightFromLeftFrameCenter_NC = unproject(mCamera.UnProjectToLeft(v2RootLeftPos + vec(ImageRef(nLevelScale,0))));
pNew->v3OneDownFromLeftFrameCenter_NC = unproject(mCamera.UnProjectToLeft(v2RootLeftPos + vec(ImageRef(0,nLevelScale))));
normalize(pNew->v3LeftFrameCenter_NC);
normalize(pNew->v3OneDownFromLeftFrameCenter_NC);
normalize(pNew->v3OneRightFromLeftFrameCenter_NC);
// Calcuate vectors used for warping patch in right image
pNew->v3RightFrameCenter_NC = unproject(mCamera.UnProjectToRight(v2RootRightPos));
pNew->v3OneRightFromRightFrameCenter_NC = unproject(mCamera.UnProjectToRight(v2RootRightPos + vec(ImageRef(nLevelScale,0))));
pNew->v3OneDownFromRightFrameCenter_NC = unproject(mCamera.UnProjectToRight(v2RootRightPos + vec(ImageRef(0,nLevelScale))));
normalize(pNew->v3RightFrameCenter_NC);
normalize(pNew->v3OneDownFromRightFrameCenter_NC);
normalize(pNew->v3OneRightFromRightFrameCenter_NC);
pNew->RefreshPixelVectors();
// generate sterem measurements
mMap.vpPoints.push_back(pNew);
mqNewQueue.push(pNew);
Measurement m;
m.Source = Measurement::SRC_ROOT;
m.v2RootPos = v2RootLeftPos;
m.v2CorrespondingPos = v2RootRightPos;
m.nLevel = nLevel;
m.bSubPix = true;
first.mMeasurements[pNew] = m;
pNew->pMMData->sMeasurementKFs.insert(&first);
return true;
}
// PTAM's original map point adder - now gets guess depth from the predicted true
//stereo depth
bool MapMaker::AddPointEpipolar(KeyFrame &kSrc,
KeyFrame &kTarget,
int nLevel,
int nCandidate)
{
static Image<Vector<2> > imUnProj;
static bool bMadeCache = false;
if(!bMadeCache)
{
imUnProj.resize(kSrc.aCamLeftLevels[0].im.size());
ImageRef ir;
do imUnProj[ir] = mCamera.UnProjectToLeft(ir);
while(ir.next(imUnProj.size()));
bMadeCache = true;
}
//levelScale is bitwise left shift 1 << nLevel so returns 1,2,4,8 etc.
int nLevelScale = LevelScale(nLevel);
Candidate &candidate = kSrc.aCamLeftLevels[nLevel].vCandidates[nCandidate];
ImageRef irSrcLeftLevelPos = candidate.irLevelPos;
Vector<2> v2SrcLeftRootPos = LevelZeroPos(irSrcLeftLevelPos, nLevel);
//find depth of point by stereo match
//make a template of the left image point
PatchFinder EpiFinder_A;
EpiFinder_A.MakeTemplateCoarseNoWarp(kSrc.aCamLeftLevels, nLevel, irSrcLeftLevelPos); //coarse no warp takes level n pos
if(EpiFinder_A.TemplateBad())
return false;
Vector<3> EpipolarLine = mCamera.GetEpipolarLine(irSrcLeftLevelPos);
vector<Candidate> &vCan = kSrc.aCamRightLevels[nLevel].vCandidates;
int nBestIndex = -1;
int nBestSSD = EpiFinder_A.mnMaxSSD + 1;
for(int i=0;i<(int)kSrc.aCamRightLevels[nLevel].vCandidates.size();i++){
ImageRef IR = vCan[i].irLevelPos;
int nZMSSD = EpiFinder_A.ZMSSDAtPoint(kSrc.aCamRightLevels[nLevel].im, IR);
if(nZMSSD < nBestSSD){
nBestIndex = i;
nBestSSD = nZMSSD;
}
}
if(nBestIndex == -1)
return false;
EpiFinder_A.MakeSubPixTemplate();
EpiFinder_A.SetSubPixPos(LevelZeroPos(vCan[nBestIndex].irLevelPos,nLevel));
if(!EpiFinder_A.IterateSubPixToConvergence(kSrc.aCamRightLevels,10))
return false;
Vector<2> v2SrcRightRootPos_A = EpiFinder_A.GetSubPixPos();
ImageRef irSrcRightLevelPos_A = ir(v2SrcRightRootPos_A/LevelScale(nLevel));
//get the depth
double Depth = mCamera.UnProjectToWorldFromPixels(v2SrcLeftRootPos,v2SrcRightRootPos_A,kSrc.se3LeftCfromW)[2];
Vector<3> v3Ray_SC = unproject(mCamera.UnProjectToLeft(v2SrcLeftRootPos));
normalize(v3Ray_SC);
Vector<3> v3LineDirn_TC = kTarget.se3LeftCfromW.get_rotation() * (kSrc.se3LeftCfromW.get_rotation().inverse() * v3Ray_SC);
double dMean = kSrc.dSceneDepthMean;
double dSigma = kSrc.dSceneDepthSigma;
// set start and end depth via stereo guess
double dStartDepth = max(Depth/2, dMean - dSigma);
double dEndDepth = min(Depth*2, dMean + dSigma);
Vector<3> v3CamCenter_TC = kTarget.se3LeftCfromW * kSrc.se3LeftCfromW.inverse().get_translation();
Vector<3> v3RayStart_TC = v3CamCenter_TC + dStartDepth * v3LineDirn_TC; Vector<3> v3RayEnd_TC = v3CamCenter_TC + dEndDepth * v3LineDirn_TC;
if(v3RayEnd_TC[2] <= v3RayStart_TC[2])
return false;
if(v3RayEnd_TC[2] <= 0.0 ) return false;
if(v3RayStart_TC[2] <= 0.0)
v3RayStart_TC += v3LineDirn_TC * (0.001 - v3RayStart_TC[2] / v3LineDirn_TC[2]);
Vector<2> v2A = project(v3RayStart_TC);
Vector<2> v2B = project(v3RayEnd_TC);
Vector<2> v2AlongProjectedLine = v2A-v2B;
if(v2AlongProjectedLine * v2AlongProjectedLine < 0.00000001)
{
return false;
}
normalize(v2AlongProjectedLine);
Vector<2> v2Normal;
v2Normal[0] = v2AlongProjectedLine[1];
v2Normal[1] = -v2AlongProjectedLine[0];
double dNormDist = v2A * v2Normal;
if(fabs(dNormDist) > mCamera.Left().LargestRadiusInImage() )
return false;
double dMinLen = min(v2AlongProjectedLine * v2A, v2AlongProjectedLine * v2B) - 0.05;
double dMaxLen = max(v2AlongProjectedLine * v2A, v2AlongProjectedLine * v2B) + 0.05;
if(dMinLen < -2.0) dMinLen = -2.0;
if(dMaxLen < -2.0) dMaxLen = -2.0;
if(dMinLen > 2.0) dMinLen = 2.0;
if(dMaxLen > 2.0) dMaxLen = 2.0;
PatchFinder Finder;
Finder.MakeTemplateCoarseNoWarp(kSrc.aCamLeftLevels, nLevel, irSrcLeftLevelPos);
if(Finder.TemplateBad()) return false;
vector<Vector<2> > &vv2Corners = kTarget.aCamLeftLevels[nLevel].vImplaneCorners;
vector<ImageRef> &vIR = kTarget.aCamLeftLevels[nLevel].vCorners;
if(!kTarget.aCamLeftLevels[nLevel].bImplaneCornersCached)
{
for(unsigned int i=0; i<vIR.size(); i++) // over all corners in target img..
vv2Corners.push_back(imUnProj[ir(LevelZeroPos(vIR[i], nLevel))]);
kTarget.aCamLeftLevels[nLevel].bImplaneCornersCached = true;
}
int nBest = -1;
int nBestZMSSD = Finder.mnMaxSSD + 1;
double dMaxDistDiff = mCamera.Left().OnePixelDist() * (4.0 + 1.0 * nLevelScale);
double dMaxDistSq = dMaxDistDiff * dMaxDistDiff;
for(unsigned int i=0; i<vv2Corners.size(); i++) // over all corners in target img..
{
Vector<2> v2Im = vv2Corners[i];
double dDistDiff = dNormDist - v2Im * v2Normal;
if(dDistDiff * dDistDiff > dMaxDistSq) continue;
if(v2Im * v2AlongProjectedLine < dMinLen) continue;
if(v2Im * v2AlongProjectedLine > dMaxLen) continue;
int nZMSSD = Finder.ZMSSDAtPoint(kTarget.aCamLeftLevels[nLevel].im, vIR[i]);
if(nZMSSD < nBestZMSSD)
{
nBest = i;
nBestZMSSD = nZMSSD;
}
}
if(nBest == -1) return false; // Nothing found.
Finder.MakeSubPixTemplate();
Finder.SetSubPixPos(LevelZeroPos(vIR[nBest], nLevel));
bool bSubPixConverges = Finder.IterateSubPixToConvergence(kTarget.aCamLeftLevels,10);
if(!bSubPixConverges)
return false;
Vector<2> v2DstLeftRootPos = Finder.GetSubPixPos();
Vector<3> v3New;
v3New = kTarget.se3LeftCfromW.inverse() *
ReprojectPoint(kSrc.se3LeftCfromW *
kTarget.se3LeftCfromW.inverse(),
mCamera.UnProjectToLeft(v2SrcLeftRootPos),
mCamera.UnProjectToLeft(v2DstLeftRootPos));
//confirm find with stereo search in second keyframe - adds robustness
Vector<3> v3RightCam = (kSrc.se3LeftCfromW * v3New);
v3RightCam = mCamera.Left().Extrinsic * v3RightCam;
Vector<2> v2RightImPos = mCamera.Right().Project(project(v3RightCam));
PatchFinder EpiFinder;
EpiFinder.MakeTemplateCoarseNoWarp(kSrc.aCamLeftLevels, nLevel, irSrcLeftLevelPos);
if(EpiFinder.TemplateBad()){
return false;
}
// find the point with epipolar search
bool bFoundEpipolar = EpiFinder.FindPatchCoarse(ir(v2RightImPos), kSrc.aCamRightLevels, 15);
if(!bFoundEpipolar){
return false;
}
EpiFinder.MakeSubPixTemplate();
if(!EpiFinder.IterateSubPixToConvergence(kSrc.aCamRightLevels,10))
return false;
Vector<2> v2SrcRightRootPos = EpiFinder.GetSubPixPos();
ImageRef irSrcRightLevelPos = ir(v2SrcRightRootPos/LevelScale(nLevel));
Vector<3> v3RightCam2 = kTarget.se3LeftCfromW * v3New;
v3RightCam2 = mCamera.Left().Extrinsic * v3RightCam2;
Vector<2> v2RightImPos2 = mCamera.Right().Project(project(v3RightCam2));
PatchFinder EpiFinder2;
EpiFinder2.MakeTemplateCoarseNoWarp(kTarget.aCamLeftLevels, nLevel, vIR[nBest]);
if(EpiFinder2.TemplateBad()){
return false;
}
bool bFoundEpipolar2 = EpiFinder2.FindPatchCoarse(ir(v2RightImPos2), kTarget.aCamRightLevels, 15);
if(!bFoundEpipolar2){
return false;
}
EpiFinder2.MakeSubPixTemplate();
if(!EpiFinder2.IterateSubPixToConvergence(kTarget.aCamRightLevels,10))
return false;
MapPoint *pNew = new MapPoint;
pNew->v3WorldPos = v3New;
pNew->pMMData = new MapMakerData();
pNew->pPatchSourceKF = &kSrc;
pNew->nSourceLevel = nLevel;
pNew->v3Normal_NC = makeVector( 0,0,-1);
pNew->irLeftFrameCenter = irSrcLeftLevelPos;
pNew->irRightFrameCenter = irSrcRightLevelPos;
// get the unit vectors for unprojection in both images
pNew->v3LeftFrameCenter_NC = unproject(mCamera.Left().UnProject(v2SrcLeftRootPos));
pNew->v3OneRightFromLeftFrameCenter_NC = unproject(mCamera.Left().UnProject(v2SrcLeftRootPos + vec(ImageRef(nLevelScale,0))));
pNew->v3OneDownFromLeftFrameCenter_NC = unproject(mCamera.Left().UnProject(v2SrcLeftRootPos + vec(ImageRef(0,nLevelScale))));
normalize(pNew->v3LeftFrameCenter_NC);
normalize(pNew->v3OneDownFromLeftFrameCenter_NC);
normalize(pNew->v3OneRightFromLeftFrameCenter_NC);
pNew->v3RightFrameCenter_NC = unproject(mCamera.Right().UnProject(v2SrcRightRootPos));
pNew->v3OneRightFromRightFrameCenter_NC = unproject(mCamera.Right().UnProject(v2SrcRightRootPos + vec(ImageRef(nLevelScale,0))));
pNew->v3OneDownFromRightFrameCenter_NC = unproject(mCamera.Right().UnProject(v2SrcRightRootPos + vec(ImageRef(0,nLevelScale))));
normalize(pNew->v3RightFrameCenter_NC);
normalize(pNew->v3OneDownFromRightFrameCenter_NC);
normalize(pNew->v3OneRightFromRightFrameCenter_NC);
pNew->RefreshPixelVectors();
mMap.vpPoints.push_back(pNew);
mqNewQueue.push(pNew);
//gen the stereo measurements
Measurement m;
m.Source = Measurement::SRC_ROOT;
m.v2RootPos = v2SrcLeftRootPos;
m.v2CorrespondingPos = v2SrcRightRootPos;
m.nLevel = nLevel;
m.bSubPix = true;
kSrc.mMeasurements[pNew] = m;
m.Source = Measurement::SRC_EPIPOLAR;
m.v2RootPos = Finder.GetSubPixPos();
m.v2CorrespondingPos = EpiFinder2.GetSubPixPos();
kTarget.mMeasurements[pNew] = m;
pNew->pMMData->sMeasurementKFs.insert(&kSrc);
pNew->pMMData->sMeasurementKFs.insert(&kTarget);
return true;
}
double MapMaker::KeyFrameLinearDist(KeyFrame &k1, KeyFrame &k2)
{
Vector<3> v3KF1_CamPos = k1.se3LeftCfromW.inverse().get_translation();
Vector<3> v3KF2_CamPos = k2.se3LeftCfromW.inverse().get_translation();
Vector<3> v3Diff = v3KF2_CamPos - v3KF1_CamPos;
double dDist = sqrt(v3Diff * v3Diff);
return dDist;
}
vector<KeyFrame*> MapMaker::NClosestKeyFrames(KeyFrame &k, unsigned int N)
{
vector<pair<double, KeyFrame* > > vKFandScores;
for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
{
if(mMap.vpKeyFrames[i] == &k)
continue;
double dDist = KeyFrameLinearDist(k, *mMap.vpKeyFrames[i]);
vKFandScores.push_back(make_pair(dDist, mMap.vpKeyFrames[i]));
}
if(N > vKFandScores.size())
N = vKFandScores.size();
partial_sort(vKFandScores.begin(), vKFandScores.begin() + N, vKFandScores.end());
vector<KeyFrame*> vResult;
for(unsigned int i=0; i<N; i++)
vResult.push_back(vKFandScores[i].second);
return vResult;
}
KeyFrame* MapMaker::ClosestKeyFrame(KeyFrame &k)
{
double dClosestDist = 9999999999.9;
int nClosest = -1;
for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
{
if(mMap.vpKeyFrames[i] == &k)
continue;
double dDist = KeyFrameLinearDist(k, *mMap.vpKeyFrames[i]);
if(dDist < dClosestDist)
{
dClosestDist = dDist;
nClosest = i;
}
}
assert(nClosest != -1);
return mMap.vpKeyFrames[nClosest];
}
double MapMaker::DistToNearestKeyFrame(KeyFrame &kCurrent)
{
KeyFrame *pClosest = ClosestKeyFrame(kCurrent);
double dDist = KeyFrameLinearDist(kCurrent, *pClosest);
return dDist;
}
bool MapMaker::NeedNewKeyFrame(KeyFrame &kCurrent)
{
KeyFrame *pClosest = ClosestKeyFrame(kCurrent);
double dDist = KeyFrameLinearDist(kCurrent, *pClosest);
dDist *= (1.0 / kCurrent.dSceneDepthMean);
if(dDist > GV2.GetDouble("MapMaker.MaxKFDistWiggleMult",1.0,SILENT) * mdBaseLineOverSceneDepth)
return true;
return false; double a[] = {0,0,0,0,0};
CvMat dist = cvMat(5,1,CV_64FC1,a);
cv::Mat dist_(&dist);// = dist;
}
void MapMaker::BundleAdjustSingleKeyframe()
{
//not used
}
void MapMaker::BundleAdjustAll()
{
set<KeyFrame*> sAdj;
set<KeyFrame*> sFixed;
for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
if(mMap.vpKeyFrames[i]->bFixed)
sFixed.insert(mMap.vpKeyFrames[i]);
else
sAdj.insert(mMap.vpKeyFrames[i]);
set<MapPoint*> sMapPoints;
for(unsigned int i=0; i<mMap.vpPoints.size();i++)
sMapPoints.insert(mMap.vpPoints[i]);
BundleAdjust(sAdj, sFixed, sMapPoints, false);
}
void MapMaker::BundleAdjustRecent()
{
if(mMap.vpKeyFrames.size() < 8)
{
mbBundleConverged_Recent = true;
return;
}
set<KeyFrame*> sAdjustSet;
KeyFrame *pkfNewest = mMap.vpKeyFrames.back();
sAdjustSet.insert(pkfNewest);
vector<KeyFrame*> vClosest = NClosestKeyFrames(*pkfNewest, 4);
for(int i=0; i<4; i++)
if(vClosest[i]->bFixed == false)
sAdjustSet.insert(vClosest[i]);
set<MapPoint*> sMapPoints;
for(set<KeyFrame*>::iterator iter = sAdjustSet.begin();
iter!=sAdjustSet.end();
iter++)
{
map<MapPoint*,Measurement> &mKFMeas = (*iter)->mMeasurements;
for(meas_it jiter = mKFMeas.begin(); jiter!= mKFMeas.end(); jiter++)
sMapPoints.insert(jiter->first);
};
set<KeyFrame*> sFixedSet;
for(vector<KeyFrame*>::iterator it = mMap.vpKeyFrames.begin(); it!=mMap.vpKeyFrames.end(); it++)
{
if(sAdjustSet.count(*it))
continue;
bool bInclude = false;
for(meas_it jiter = (*it)->mMeasurements.begin(); jiter!= (*it)->mMeasurements.end(); jiter++)
if(sMapPoints.count(jiter->first))
{
bInclude = true;
break;
}
if(bInclude)
sFixedSet.insert(*it);
}
BundleAdjust(sAdjustSet, sFixedSet, sMapPoints, true);
}
void MapMaker::BundleAdjust(set<KeyFrame*> sAdjustSet, set<KeyFrame*> sFixedSet, set<MapPoint*> sMapPoints, bool bRecent)
{
Bundle b(mCamera.Left(), mCamera.Right());
mbBundleRunning = true;
mbBundleRunningIsRecent = bRecent;
map<MapPoint*, int> mPoint_BundleID;
map<int, MapPoint*> mBundleID_Point;
map<KeyFrame*, int> mView_BundleID;
map<int, KeyFrame*> mBundleID_View;
for(set<KeyFrame*>::iterator it = sAdjustSet.begin(); it!= sAdjustSet.end(); it++)
{
int nBundleID = b.AddCamera((*it)->se3LeftCfromW, (*it)->bFixed);
mView_BundleID[*it] = nBundleID;
mBundleID_View[nBundleID] = *it;
}
for(set<KeyFrame*>::iterator it = sFixedSet.begin(); it!= sFixedSet.end(); it++)
{
int nBundleID = b.AddCamera((*it)->se3LeftCfromW, true);
mView_BundleID[*it] = nBundleID;
mBundleID_View[nBundleID] = *it;
}
for(set<MapPoint*>::iterator it = sMapPoints.begin(); it!=sMapPoints.end(); it++)
{
int nBundleID = b.AddPoint((*it)->v3WorldPos);
mPoint_BundleID[*it] = nBundleID;
mBundleID_Point[nBundleID] = *it;
}
// Add the relevant stereo measurments measurements
for(unsigned int i=0; i<mMap.vpKeyFrames.size(); i++)
{
if(mView_BundleID.count(mMap.vpKeyFrames[i]) == 0)
continue;