-
Notifications
You must be signed in to change notification settings - Fork 392
/
Copy pathMLPnPsolver.cpp
1099 lines (965 loc) · 43 KB
/
MLPnPsolver.cpp
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 PYSLAM
*
* Copyright (C) 2016-present Luigi Freda <luigi dot freda at gmail dot com>
*
* PYSLAM 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.
*
* PYSLAM 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 PYSLAM. 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/>.
*/
/******************************************************************************
* Author: Steffen Urban *
* Contact: urbste@gmail.com *
* License: Copyright (c) 2016 Steffen Urban, ANU. All rights reserved. *
* *
* Redistribution and use in source and binary forms, with or without *
* modification, are permitted provided that the following conditions *
* are met: *
* * Redistributions of source code must retain the above copyright *
* notice, this list of conditions and the following disclaimer. *
* * Redistributions in binary form must reproduce the above copyright *
* notice, this list of conditions and the following disclaimer in the *
* documentation and/or other materials provided with the distribution. *
* * Neither the name of ANU nor the names of its contributors may be *
* used to endorse or promote products derived from this software without *
* specific prior written permission. *
* *
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"*
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE *
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE *
* ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE *
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL *
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR *
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY *
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF *
* SUCH DAMAGE. *
******************************************************************************/
#include "MLPnPsolver.h"
#include "Random.h"
#include <Eigen/Sparse>
using namespace std;
namespace utils {
Eigen::Matrix<float,3,3> toMatrix3f(const cv::Mat &cvMat3)
{
Eigen::Matrix<float,3,3> M;
M << cvMat3.at<float>(0,0), cvMat3.at<float>(0,1), cvMat3.at<float>(0,2),
cvMat3.at<float>(1,0), cvMat3.at<float>(1,1), cvMat3.at<float>(1,2),
cvMat3.at<float>(2,0), cvMat3.at<float>(2,1), cvMat3.at<float>(2,2);
return M;
}
Eigen::Matrix<float,3,1> toVector3f(const cv::Mat &cvVector)
{
Eigen::Matrix<float,3,1> v;
v << cvVector.at<float>(0), cvVector.at<float>(1), cvVector.at<float>(2);
return v;
}
MLPnPsolver::MLPnPsolver(const PnPsolverInput& input):
mnInliersi(0), mnIterations(0), mnBestInliers(0), N(0){
assert(input.mvP3Dw.size() == input.mvP2D.size());
assert(input.mvP3Dw.size() == input.mvSigma2.size());
N = input.mvP3Dw.size();
mvBearingVecs.reserve(N);
mvP2D.reserve(N);
mvSigma2.reserve(N);
mvP3Dw.reserve(N);
mvKeyPointIndices.reserve(N);
mvAllIndices.reserve(N);
mpCamera = std::make_shared<PinHoleCamera>(input.fx, input.fy, input.cx, input.cy);
for(size_t i = 0, iend = N; i < iend; i++)
{
const auto& p2 = input.mvP2D[i];
const auto& p3 = input.mvP3Dw[i];
mvP2D.push_back(cv::Point2f(p2.x(), p2.y()));
mvSigma2.push_back(input.mvSigma2[i]);
//Bearing vector should be normalized
cv::Point3f cv_br = mpCamera->unproject(p2);
cv_br /= cv_br.z;
bearingVector_t br(cv_br.x,cv_br.y,cv_br.z);
mvBearingVecs.push_back(br);
//3D coordinates
point_t pos(p3.x(), p3.y(), p3.z());
mvP3Dw.push_back(pos);
mvKeyPointIndices.push_back(i);
mvAllIndices.push_back(i);
}
SetRansacParameters();
}
//RANSAC methods
bool MLPnPsolver::iterate(int nIterations, bool &bNoMore, std::vector<uint8_t> &vbInliers, int &nInliers, Eigen::Matrix4f &Tout){
Tout.setIdentity();
bNoMore = false;
vbInliers.clear();
nInliers=0;
if(N<mRansacMinInliers)
{
bNoMore = true;
return false;
}
vector<size_t> vAvailableIndices;
int nCurrentIterations = 0;
while(mnIterations<mRansacMaxIts || nCurrentIterations<nIterations)
{
nCurrentIterations++;
mnIterations++;
vAvailableIndices = mvAllIndices;
//Bearing vectors and 3D points used for this ransac iteration
bearingVectors_t bearingVecs(mRansacMinSet);
points_t p3DS(mRansacMinSet);
vector<int> indexes(mRansacMinSet);
// Get min set of points
for(short i = 0; i < mRansacMinSet; ++i)
{
int randi = Random::RandomInt(0, vAvailableIndices.size()-1);
int idx = vAvailableIndices[randi];
bearingVecs[i] = mvBearingVecs[idx];
p3DS[i] = mvP3Dw[idx];
indexes[i] = i;
vAvailableIndices[randi] = vAvailableIndices.back();
vAvailableIndices.pop_back();
}
//By the moment, we are using MLPnP without covariance info
cov3_mats_t covs(1);
//Result
transformation_t result;
// Compute camera pose
computePose(bearingVecs,p3DS,covs,indexes,result);
//Save result
mRi[0][0] = result(0,0);
mRi[0][1] = result(0,1);
mRi[0][2] = result(0,2);
mRi[1][0] = result(1,0);
mRi[1][1] = result(1,1);
mRi[1][2] = result(1,2);
mRi[2][0] = result(2,0);
mRi[2][1] = result(2,1);
mRi[2][2] = result(2,2);
mti[0] = result(0,3);mti[1] = result(1,3);mti[2] = result(2,3);
// Check inliers
CheckInliers();
if(mnInliersi>=mRansacMinInliers)
{
// If it is the best solution so far, save it
if(mnInliersi>mnBestInliers)
{
mvbBestInliers = mvbInliersi;
mnBestInliers = mnInliersi;
cv::Mat Rcw(3,3,CV_64F,mRi);
cv::Mat tcw(3,1,CV_64F,mti);
Rcw.convertTo(Rcw,CV_32F);
tcw.convertTo(tcw,CV_32F);
mBestTcw.setIdentity();
mBestTcw.block<3,3>(0,0) = toMatrix3f(Rcw);
mBestTcw.block<3,1>(0,3) = toVector3f(tcw);
Eigen::Matrix<double, 3, 3, Eigen::RowMajor> eigRcw(mRi[0]);
Eigen::Vector3d eigtcw(mti);
}
if(Refine())
{
nInliers = mnRefinedInliers;
vbInliers = vector<uint8_t>(N,0);
for(int i=0; i<N; i++)
{
if(mvbRefinedInliers[i])
vbInliers[mvKeyPointIndices[i]] = 1;
}
Tout = mRefinedTcw;
return true;
}
}
}
if(mnIterations>=mRansacMaxIts)
{
bNoMore=true;
if(mnBestInliers>=mRansacMinInliers)
{
nInliers=mnBestInliers;
vbInliers = vector<uint8_t>(N,0);
for(int i=0; i<N; i++)
{
if(mvbBestInliers[i])
vbInliers[mvKeyPointIndices[i]] = 1;
}
Tout = mBestTcw;
return true;
}
}
return false;
}
void MLPnPsolver::SetRansacParameters(double probability, int minInliers, int maxIterations, int minSet, float epsilon, float th2){
mRansacProb = probability;
mRansacMinInliers = minInliers;
mRansacMaxIts = maxIterations;
mRansacEpsilon = epsilon;
mRansacMinSet = minSet;
N = mvP2D.size(); // number of correspondences
mvbInliersi.resize(N);
// Adjust Parameters according to number of correspondences
int nMinInliers = N*mRansacEpsilon;
if(nMinInliers<mRansacMinInliers)
nMinInliers=mRansacMinInliers;
if(nMinInliers<minSet)
nMinInliers=minSet;
mRansacMinInliers = nMinInliers;
if(mRansacEpsilon<(float)mRansacMinInliers/N)
mRansacEpsilon=(float)mRansacMinInliers/N;
// Set RANSAC iterations according to probability, epsilon, and max iterations
int nIterations;
if(mRansacMinInliers==N)
nIterations=1;
else
nIterations = ceil(log(1-mRansacProb)/log(1-pow(mRansacEpsilon,3)));
mRansacMaxIts = std::max(1,std::min(nIterations,mRansacMaxIts));
mvMaxError.resize(mvSigma2.size());
for(size_t i=0; i<mvSigma2.size(); i++)
mvMaxError[i] = mvSigma2[i]*th2;
}
void MLPnPsolver::CheckInliers(){
mnInliersi=0;
for(int i=0; i<N; i++)
{
const point_t& p = mvP3Dw[i];
const cv::Point3f P3Dw(p(0),p(1),p(2));
const cv::Point2f& P2D = mvP2D[i];
const float xc = mRi[0][0]*P3Dw.x+mRi[0][1]*P3Dw.y+mRi[0][2]*P3Dw.z+mti[0];
const float yc = mRi[1][0]*P3Dw.x+mRi[1][1]*P3Dw.y+mRi[1][2]*P3Dw.z+mti[1];
const float zc = mRi[2][0]*P3Dw.x+mRi[2][1]*P3Dw.y+mRi[2][2]*P3Dw.z+mti[2];
const cv::Point3f P3Dc(xc,yc,zc);
const cv::Point2f uv = mpCamera->project(P3Dc);
const float distX = P2D.x-uv.x;
const float distY = P2D.y-uv.y;
const float error2 = distX*distX+distY*distY;
if(error2<mvMaxError[i])
{
mvbInliersi[i]=true;
mnInliersi++;
}
else
{
mvbInliersi[i]=false;
}
}
}
bool MLPnPsolver::Refine(){
vector<int> vIndices;
vIndices.reserve(mvbBestInliers.size());
for(size_t i=0; i<mvbBestInliers.size(); i++)
{
if(mvbBestInliers[i])
{
vIndices.push_back(i);
}
}
//Bearing vectors and 3D points used for this ransac iteration
bearingVectors_t bearingVecs;
points_t p3DS;
vector<int> indexes;
for(size_t i=0; i<vIndices.size(); i++)
{
int idx = vIndices[i];
bearingVecs.push_back(mvBearingVecs[idx]);
p3DS.push_back(mvP3Dw[idx]);
indexes.push_back(i);
}
//By the moment, we are using MLPnP without covariance info
cov3_mats_t covs(1);
//Result
transformation_t result;
// Compute camera pose
computePose(bearingVecs,p3DS,covs,indexes,result);
// Check inliers
CheckInliers();
mnRefinedInliers =mnInliersi;
mvbRefinedInliers = mvbInliersi;
if(mnInliersi>mRansacMinInliers)
{
cv::Mat Rcw(3,3,CV_64F,mRi);
cv::Mat tcw(3,1,CV_64F,mti);
Rcw.convertTo(Rcw,CV_32F);
tcw.convertTo(tcw,CV_32F);
mRefinedTcw.setIdentity();
mRefinedTcw.block<3,3>(0,0) = toMatrix3f(Rcw);
mRefinedTcw.block<3,1>(0,3) = toVector3f(tcw);
Eigen::Matrix<double, 3, 3, Eigen::RowMajor> eigRcw(mRi[0]);
Eigen::Vector3d eigtcw(mti);
return true;
}
return false;
}
//MLPnP methods
void MLPnPsolver::computePose(const bearingVectors_t &f, const points_t &p, const cov3_mats_t &covMats,
const std::vector<int> &indices, transformation_t &result) {
size_t numberCorrespondences = indices.size();
assert(numberCorrespondences > 5);
bool planar = false;
// compute the nullspace of all vectors
std::vector<Eigen::MatrixXd> nullspaces(numberCorrespondences);
Eigen::MatrixXd points3(3, numberCorrespondences);
points_t points3v(numberCorrespondences);
points4_t points4v(numberCorrespondences);
for (size_t i = 0; i < numberCorrespondences; i++) {
bearingVector_t f_current = f[indices[i]];
points3.col(i) = p[indices[i]];
// nullspace of right vector
Eigen::JacobiSVD<Eigen::MatrixXd, Eigen::HouseholderQRPreconditioner>
svd_f(f_current.transpose(), Eigen::ComputeFullV);
nullspaces[i] = svd_f.matrixV().block(0, 1, 3, 2);
points3v[i] = p[indices[i]];
}
//////////////////////////////////////
// 1. test if we have a planar scene
//////////////////////////////////////
Eigen::Matrix3d planarTest = points3 * points3.transpose();
Eigen::FullPivHouseholderQR<Eigen::Matrix3d> rankTest(planarTest);
Eigen::Matrix3d eigenRot;
eigenRot.setIdentity();
// if yes -> transform points to new eigen frame
//if (minEigenVal < 1e-3 || minEigenVal == 0.0)
//rankTest.setThreshold(1e-10);
if (rankTest.rank() == 2) {
planar = true;
// self adjoint is faster and more accurate than general eigen solvers
// also has closed form solution for 3x3 self-adjoint matrices
// in addition this solver sorts the eigenvalues in increasing order
Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigen_solver(planarTest);
eigenRot = eigen_solver.eigenvectors().real();
eigenRot.transposeInPlace();
for (size_t i = 0; i < numberCorrespondences; i++)
points3.col(i) = eigenRot * points3.col(i);
}
//////////////////////////////////////
// 2. stochastic model
//////////////////////////////////////
Eigen::SparseMatrix<double> P(2 * numberCorrespondences,
2 * numberCorrespondences);
bool use_cov = false;
P.setIdentity(); // standard
// if we do have covariance information
// -> fill covariance matrix
if (covMats.size() == numberCorrespondences) {
use_cov = true;
int l = 0;
for (size_t i = 0; i < numberCorrespondences; ++i) {
// invert matrix
cov2_mat_t temp = nullspaces[i].transpose() * covMats[i] * nullspaces[i];
temp = temp.inverse().eval();
P.coeffRef(l, l) = temp(0, 0);
P.coeffRef(l, l + 1) = temp(0, 1);
P.coeffRef(l + 1, l) = temp(1, 0);
P.coeffRef(l + 1, l + 1) = temp(1, 1);
l += 2;
}
}
//////////////////////////////////////
// 3. fill the design matrix A
//////////////////////////////////////
const int rowsA = 2 * numberCorrespondences;
int colsA = 12;
Eigen::MatrixXd A;
if (planar) {
colsA = 9;
A = Eigen::MatrixXd(rowsA, 9);
} else
A = Eigen::MatrixXd(rowsA, 12);
A.setZero();
// fill design matrix
if (planar) {
for (size_t i = 0; i < numberCorrespondences; ++i) {
point_t pt3_current = points3.col(i);
// r12
A(2 * i, 0) = nullspaces[i](0, 0) * pt3_current[1];
A(2 * i + 1, 0) = nullspaces[i](0, 1) * pt3_current[1];
// r13
A(2 * i, 1) = nullspaces[i](0, 0) * pt3_current[2];
A(2 * i + 1, 1) = nullspaces[i](0, 1) * pt3_current[2];
// r22
A(2 * i, 2) = nullspaces[i](1, 0) * pt3_current[1];
A(2 * i + 1, 2) = nullspaces[i](1, 1) * pt3_current[1];
// r23
A(2 * i, 3) = nullspaces[i](1, 0) * pt3_current[2];
A(2 * i + 1, 3) = nullspaces[i](1, 1) * pt3_current[2];
// r32
A(2 * i, 4) = nullspaces[i](2, 0) * pt3_current[1];
A(2 * i + 1, 4) = nullspaces[i](2, 1) * pt3_current[1];
// r33
A(2 * i, 5) = nullspaces[i](2, 0) * pt3_current[2];
A(2 * i + 1, 5) = nullspaces[i](2, 1) * pt3_current[2];
// t1
A(2 * i, 6) = nullspaces[i](0, 0);
A(2 * i + 1, 6) = nullspaces[i](0, 1);
// t2
A(2 * i, 7) = nullspaces[i](1, 0);
A(2 * i + 1, 7) = nullspaces[i](1, 1);
// t3
A(2 * i, 8) = nullspaces[i](2, 0);
A(2 * i + 1, 8) = nullspaces[i](2, 1);
}
} else {
for (size_t i = 0; i < numberCorrespondences; ++i) {
point_t pt3_current = points3.col(i);
// r11
A(2 * i, 0) = nullspaces[i](0, 0) * pt3_current[0];
A(2 * i + 1, 0) = nullspaces[i](0, 1) * pt3_current[0];
// r12
A(2 * i, 1) = nullspaces[i](0, 0) * pt3_current[1];
A(2 * i + 1, 1) = nullspaces[i](0, 1) * pt3_current[1];
// r13
A(2 * i, 2) = nullspaces[i](0, 0) * pt3_current[2];
A(2 * i + 1, 2) = nullspaces[i](0, 1) * pt3_current[2];
// r21
A(2 * i, 3) = nullspaces[i](1, 0) * pt3_current[0];
A(2 * i + 1, 3) = nullspaces[i](1, 1) * pt3_current[0];
// r22
A(2 * i, 4) = nullspaces[i](1, 0) * pt3_current[1];
A(2 * i + 1, 4) = nullspaces[i](1, 1) * pt3_current[1];
// r23
A(2 * i, 5) = nullspaces[i](1, 0) * pt3_current[2];
A(2 * i + 1, 5) = nullspaces[i](1, 1) * pt3_current[2];
// r31
A(2 * i, 6) = nullspaces[i](2, 0) * pt3_current[0];
A(2 * i + 1, 6) = nullspaces[i](2, 1) * pt3_current[0];
// r32
A(2 * i, 7) = nullspaces[i](2, 0) * pt3_current[1];
A(2 * i + 1, 7) = nullspaces[i](2, 1) * pt3_current[1];
// r33
A(2 * i, 8) = nullspaces[i](2, 0) * pt3_current[2];
A(2 * i + 1, 8) = nullspaces[i](2, 1) * pt3_current[2];
// t1
A(2 * i, 9) = nullspaces[i](0, 0);
A(2 * i + 1, 9) = nullspaces[i](0, 1);
// t2
A(2 * i, 10) = nullspaces[i](1, 0);
A(2 * i + 1, 10) = nullspaces[i](1, 1);
// t3
A(2 * i, 11) = nullspaces[i](2, 0);
A(2 * i + 1, 11) = nullspaces[i](2, 1);
}
}
//////////////////////////////////////
// 4. solve least squares
//////////////////////////////////////
Eigen::MatrixXd AtPA;
if (use_cov)
AtPA = A.transpose() * P * A; // setting up the full normal equations seems to be unstable
else
AtPA = A.transpose() * A;
Eigen::JacobiSVD<Eigen::MatrixXd> svd_A(AtPA, Eigen::ComputeFullV);
Eigen::MatrixXd result1 = svd_A.matrixV().col(colsA - 1);
////////////////////////////////
// now we treat the results differently,
// depending on the scene (planar or not)
////////////////////////////////
rotation_t Rout;
translation_t tout;
if (planar) // planar case
{
rotation_t tmp;
// until now, we only estimated
// row one and two of the transposed rotation matrix
tmp << 0.0, result1(0, 0), result1(1, 0),
0.0, result1(2, 0), result1(3, 0),
0.0, result1(4, 0), result1(5, 0);
// row 3
tmp.col(0) = tmp.col(1).cross(tmp.col(2));
tmp.transposeInPlace();
double scale = 1.0 / std::sqrt(std::abs(tmp.col(1).norm() * tmp.col(2).norm()));
// find best rotation matrix in frobenius sense
Eigen::JacobiSVD<Eigen::MatrixXd> svd_R_frob(tmp, Eigen::ComputeFullU | Eigen::ComputeFullV);
rotation_t Rout1 = svd_R_frob.matrixU() * svd_R_frob.matrixV().transpose();
// test if we found a good rotation matrix
if (Rout1.determinant() < 0)
Rout1 *= -1.0;
// rotate this matrix back using the eigen frame
Rout1 = eigenRot.transpose() * Rout1;
translation_t t = scale * translation_t(result1(6, 0), result1(7, 0), result1(8, 0));
Rout1.transposeInPlace();
Rout1 *= -1;
if (Rout1.determinant() < 0.0)
Rout1.col(2) *= -1;
// now we have to find the best out of 4 combinations
rotation_t R1, R2;
R1.col(0) = Rout1.col(0);
R1.col(1) = Rout1.col(1);
R1.col(2) = Rout1.col(2);
R2.col(0) = -Rout1.col(0);
R2.col(1) = -Rout1.col(1);
R2.col(2) = Rout1.col(2);
vector<transformation_t, Eigen::aligned_allocator<transformation_t>> Ts(4);
Ts[0].block<3, 3>(0, 0) = R1;
Ts[0].block<3, 1>(0, 3) = t;
Ts[1].block<3, 3>(0, 0) = R1;
Ts[1].block<3, 1>(0, 3) = -t;
Ts[2].block<3, 3>(0, 0) = R2;
Ts[2].block<3, 1>(0, 3) = t;
Ts[3].block<3, 3>(0, 0) = R2;
Ts[3].block<3, 1>(0, 3) = -t;
vector<double> normVal(4);
for (int i = 0; i < 4; ++i) {
point_t reproPt;
double norms = 0.0;
for (int p = 0; p < 6; ++p) {
reproPt = Ts[i].block<3, 3>(0, 0) * points3v[p] + Ts[i].block<3, 1>(0, 3);
reproPt = reproPt / reproPt.norm();
norms += (1.0 - reproPt.transpose() * f[indices[p]]);
}
normVal[i] = norms;
}
std::vector<double>::iterator
findMinRepro = std::min_element(std::begin(normVal), std::end(normVal));
int idx = std::distance(std::begin(normVal), findMinRepro);
Rout = Ts[idx].block<3, 3>(0, 0);
tout = Ts[idx].block<3, 1>(0, 3);
} else // non-planar
{
rotation_t tmp;
tmp << result1(0, 0), result1(3, 0), result1(6, 0),
result1(1, 0), result1(4, 0), result1(7, 0),
result1(2, 0), result1(5, 0), result1(8, 0);
// get the scale
double scale = 1.0 /
std::pow(std::abs(tmp.col(0).norm() * tmp.col(1).norm() * tmp.col(2).norm()), 1.0 / 3.0);
//double scale = 1.0 / std::sqrt(std::abs(tmp.col(0).norm() * tmp.col(1).norm()));
// find best rotation matrix in frobenius sense
Eigen::JacobiSVD<Eigen::MatrixXd> svd_R_frob(tmp, Eigen::ComputeFullU | Eigen::ComputeFullV);
Rout = svd_R_frob.matrixU() * svd_R_frob.matrixV().transpose();
// test if we found a good rotation matrix
if (Rout.determinant() < 0)
Rout *= -1.0;
// scale translation
tout = Rout * (scale * translation_t(result1(9, 0), result1(10, 0), result1(11, 0)));
// find correct direction in terms of reprojection error, just take the first 6 correspondences
vector<double> error(2);
vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> Ts(2);
for (int s = 0; s < 2; ++s) {
error[s] = 0.0;
Ts[s] = Eigen::Matrix4d::Identity();
Ts[s].block<3, 3>(0, 0) = Rout;
if (s == 0)
Ts[s].block<3, 1>(0, 3) = tout;
else
Ts[s].block<3, 1>(0, 3) = -tout;
Ts[s] = Ts[s].inverse().eval();
for (int p = 0; p < 6; ++p) {
bearingVector_t v = Ts[s].block<3, 3>(0, 0) * points3v[p] + Ts[s].block<3, 1>(0, 3);
v = v / v.norm();
error[s] += (1.0 - v.transpose() * f[indices[p]]);
}
}
if (error[0] < error[1])
tout = Ts[0].block<3, 1>(0, 3);
else
tout = Ts[1].block<3, 1>(0, 3);
Rout = Ts[0].block<3, 3>(0, 0);
}
//////////////////////////////////////
// 5. gauss newton
//////////////////////////////////////
rodrigues_t omega = rot2rodrigues(Rout);
Eigen::VectorXd minx(6);
minx[0] = omega[0];
minx[1] = omega[1];
minx[2] = omega[2];
minx[3] = tout[0];
minx[4] = tout[1];
minx[5] = tout[2];
mlpnp_gn(minx, points3v, nullspaces, P, use_cov);
Rout = rodrigues2rot(rodrigues_t(minx[0], minx[1], minx[2]));
tout = translation_t(minx[3], minx[4], minx[5]);
// result inverse as opengv uses this convention
result.block<3, 3>(0, 0) = Rout;
result.block<3, 1>(0, 3) = tout;
}
Eigen::Matrix3d MLPnPsolver::rodrigues2rot(const Eigen::Vector3d &omega) {
rotation_t R = Eigen::Matrix3d::Identity();
Eigen::Matrix3d skewW;
skewW << 0.0, -omega(2), omega(1),
omega(2), 0.0, -omega(0),
-omega(1), omega(0), 0.0;
double omega_norm = omega.norm();
if (omega_norm > std::numeric_limits<double>::epsilon())
R = R + sin(omega_norm) / omega_norm * skewW
+ (1 - cos(omega_norm)) / (omega_norm * omega_norm) * (skewW * skewW);
return R;
}
Eigen::Vector3d MLPnPsolver::rot2rodrigues(const Eigen::Matrix3d &R) {
rodrigues_t omega;
omega << 0.0, 0.0, 0.0;
double trace = R.trace() - 1.0;
double wnorm = acos(trace / 2.0);
if (wnorm > std::numeric_limits<double>::epsilon())
{
omega[0] = (R(2, 1) - R(1, 2));
omega[1] = (R(0, 2) - R(2, 0));
omega[2] = (R(1, 0) - R(0, 1));
double sc = wnorm / (2.0*sin(wnorm));
omega *= sc;
}
return omega;
}
void MLPnPsolver::mlpnp_gn(Eigen::VectorXd &x, const points_t &pts, const std::vector<Eigen::MatrixXd> &nullspaces,
const Eigen::SparseMatrix<double> Kll, bool use_cov) {
const int numObservations = pts.size();
const int numUnknowns = 6;
// check redundancy
assert((2 * numObservations - numUnknowns) > 0);
// =============
// set all matrices up
// =============
Eigen::VectorXd r(2 * numObservations);
Eigen::VectorXd rd(2 * numObservations);
Eigen::MatrixXd Jac(2 * numObservations, numUnknowns);
Eigen::VectorXd g(numUnknowns, 1);
Eigen::VectorXd dx(numUnknowns, 1); // result vector
Jac.setZero();
r.setZero();
dx.setZero();
g.setZero();
int it_cnt = 0;
bool stop = false;
const int maxIt = 5;
double epsP = 1e-5;
Eigen::MatrixXd JacTSKll;
Eigen::MatrixXd A;
// solve simple gradient descent
while (it_cnt < maxIt && !stop) {
mlpnp_residuals_and_jacs(x, pts,
nullspaces,
r, Jac, true);
if (use_cov)
JacTSKll = Jac.transpose() * Kll;
else
JacTSKll = Jac.transpose();
A = JacTSKll * Jac;
// get system matrix
g = JacTSKll * r;
// solve
Eigen::LDLT<Eigen::MatrixXd> chol(A);
dx = chol.solve(g);
//dx = A.jacobiSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(g);
// this is to prevent the solution from falling into a wrong minimum
// if the linear estimate is spurious
if (dx.array().abs().maxCoeff() > 5.0 || dx.array().abs().minCoeff() > 1.0)
break;
// observation update
Eigen::MatrixXd dl = Jac * dx;
if (dl.array().abs().maxCoeff() < epsP) {
stop = true;
x = x - dx;
break;
} else
x = x - dx;
++it_cnt;
}//while
// result
}
void MLPnPsolver::mlpnp_residuals_and_jacs(const Eigen::VectorXd &x, const points_t &pts,
const std::vector<Eigen::MatrixXd> &nullspaces, Eigen::VectorXd &r,
Eigen::MatrixXd &fjac, bool getJacs) {
rodrigues_t w(x[0], x[1], x[2]);
translation_t T(x[3], x[4], x[5]);
//rotation_t R = math::cayley2rot(c);
rotation_t R = rodrigues2rot(w);
int ii = 0;
Eigen::MatrixXd jacs(2, 6);
for (int i = 0; i < pts.size(); ++i)
{
Eigen::Vector3d ptCam = R*pts[i] + T;
ptCam /= ptCam.norm();
r[ii] = nullspaces[i].col(0).transpose()*ptCam;
r[ii + 1] = nullspaces[i].col(1).transpose()*ptCam;
if (getJacs)
{
// jacs
mlpnpJacs(pts[i],
nullspaces[i].col(0), nullspaces[i].col(1),
w, T,
jacs);
// r
fjac(ii, 0) = jacs(0, 0);
fjac(ii, 1) = jacs(0, 1);
fjac(ii, 2) = jacs(0, 2);
fjac(ii, 3) = jacs(0, 3);
fjac(ii, 4) = jacs(0, 4);
fjac(ii, 5) = jacs(0, 5);
// s
fjac(ii + 1, 0) = jacs(1, 0);
fjac(ii + 1, 1) = jacs(1, 1);
fjac(ii + 1, 2) = jacs(1, 2);
fjac(ii + 1, 3) = jacs(1, 3);
fjac(ii + 1, 4) = jacs(1, 4);
fjac(ii + 1, 5) = jacs(1, 5);
}
ii += 2;
}
}
void MLPnPsolver::mlpnpJacs(const point_t& pt, const Eigen::Vector3d& nullspace_r,
const Eigen::Vector3d& nullspace_s, const rodrigues_t& w,
const translation_t& t, Eigen::MatrixXd& jacs){
double r1 = nullspace_r[0];
double r2 = nullspace_r[1];
double r3 = nullspace_r[2];
double s1 = nullspace_s[0];
double s2 = nullspace_s[1];
double s3 = nullspace_s[2];
double X1 = pt[0];
double Y1 = pt[1];
double Z1 = pt[2];
double w1 = w[0];
double w2 = w[1];
double w3 = w[2];
double t1 = t[0];
double t2 = t[1];
double t3 = t[2];
double t5 = w1*w1;
double t6 = w2*w2;
double t7 = w3*w3;
double t8 = t5+t6+t7;
double t9 = sqrt(t8);
double t10 = sin(t9);
double t11 = 1.0/sqrt(t8);
double t12 = cos(t9);
double t13 = t12-1.0;
double t14 = 1.0/t8;
double t16 = t10*t11*w3;
double t17 = t13*t14*w1*w2;
double t19 = t10*t11*w2;
double t20 = t13*t14*w1*w3;
double t24 = t6+t7;
double t27 = t16+t17;
double t28 = Y1*t27;
double t29 = t19-t20;
double t30 = Z1*t29;
double t31 = t13*t14*t24;
double t32 = t31+1.0;
double t33 = X1*t32;
double t15 = t1-t28+t30+t33;
double t21 = t10*t11*w1;
double t22 = t13*t14*w2*w3;
double t45 = t5+t7;
double t53 = t16-t17;
double t54 = X1*t53;
double t55 = t21+t22;
double t56 = Z1*t55;
double t57 = t13*t14*t45;
double t58 = t57+1.0;
double t59 = Y1*t58;
double t18 = t2+t54-t56+t59;
double t34 = t5+t6;
double t38 = t19+t20;
double t39 = X1*t38;
double t40 = t21-t22;
double t41 = Y1*t40;
double t42 = t13*t14*t34;
double t43 = t42+1.0;
double t44 = Z1*t43;
double t23 = t3-t39+t41+t44;
double t25 = 1.0/pow(t8,3.0/2.0);
double t26 = 1.0/(t8*t8);
double t35 = t12*t14*w1*w2;
double t36 = t5*t10*t25*w3;
double t37 = t5*t13*t26*w3*2.0;
double t46 = t10*t25*w1*w3;
double t47 = t5*t10*t25*w2;
double t48 = t5*t13*t26*w2*2.0;
double t49 = t10*t11;
double t50 = t5*t12*t14;
double t51 = t13*t26*w1*w2*w3*2.0;
double t52 = t10*t25*w1*w2*w3;
double t60 = t15*t15;
double t61 = t18*t18;
double t62 = t23*t23;
double t63 = t60+t61+t62;
double t64 = t5*t10*t25;
double t65 = 1.0/sqrt(t63);
double t66 = Y1*r2*t6;
double t67 = Z1*r3*t7;
double t68 = r1*t1*t5;
double t69 = r1*t1*t6;
double t70 = r1*t1*t7;
double t71 = r2*t2*t5;
double t72 = r2*t2*t6;
double t73 = r2*t2*t7;
double t74 = r3*t3*t5;
double t75 = r3*t3*t6;
double t76 = r3*t3*t7;
double t77 = X1*r1*t5;
double t78 = X1*r2*w1*w2;
double t79 = X1*r3*w1*w3;
double t80 = Y1*r1*w1*w2;
double t81 = Y1*r3*w2*w3;
double t82 = Z1*r1*w1*w3;
double t83 = Z1*r2*w2*w3;
double t84 = X1*r1*t6*t12;
double t85 = X1*r1*t7*t12;
double t86 = Y1*r2*t5*t12;
double t87 = Y1*r2*t7*t12;
double t88 = Z1*r3*t5*t12;
double t89 = Z1*r3*t6*t12;
double t90 = X1*r2*t9*t10*w3;
double t91 = Y1*r3*t9*t10*w1;
double t92 = Z1*r1*t9*t10*w2;
double t102 = X1*r3*t9*t10*w2;
double t103 = Y1*r1*t9*t10*w3;
double t104 = Z1*r2*t9*t10*w1;
double t105 = X1*r2*t12*w1*w2;
double t106 = X1*r3*t12*w1*w3;
double t107 = Y1*r1*t12*w1*w2;
double t108 = Y1*r3*t12*w2*w3;
double t109 = Z1*r1*t12*w1*w3;
double t110 = Z1*r2*t12*w2*w3;
double t93 = t66+t67+t68+t69+t70+t71+t72+t73+t74+t75+t76+t77+t78+t79+t80+t81+t82+t83+t84+t85+t86+t87+t88+t89+t90+t91+t92-t102-t103-t104-t105-t106-t107-t108-t109-t110;
double t94 = t10*t25*w1*w2;
double t95 = t6*t10*t25*w3;
double t96 = t6*t13*t26*w3*2.0;
double t97 = t12*t14*w2*w3;
double t98 = t6*t10*t25*w1;
double t99 = t6*t13*t26*w1*2.0;
double t100 = t6*t10*t25;
double t101 = 1.0/pow(t63,3.0/2.0);
double t111 = t6*t12*t14;
double t112 = t10*t25*w2*w3;
double t113 = t12*t14*w1*w3;
double t114 = t7*t10*t25*w2;
double t115 = t7*t13*t26*w2*2.0;
double t116 = t7*t10*t25*w1;
double t117 = t7*t13*t26*w1*2.0;
double t118 = t7*t12*t14;
double t119 = t13*t24*t26*w1*2.0;
double t120 = t10*t24*t25*w1;
double t121 = t119+t120;
double t122 = t13*t26*t34*w1*2.0;
double t123 = t10*t25*t34*w1;
double t131 = t13*t14*w1*2.0;
double t124 = t122+t123-t131;
double t139 = t13*t14*w3;
double t125 = -t35+t36+t37+t94-t139;
double t126 = X1*t125;
double t127 = t49+t50+t51+t52-t64;
double t128 = Y1*t127;
double t129 = t126+t128-Z1*t124;
double t130 = t23*t129*2.0;