testEssentialMatrixFactor.cpp
Go to the documentation of this file.
1 /*
2  * @file testEssentialMatrixFactor.cpp
3  * @brief Test EssentialMatrixFactor class
4  * @author Frank Dellaert
5  * @date December 17, 2013
6  */
7 
9 #include <gtsam/base/Testable.h>
10 #include <gtsam/geometry/Cal3_S2.h>
17 #include <gtsam/sfm/SfmData.h>
19 #include <gtsam/slam/dataset.h>
20 
21 using namespace std::placeholders;
22 using namespace std;
23 using namespace gtsam;
24 
25 // Noise model for first type of factor is evaluating algebraic error
27  noiseModel::Isotropic::Sigma(1, 0.01);
28 // Noise model for second type of factor is evaluating pixel coordinates
29 noiseModel::Unit::shared_ptr model2 = noiseModel::Unit::Create(2);
30 
31 // The rotation between body and camera is:
32 gtsam::Point3 bX(1, 0, 0), bY(0, 1, 0), bZ(0, 0, 1);
34 
35 namespace example1 {
36 
37 const string filename = findExampleDataFile("18pointExample1.txt");
38 SfmData data = SfmData::FromBalFile(filename);
39 Rot3 c1Rc2 = data.cameras[1].pose().rotation();
40 Point3 c1Tc2 = data.cameras[1].pose().translation();
41 // TODO: maybe default value not good; assert with 0th
47 double baseline = 0.1; // actual baseline of the camera
48 
49 Point2 pA(size_t i) { return data.tracks[i].measurements[0].second; }
50 Point2 pB(size_t i) { return data.tracks[i].measurements[1].second; }
51 Vector vA(size_t i) { return EssentialMatrix::Homogeneous(pA(i)); }
52 Vector vB(size_t i) { return EssentialMatrix::Homogeneous(pB(i)); }
53 
54 //*************************************************************************
56  // Check E matrix
57  Matrix expected(3, 3);
58  expected << 0, 0, 0, 0, 0, -0.1, 0.1, 0, 0;
59  Matrix aEb_matrix =
60  skewSymmetric(c1Tc2.x(), c1Tc2.y(), c1Tc2.z()) * c1Rc2.matrix();
61  EXPECT(assert_equal(expected, aEb_matrix, 1e-8));
62 
63  // Check some projections
64  EXPECT(assert_equal(Point2(0, 0), pA(0), 1e-8));
65  EXPECT(assert_equal(Point2(0, 0.1), pB(0), 1e-8));
66  EXPECT(assert_equal(Point2(0, -1), pA(4), 1e-8));
67  EXPECT(assert_equal(Point2(-1, 0.2), pB(4), 1e-8));
68 
69  // Check homogeneous version
70  EXPECT(assert_equal(Vector3(-1, 0.2, 1), vB(4), 1e-8));
71 
72  // Check epipolar constraint
73  for (size_t i = 0; i < 5; i++)
74  EXPECT_DOUBLES_EQUAL(0, vA(i).transpose() * aEb_matrix * vB(i), 1e-8);
75 
76  // Check epipolar constraint
77  for (size_t i = 0; i < 5; i++)
78  EXPECT_DOUBLES_EQUAL(0, trueE.error(vA(i), vB(i)), 1e-7);
79 }
80 
81 //*************************************************************************
83  Key key(1);
84  for (size_t i = 0; i < 5; i++) {
86 
87  // Check evaluation
88  Vector expected(1);
89  expected << 0;
90  Vector actual = factor.evaluateError(trueE);
91  EXPECT(assert_equal(expected, actual, 1e-7));
92 
93  Values val;
94  val.insert(key, trueE);
96  }
97 }
98 
99 //*************************************************************************
101  Key key(1);
102  for (size_t i = 0; i < 5; i++) {
103  std::function<double(const EssentialMatrix &, OptionalJacobian<1, 5>)> f =
104  std::bind(&EssentialMatrix::error, std::placeholders::_1, vA(i), vB(i),
105  std::placeholders::_2);
106  Expression<EssentialMatrix> E_(key); // leaf expression
107  Expression<double> expr(f, E_); // unary expression
108 
109  // Test the derivatives using Paul's magic
110  Values values;
113 
114  // Create the factor
116 
117  // Check evaluation
118  Vector expected(1);
119  expected << 0;
120  vector<Matrix> actualH(1);
121  Vector actual = factor.unwhitenedError(values, actualH);
122  EXPECT(assert_equal(expected, actual, 1e-7));
123  }
124 }
125 
126 //*************************************************************************
127 TEST(EssentialMatrixFactor, ExpressionFactorRotationOnly) {
128  Key key(1);
129  for (size_t i = 0; i < 5; i++) {
130  std::function<double(const EssentialMatrix &, OptionalJacobian<1, 5>)> f =
131  std::bind(&EssentialMatrix::error, std::placeholders::_1, vA(i), vB(i),
132  std::placeholders::_2);
133  std::function<EssentialMatrix(const Rot3 &, const Unit3 &,
136  g;
137  Expression<Rot3> R_(key);
139  Expression<EssentialMatrix> E_(&EssentialMatrix::FromRotationAndDirection,
140  R_, d_);
141  Expression<double> expr(f, E_);
142 
143  // Test the derivatives using Paul's magic
144  Values values;
147 
148  // Create the factor
150 
151  // Check evaluation
152  Vector expected(1);
153  expected << 0;
154  vector<Matrix> actualH(1);
155  Vector actual = factor.unwhitenedError(values, actualH);
156  EXPECT(assert_equal(expected, actual, 1e-7));
157  }
158 }
159 
160 //*************************************************************************
161 TEST(EssentialMatrixFactor, minimization) {
162  // Here we want to optimize directly on essential matrix constraints
163  // Yi Ma's algorithm (Ma01ijcv) is a bit cumbersome to implement,
164  // but GTSAM does the equivalent anyway, provided we give the right
165  // factors. In this case, the factors are the constraints.
166 
167  // We start with a factor graph and add constraints to it
168  // Noise sigma is 1cm, assuming metric measurements
170  for (size_t i = 0; i < 5; i++)
172 
173  // Check error at ground truth
174  Values truth;
175  truth.insert(1, trueE);
176  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
177 
178  // Check error at initial estimate
179  Values initial;
180  EssentialMatrix initialE =
181  trueE.retract((Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
182  initial.insert(1, initialE);
183 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
184  EXPECT_DOUBLES_EQUAL(643.26, graph.error(initial), 1e-2);
185 #else
186  EXPECT_DOUBLES_EQUAL(639.84, graph.error(initial), 1e-2);
187 #endif
188 
189  // Optimize
192  Values result = optimizer.optimize();
193 
194  // Check result
196  EXPECT(assert_equal(trueE, actual, 1e-1));
197 
198  // Check error at result
200 
201  // Check errors individually
202  for (size_t i = 0; i < 5; i++)
203  EXPECT_DOUBLES_EQUAL(0, actual.error(vA(i), vB(i)), 1e-6);
204 }
205 
206 //*************************************************************************
208  for (size_t i = 0; i < 5; i++) {
210 
211  // Check evaluation
212  Point3 P1 = data.tracks[i].p, P2 = data.cameras[1].pose().transformTo(P1);
213  const Point2 pi = PinholeBase::Project(P2);
214  Point2 expected(pi - pB(i));
215 
216  Matrix actualH1, actualH2;
217  double d(baseline / P1.z());
218  Vector actual = factor.evaluateError(trueE, d, actualH1, actualH2);
219  EXPECT(assert_equal(expected, actual, 1e-7));
220 
221  Values val;
222  val.insert(100, trueE);
223  val.insert(i, d);
225  }
226 }
227 
228 //*************************************************************************
229 TEST(EssentialMatrixFactor2, minimization) {
230  // Here we want to optimize for E and inverse depths at the same time
231 
232  // We start with a factor graph and add constraints to it
233  // Noise sigma is 1cm, assuming metric measurements
235  for (size_t i = 0; i < 5; i++)
237 
238  // Check error at ground truth
239  Values truth;
240  truth.insert(100, trueE);
241  for (size_t i = 0; i < 5; i++) {
242  Point3 P1 = data.tracks[i].p;
243  truth.insert(i, double(baseline / P1.z()));
244  }
245  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
246 
247  // Optimize
249  // parameters.setVerbosity("ERROR");
250  LevenbergMarquardtOptimizer optimizer(graph, truth, parameters);
251  Values result = optimizer.optimize();
252 
253  // Check result
254  EssentialMatrix actual = result.at<EssentialMatrix>(100);
255  EXPECT(assert_equal(trueE, actual, 1e-1));
256  for (size_t i = 0; i < 5; i++)
257  EXPECT_DOUBLES_EQUAL(truth.at<double>(i), result.at<double>(i), 1e-1);
258 
259  // Check error at result
261 }
262 
263 //*************************************************************************
264 // Below we want to optimize for an essential matrix specified in a
265 // body coordinate frame B which is rotated with respect to the camera
266 // frame C, via the rotation bRc.
267 
268 // The "true E" in the body frame is then
270 
271 //*************************************************************************
273  for (size_t i = 0; i < 5; i++) {
275 
276  // Check evaluation
277  Point3 P1 = data.tracks[i].p;
278  const Point2 pi = camera2.project(P1);
279  Point2 expected(pi - pB(i));
280 
281  Matrix actualH1, actualH2;
282  double d(baseline / P1.z());
283  Vector actual = factor.evaluateError(bodyE, d, actualH1, actualH2);
284  EXPECT(assert_equal(expected, actual, 1e-7));
285 
286  Values val;
287  val.insert(100, bodyE);
288  val.insert(i, d);
290  }
291 }
292 
293 //*************************************************************************
294 TEST(EssentialMatrixFactor3, minimization) {
295  // As before, we start with a factor graph and add constraints to it
297  for (size_t i = 0; i < 5; i++)
298  // but now we specify the rotation bRc
300  model2);
301 
302  // Check error at ground truth
303  Values truth;
304  truth.insert(100, bodyE);
305  for (size_t i = 0; i < 5; i++) {
306  Point3 P1 = data.tracks[i].p;
307  truth.insert(i, double(baseline / P1.z()));
308  }
309  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
310 
311  // Optimize
313  // parameters.setVerbosity("ERROR");
314  LevenbergMarquardtOptimizer optimizer(graph, truth, parameters);
315  Values result = optimizer.optimize();
316 
317  // Check result
318  EssentialMatrix actual = result.at<EssentialMatrix>(100);
319  EXPECT(assert_equal(bodyE, actual, 1e-1));
320  for (size_t i = 0; i < 5; i++)
321  EXPECT_DOUBLES_EQUAL(truth.at<double>(i), result.at<double>(i), 1e-1);
322 
323  // Check error at result
325 }
326 
327 //*************************************************************************
329  Key keyE(1);
330  Key keyK(2);
331  for (size_t i = 0; i < 5; i++) {
333 
334  // Check evaluation
336  expected << 0;
337  Vector actual = factor.evaluateError(trueE, trueK);
338  EXPECT(assert_equal(expected, actual, 1e-7));
339 
340  Values truth;
341  truth.insert(keyE, trueE);
342  truth.insert(keyK, trueK);
343  EXPECT_CORRECT_FACTOR_JACOBIANS(factor, truth, 1e-6, 1e-7);
344  }
345 }
346 
347 //*************************************************************************
348 TEST(EssentialMatrixFactor4, evaluateErrorJacobiansCal3S2) {
349  Key keyE(1);
350  Key keyK(2);
351  // initialize essential matrix
352  Rot3 r = Rot3::Expmap(Vector3(M_PI / 6, M_PI / 3, M_PI / 9));
353  Unit3 t(Point3(2, -1, 0.5));
354  EssentialMatrix E = EssentialMatrix::FromRotationAndDirection(r, t);
355  Cal3_S2 K(200, 1, 1, 10, 10);
356  Values val;
357  val.insert(keyE, E);
358  val.insert(keyK, K);
359 
360  Point2 pA(10.0, 20.0);
361  Point2 pB(12.0, 15.0);
362 
364  EXPECT_CORRECT_FACTOR_JACOBIANS(f, val, 1e-5, 1e-6);
365 }
366 
367 //*************************************************************************
368 TEST(EssentialMatrixFactor4, evaluateErrorJacobiansCal3Bundler) {
369  Key keyE(1);
370  Key keyK(2);
371  // initialize essential matrix
372  Rot3 r = Rot3::Expmap(Vector3(0, 0, M_PI_2));
373  Unit3 t(Point3(0.1, 0, 0));
374  EssentialMatrix E = EssentialMatrix::FromRotationAndDirection(r, t);
375  Cal3Bundler K;
376  Values val;
377  val.insert(keyE, E);
378  val.insert(keyK, K);
379 
380  Point2 pA(-0.1, 0.5);
381  Point2 pB(-0.5, -0.2);
382 
384  EXPECT_CORRECT_FACTOR_JACOBIANS(f, val, 1e-5, 1e-5);
385 }
386 
387 //*************************************************************************
388 TEST(EssentialMatrixFactor4, minimizationWithStrongCal3S2Prior) {
390  for (size_t i = 0; i < 5; i++)
392  model1);
393 
394  // Check error at ground truth
395  Values truth;
396  truth.insert(1, trueE);
397  truth.insert(2, trueK);
398  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
399 
400  // Initialization
401  Values initial;
402  EssentialMatrix initialE =
403  trueE.retract((Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
404  initial.insert(1, initialE);
405  initial.insert(2, trueK);
406 
407  // add prior factor for calibration
408  Vector5 priorNoiseModelSigma;
409  priorNoiseModelSigma << 10, 10, 10, 10, 10;
411  2, trueK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma));
412 
414  Values result = optimizer.optimize();
415 
416  // Check result
418  Cal3_S2 actualK = result.at<Cal3_S2>(2);
419  EXPECT(assert_equal(trueE, actualE, 1e-1));
420  EXPECT(assert_equal(trueK, actualK, 1e-2));
421 
422  // Check error at result
424 
425  // Check errors individually
426  for (size_t i = 0; i < 5; i++)
428  0,
429  actualE.error(EssentialMatrix::Homogeneous(actualK.calibrate(pA(i))),
430  EssentialMatrix::Homogeneous(actualK.calibrate(pB(i)))),
431  1e-6);
432 }
433 
434 //*************************************************************************
435 TEST(EssentialMatrixFactor4, minimizationWithWeakCal3S2Prior) {
436  // We need 7 points here as the prior on the focal length parameters is weak
437  // and the initialization is noisy. So in total we are trying to optimize 7
438  // DOF, with a strong prior on the remaining 3 DOF.
440  for (size_t i = 0; i < 7; i++)
442  model1);
443 
444  // Check error at ground truth
445  Values truth;
446  truth.insert(1, trueE);
447  truth.insert(2, trueK);
448  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
449 
450  // Initialization
451  Values initial;
452  EssentialMatrix initialE =
453  trueE.retract((Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
454  Cal3_S2 initialK =
455  trueK.retract((Vector(5) << 0.1, -0.1, 0.0, -0.0, 0.0).finished());
456  initial.insert(1, initialE);
457  initial.insert(2, initialK);
458 
459  // add prior factor for calibration
460  Vector5 priorNoiseModelSigma;
461  priorNoiseModelSigma << 20, 20, 1, 1, 1;
463  2, initialK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma));
464 
466  Values result = optimizer.optimize();
467 
468  // Check result
470  Cal3_S2 actualK = result.at<Cal3_S2>(2);
471  EXPECT(assert_equal(trueE, actualE, 1e-1));
472  EXPECT(assert_equal(trueK, actualK, 1e-2));
473 
474  // Check error at result
476 
477  // Check errors individually
478  for (size_t i = 0; i < 7; i++)
480  0,
481  actualE.error(EssentialMatrix::Homogeneous(actualK.calibrate(pA(i))),
482  EssentialMatrix::Homogeneous(actualK.calibrate(pB(i)))),
483  1e-5);
484 }
485 
486 //*************************************************************************
487 TEST(EssentialMatrixFactor4, minimizationWithStrongCal3BundlerPrior) {
489  for (size_t i = 0; i < 5; i++)
491  pB(i), model1);
492  Cal3Bundler trueK(1, 0, 0, 0, 0, /*tolerance=*/5e-3);
493  // Check error at ground truth
494  Values truth;
495  truth.insert(1, trueE);
496  truth.insert(2, trueK);
497  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
498 
499  // Check error at initial estimate
500  Values initial;
501  EssentialMatrix initialE =
502  trueE.retract((Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
503  Cal3Bundler initialK = trueK;
504  initial.insert(1, initialE);
505  initial.insert(2, initialK);
506 
507  // add prior factor for calibration
508  Vector3 priorNoiseModelSigma;
509  priorNoiseModelSigma << 0.1, 0.1, 0.1;
511  2, trueK, noiseModel::Diagonal::Sigmas(priorNoiseModelSigma));
512 
514  Values result = optimizer.optimize();
515 
516  // Check result
518  Cal3Bundler actualK = result.at<Cal3Bundler>(2);
519  EXPECT(assert_equal(trueE, actualE, 1e-1));
520  EXPECT(assert_equal(trueK, actualK, 1e-2));
521 
522  // Check error at result
524 
525  // Check errors individually
526  for (size_t i = 0; i < 5; i++)
528  0,
529  actualE.error(EssentialMatrix::Homogeneous(actualK.calibrate(pA(i))),
530  EssentialMatrix::Homogeneous(actualK.calibrate(pB(i)))),
531  1e-6);
532 }
533 
534 //*************************************************************************
536  Key keyE(1), keyKa(2), keyKb(3);
537  for (size_t i = 0; i < 5; i++) {
538  EssentialMatrixFactor5<Cal3_S2> factor(keyE, keyKa, keyKb, pA(i), pB(i),
539  model1);
540 
541  // Check evaluation
543  expected << 0;
544  Vector actual = factor.evaluateError(trueE, trueK, trueK);
545  EXPECT(assert_equal(expected, actual, 1e-7));
546 
547  Values truth;
548  truth.insert(keyE, trueE);
549  truth.insert(keyKa, trueK);
550  truth.insert(keyKb, trueK);
551  EXPECT_CORRECT_FACTOR_JACOBIANS(factor, truth, 1e-6, 1e-7);
552  }
553 }
554 
555 //*************************************************************************
556 // Test that if we use the same keys for Ka and Kb the sum of the two K
557 // Jacobians equals that of the single K Jacobian for EssentialMatrix4
559  Key keyE(1), keyK(2);
560  for (size_t i = 0; i < 5; i++) {
561  EssentialMatrixFactor4<Cal3_S2> factor4(keyE, keyK, pA(i), pB(i), model1);
562  EssentialMatrixFactor5<Cal3_S2> factor5(keyE, keyK, keyK, pA(i), pB(i),
563  model1);
564 
565  Values truth;
566  truth.insert(keyE, trueE);
567  truth.insert(keyK, trueK);
568 
569  // Check Jacobians
570  Matrix H0, H1, H2;
571  factor4.evaluateError(trueE, trueK, nullptr, &H0);
572  factor5.evaluateError(trueE, trueK, trueK, nullptr, &H1, &H2);
573  EXPECT(assert_equal(H0, H1 + H2, 1e-9));
574  }
575 }
576 } // namespace example1
577 
578 //*************************************************************************
579 
580 namespace example2 {
581 
582 const string filename = findExampleDataFile("5pointExample2.txt");
583 SfmData data = SfmData::FromBalFile(filename);
584 Rot3 aRb = data.cameras[1].pose().rotation();
585 Point3 aTb = data.cameras[1].pose().translation();
587 
588 double baseline = 10; // actual baseline of the camera
589 
590 Point2 pA(size_t i) { return data.tracks[i].measurements[0].second; }
591 Point2 pB(size_t i) { return data.tracks[i].measurements[1].second; }
592 
594 std::shared_ptr<Cal3Bundler> K = std::make_shared<Cal3Bundler>(trueK);
596 
597 Vector vA(size_t i) {
598  Point2 xy = trueK.calibrate(pA(i));
599  return EssentialMatrix::Homogeneous(xy);
600 }
601 Vector vB(size_t i) {
602  Point2 xy = trueK.calibrate(pB(i));
603  return EssentialMatrix::Homogeneous(xy);
604 }
605 
606 //*************************************************************************
607 TEST(EssentialMatrixFactor, extraMinimization) {
608  // Additional test with camera moving in positive X direction
609 
611  for (size_t i = 0; i < 5; i++)
613 
614  // Check error at ground truth
615  Values truth;
616  truth.insert(1, trueE);
617  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
618 
619  // Check error at initial estimate
620  Values initial;
621  EssentialMatrix initialE =
622  trueE.retract((Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
623  initial.insert(1, initialE);
624 
625 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
626  EXPECT_DOUBLES_EQUAL(643.26, graph.error(initial), 1e-2);
627 #else
628  EXPECT_DOUBLES_EQUAL(639.84, graph.error(initial), 1e-2);
629 #endif
630 
631  // Optimize
634  Values result = optimizer.optimize();
635 
636  // Check result
638  EXPECT(assert_equal(trueE, actual, 1e-1));
639 
640  // Check error at result
642 
643  // Check errors individually
644  for (size_t i = 0; i < 5; i++)
645  EXPECT_DOUBLES_EQUAL(0, actual.error(vA(i), vB(i)), 1e-6);
646 }
647 
648 //*************************************************************************
650  for (size_t i = 0; i < 5; i++) {
651  EssentialMatrixFactor2 factor(100, i, pA(i), pB(i), model2, K);
652 
653  // Check evaluation
654  Point3 P1 = data.tracks[i].p;
655  const Point2 pi = camera2.project(P1);
656  Point2 expected(pi - pB(i));
657 
658  double d(baseline / P1.z());
659  Vector actual = factor.evaluateError(trueE, d);
660  EXPECT(assert_equal(expected, actual, 1e-7));
661 
662  Values val;
663  val.insert(100, trueE);
664  val.insert(i, d);
666  }
667 }
668 
669 //*************************************************************************
670 TEST(EssentialMatrixFactor2, extraMinimization) {
671  // Additional test with camera moving in positive X direction
672 
673  // We start with a factor graph and add constraints to it
674  // Noise sigma is 1, assuming pixel measurements
676  for (size_t i = 0; i < data.numberTracks(); i++)
678  K);
679 
680  // Check error at ground truth
681  Values truth;
682  truth.insert(100, trueE);
683  for (size_t i = 0; i < data.numberTracks(); i++) {
684  Point3 P1 = data.tracks[i].p;
685  truth.insert(i, double(baseline / P1.z()));
686  }
687  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
688 
689  // Optimize
691  // parameters.setVerbosity("ERROR");
692  LevenbergMarquardtOptimizer optimizer(graph, truth, parameters);
693  Values result = optimizer.optimize();
694 
695  // Check result
696  EssentialMatrix actual = result.at<EssentialMatrix>(100);
697  EXPECT(assert_equal(trueE, actual, 1e-1));
698  for (size_t i = 0; i < data.numberTracks(); i++)
699  EXPECT_DOUBLES_EQUAL(truth.at<double>(i), result.at<double>(i), 1e-1);
700 
701  // Check error at result
703 }
704 
705 //*************************************************************************
707  // The "true E" in the body frame is
709 
710  for (size_t i = 0; i < 5; i++) {
711  EssentialMatrixFactor3 factor(100, i, pA(i), pB(i), cRb, model2, K);
712 
713  // Check evaluation
714  Point3 P1 = data.tracks[i].p;
715  const Point2 pi = camera2.project(P1);
716  Point2 expected(pi - pB(i));
717 
718  double d(baseline / P1.z());
719  Vector actual = factor.evaluateError(bodyE, d);
720  EXPECT(assert_equal(expected, actual, 1e-7));
721 
722  Values val;
723  val.insert(100, bodyE);
724  val.insert(i, d);
726  }
727 }
728 
729 } // namespace example2
730 
731 /* ************************************************************************* */
732 int main() {
733  TestResult tr;
734  return TestRegistry::runAllTests(tr);
735 }
736 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
example2::vB
Vector vB(size_t i)
Definition: testEssentialMatrixFactor.cpp:601
gtsam::Cal3Bundler::retract
Cal3Bundler retract(const Vector &d) const
Update calibration with tangent space delta.
Definition: Cal3Bundler.h:134
example2::camera2
PinholeCamera< Cal3Bundler > camera2(data.cameras[1].pose(), trueK)
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
EXPECT_CORRECT_FACTOR_JACOBIANS
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
Definition: factorTesting.h:114
gtsam::EssentialMatrixFactor5::evaluateError
Vector evaluateError(const EssentialMatrix &E, const CALIBRATION &Ka, const CALIBRATION &Kb, OptionalMatrixType HE, OptionalMatrixType HKa, OptionalMatrixType HKb) const override
Calculate the algebraic epipolar error pA' (Ka^-1)' E Kb pB.
Definition: EssentialMatrixFactor.h:491
aRb
Rot3 aRb
Definition: testFundamentalMatrix.cpp:146
trueRotation
Rot3 trueRotation
Definition: testEssentialMatrix.cpp:25
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::EssentialMatrix::error
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H={}) const
epipolar error, algebraic
Definition: EssentialMatrix.cpp:104
Cal3_S2.h
The most common 5DOF 3D->2D calibration.
TestHarness.h
xy
Matrix< float, 2, 1 > xy
Definition: LLT_solve.cpp:7
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
model2
noiseModel::Unit::shared_ptr model2
Definition: testEssentialMatrixFactor.cpp:29
initial
Values initial
Definition: OdometryOptimize.cpp:2
gtsam::EssentialMatrixFactor4::evaluateError
Vector evaluateError(const EssentialMatrix &E, const CALIBRATION &K, OptionalMatrixType HE, OptionalMatrixType HK) const override
Calculate the algebraic epipolar error pA' (K^-1)' E K pB.
Definition: EssentialMatrixFactor.h:387
gtsam::noiseModel::Unit::shared_ptr
std::shared_ptr< Unit > shared_ptr
Definition: NoiseModel.h:621
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
gtsam::EssentialMatrixFactor3
Definition: EssentialMatrixFactor.h:237
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
trueDirection
Unit3 trueDirection(trueTranslation)
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
example2::TEST
TEST(EssentialMatrixFactor3, extraTest)
Definition: testEssentialMatrixFactor.cpp:706
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::skewSymmetric
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:400
result
Values result
Definition: OdometryOptimize.cpp:8
CalibratedCamera.h
Calibrated camera for which only pose is unknown.
example2::vA
Vector vA(size_t i)
Definition: testEssentialMatrixFactor.cpp:597
gtsam::EssentialMatrix::retract
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
Definition: EssentialMatrix.h:92
gtsam::PinholeBaseK::project
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:112
gtsam::SfmData
SfmData stores a bunch of SfmTracks.
Definition: SfmData.h:39
example1::c1Tc2
Point3 c1Tc2
Definition: testEssentialMatrixFactor.cpp:40
pruning_fixture::factor
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
example2::data
SfmData data
Definition: testEssentialMatrixFactor.cpp:583
bX
gtsam::Point3 bX(1, 0, 0)
gtsam::Expression
Definition: Expression.h:47
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::SfmData::tracks
std::vector< SfmTrack > tracks
Sparse set of points.
Definition: SfmData.h:42
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
example2::pB
Point2 pB(size_t i)
Definition: testEssentialMatrixFactor.cpp:591
dataset.h
utility functions for loading datasets
EssentialMatrixFactor.h
bY
gtsam::Point3 bY(0, 1, 0)
gtsam::EssentialMatrixFactor4
Definition: EssentialMatrixFactor.h:334
gtsam::EssentialMatrix
Definition: EssentialMatrix.h:26
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
P1
static double P1[]
Definition: jv.c:552
parameters
static ConjugateGradientParameters parameters
Definition: testIterative.cpp:33
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::Cal3Bundler
Calibration used by Bundler.
Definition: Cal3Bundler.h:32
factorTesting.h
Evaluate derivatives of a nonlinear factor numerically.
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
example2::aTb
Point3 aTb
Definition: testEssentialMatrixFactor.cpp:585
gtsam::HybridValues::insert
void insert(Key j, const Vector &value)
Definition: HybridValues.cpp:85
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
main
int main()
Definition: testEssentialMatrixFactor.cpp:732
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
gtsam::Rot3::inverse
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:312
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
TestResult
Definition: TestResult.h:26
expressionTesting.h
Test harness methods for expressions.
key
const gtsam::Symbol key('X', 0)
M_PI_2
#define M_PI_2
Definition: mconf.h:118
E
DiscreteKey E(5, 2)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
SfmData.h
Data structure for dealing with Structure from Motion data.
gtsam::EssentialMatrixFactor5
Definition: EssentialMatrixFactor.h:434
example2::K
std::shared_ptr< Cal3Bundler > K
Definition: testEssentialMatrixFactor.cpp:594
example2
Definition: testEssentialMatrixFactor.cpp:580
gtsam
traits
Definition: SFMdata.h:40
error
static double error
Definition: testRot3.cpp:37
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::SfmData::cameras
std::vector< SfmCamera > cameras
Set of cameras.
Definition: SfmData.h:40
gtsam::Values
Definition: Values.h:65
gtsam::EssentialMatrixFactor2
Definition: EssentialMatrixFactor.h:112
example2::pA
Point2 pA(size_t i)
Definition: testEssentialMatrixFactor.cpp:590
std
Definition: BFloat16.h:88
gtsam::EssentialMatrixFactor
Definition: EssentialMatrixFactor.h:34
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:156
gtsam::Rot3::matrix
Matrix3 matrix() const
Definition: Rot3M.cpp:218
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
baseline
const double baseline
Definition: testSmartStereoFactor_iSAM2.cpp:51
bZ
gtsam::Point3 bZ(0, 0, 1)
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
ExpressionFactor.h
example1::c1Rc2
Rot3 c1Rc2
Definition: testEssentialMatrixFactor.cpp:39
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
initial
Definition: testScenarioRunner.cpp:148
example2::trueK
Cal3Bundler trueK
Definition: testEssentialMatrixFactor.cpp:593
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
trueE
EssentialMatrix trueE(trueRotation, trueDirection)
gtsam::findExampleDataFile
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
EXPECT_CORRECT_EXPRESSION_JACOBIANS
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by an expression against finite differences.
Definition: expressionTesting.h:48
gtsam::noiseModel::Isotropic::shared_ptr
std::shared_ptr< Isotropic > shared_ptr
Definition: NoiseModel.h:559
gtsam::Cal3Bundler::calibrate
Point2 calibrate(const Point2 &pi, OptionalJacobian< 2, 3 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const
Definition: Cal3Bundler.cpp:93
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Project
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpressionFactor.cpp:40
M_PI
#define M_PI
Definition: mconf.h:117
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
align_3::t
Point2 t(10, 10)
cRb
gtsam::Rot3 cRb
Definition: testEssentialMatrixFactor.cpp:33
model1
noiseModel::Isotropic::shared_ptr model1
Definition: testEssentialMatrixFactor.cpp:26
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
example1
Definition: testEssentialMatrixFactor.cpp:35
gtsam::SfmData::numberTracks
size_t numberTracks() const
The number of reconstructed 3D points.
Definition: SfmData.h:74
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
example1::bodyE
EssentialMatrix bodyE
Definition: testEssentialMatrixFactor.cpp:269
gtsam::ExpressionFactor
Definition: Expression.h:36
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
P2
static double P2[]
Definition: jv.c:557
example2::filename
const string filename
Definition: testEssentialMatrixFactor.cpp:582


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:16:15