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 
10 #include <gtsam/slam/dataset.h>
16 #include <gtsam/geometry/Cal3_S2.h>
17 #include <gtsam/base/Testable.h>
19 
21 
22 using namespace std;
23 using namespace gtsam;
24 
25 // Noise model for first type of factor is evaluating algebraic error
26 noiseModel::Isotropic::shared_ptr model1 = noiseModel::Isotropic::Sigma(1,
27  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("5pointExample1.txt");
39 bool readOK = readBAL(filename, data);
40 Rot3 c1Rc2 = data.cameras[1].pose().rotation();
41 Point3 c1Tc2 = data.cameras[1].pose().translation();
43 Rot3 trueRotation(c1Rc2);
44 Unit3 trueDirection(c1Tc2);
46 double baseline = 0.1; // actual baseline of the camera
47 
48 Point2 pA(size_t i) {
49  return data.tracks[i].measurements[0].second;
50 }
51 Point2 pB(size_t i) {
52  return data.tracks[i].measurements[1].second;
53 }
54 Vector vA(size_t i) {
55  return EssentialMatrix::Homogeneous(pA(i));
56 }
57 Vector vB(size_t i) {
58  return EssentialMatrix::Homogeneous(pB(i));
59 }
60 
61 //*************************************************************************
63  CHECK(readOK);
64 
65  // Check E matrix
66  Matrix expected(3, 3);
67  expected << 0, 0, 0, 0, 0, -0.1, 0.1, 0, 0;
68  Matrix aEb_matrix = skewSymmetric(c1Tc2.x(), c1Tc2.y(), c1Tc2.z())
69  * c1Rc2.matrix();
70  EXPECT(assert_equal(expected, aEb_matrix, 1e-8));
71 
72  // Check some projections
73  EXPECT(assert_equal(Point2(0, 0), pA(0), 1e-8));
74  EXPECT(assert_equal(Point2(0, 0.1), pB(0), 1e-8));
75  EXPECT(assert_equal(Point2(0, -1), pA(4), 1e-8));
76  EXPECT(assert_equal(Point2(-1, 0.2), pB(4), 1e-8));
77 
78  // Check homogeneous version
79  EXPECT(assert_equal(Vector3(-1, 0.2, 1), vB(4), 1e-8));
80 
81  // Check epipolar constraint
82  for (size_t i = 0; i < 5; i++)
83  EXPECT_DOUBLES_EQUAL(0, vA(i).transpose() * aEb_matrix * vB(i), 1e-8);
84 
85  // Check epipolar constraint
86  for (size_t i = 0; i < 5; i++)
87  EXPECT_DOUBLES_EQUAL(0, trueE.error(vA(i), vB(i)), 1e-7);
88 }
89 
90 //*************************************************************************
92  Key key(1);
93  for (size_t i = 0; i < 5; i++) {
94  EssentialMatrixFactor factor(key, pA(i), pB(i), model1);
95 
96  // Check evaluation
97  Vector expected(1);
98  expected << 0;
99  Matrix Hactual;
100  Vector actual = factor.evaluateError(trueE, Hactual);
101  EXPECT(assert_equal(expected, actual, 1e-7));
102 
103  // Use numerical derivatives to calculate the expected Jacobian
104  Matrix Hexpected;
106  Hexpected = numericalDerivative11<Vector1, EssentialMatrix>(
107  boost::bind(&EssentialMatrixFactor::evaluateError, &factor, _1,
108  boost::none), trueE);
109 
110  // Verify the Jacobian is correct
111  EXPECT(assert_equal(Hexpected, Hactual, 1e-8));
112  }
113 }
114 
115 //*************************************************************************
117  Key key(1);
118  for (size_t i = 0; i < 5; i++) {
119  boost::function<double(const EssentialMatrix&, OptionalJacobian<1, 5>)> f =
120  boost::bind(&EssentialMatrix::error, _1, vA(i), vB(i), _2);
121  Expression<EssentialMatrix> E_(key); // leaf expression
122  Expression<double> expr(f, E_); // unary expression
123 
124  // Test the derivatives using Paul's magic
125  Values values;
126  values.insert(key, trueE);
127  EXPECT_CORRECT_EXPRESSION_JACOBIANS(expr, values, 1e-5, 1e-9);
128 
129  // Create the factor
130  ExpressionFactor<double> factor(model1, 0, expr);
131 
132  // Check evaluation
133  Vector expected(1);
134  expected << 0;
135  vector<Matrix> Hactual(1);
136  Vector actual = factor.unwhitenedError(values, Hactual);
137  EXPECT(assert_equal(expected, actual, 1e-7));
138  }
139 }
140 
141 //*************************************************************************
142 TEST(EssentialMatrixFactor, ExpressionFactorRotationOnly) {
143  Key key(1);
144  for (size_t i = 0; i < 5; i++) {
145  boost::function<double(const EssentialMatrix&, OptionalJacobian<1, 5>)> f =
146  boost::bind(&EssentialMatrix::error, _1, vA(i), vB(i), _2);
147  boost::function<EssentialMatrix(const Rot3&, const Unit3&, OptionalJacobian<5, 3>,
149  Expression<Rot3> R_(key);
151  Expression<EssentialMatrix> E_(&EssentialMatrix::FromRotationAndDirection, R_, d_);
152  Expression<double> expr(f, E_);
153 
154  // Test the derivatives using Paul's magic
155  Values values;
156  values.insert(key, trueRotation);
157  EXPECT_CORRECT_EXPRESSION_JACOBIANS(expr, values, 1e-5, 1e-9);
158 
159  // Create the factor
160  ExpressionFactor<double> factor(model1, 0, expr);
161 
162  // Check evaluation
163  Vector expected(1);
164  expected << 0;
165  vector<Matrix> Hactual(1);
166  Vector actual = factor.unwhitenedError(values, Hactual);
167  EXPECT(assert_equal(expected, actual, 1e-7));
168  }
169 }
170 
171 //*************************************************************************
172 TEST (EssentialMatrixFactor, minimization) {
173  // Here we want to optimize directly on essential matrix constraints
174  // Yi Ma's algorithm (Ma01ijcv) is a bit cumbersome to implement,
175  // but GTSAM does the equivalent anyway, provided we give the right
176  // factors. In this case, the factors are the constraints.
177 
178  // We start with a factor graph and add constraints to it
179  // Noise sigma is 1cm, assuming metric measurements
181  for (size_t i = 0; i < 5; i++)
183 
184  // Check error at ground truth
185  Values truth;
186  truth.insert(1, trueE);
187  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
188 
189  // Check error at initial estimate
190  Values initial;
191  EssentialMatrix initialE = trueE.retract(
192  (Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
193  initial.insert(1, initialE);
194 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
195  EXPECT_DOUBLES_EQUAL(643.26, graph.error(initial), 1e-2);
196 #else
197  EXPECT_DOUBLES_EQUAL(639.84, graph.error(initial), 1e-2);
198 #endif
199 
200  // Optimize
202  LevenbergMarquardtOptimizer optimizer(graph, initial, parameters);
203  Values result = optimizer.optimize();
204 
205  // Check result
206  EssentialMatrix actual = result.at<EssentialMatrix>(1);
207  EXPECT(assert_equal(trueE, actual, 1e-1));
208 
209  // Check error at result
210  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-4);
211 
212  // Check errors individually
213  for (size_t i = 0; i < 5; i++)
214  EXPECT_DOUBLES_EQUAL(0, actual.error(vA(i), vB(i)), 1e-6);
215 
216 }
217 
218 //*************************************************************************
220  for (size_t i = 0; i < 5; i++) {
221  EssentialMatrixFactor2 factor(100, i, pA(i), pB(i), model2);
222 
223  // Check evaluation
224  Point3 P1 = data.tracks[i].p, P2 = data.cameras[1].pose().transformTo(P1);
225  const Point2 pi = PinholeBase::Project(P2);
226  Point2 expected(pi - pB(i));
227 
228  Matrix Hactual1, Hactual2;
229  double d(baseline / P1.z());
230  Vector actual = factor.evaluateError(trueE, d, Hactual1, Hactual2);
231  EXPECT(assert_equal(expected, actual, 1e-7));
232 
233  // Use numerical derivatives to calculate the expected Jacobian
234  Matrix Hexpected1, Hexpected2;
235  boost::function<Vector(const EssentialMatrix&, double)> f = boost::bind(
236  &EssentialMatrixFactor2::evaluateError, &factor, _1, _2, boost::none,
237  boost::none);
238  Hexpected1 = numericalDerivative21<Vector2, EssentialMatrix, double>(f, trueE, d);
239  Hexpected2 = numericalDerivative22<Vector2, EssentialMatrix, double>(f, trueE, d);
240 
241  // Verify the Jacobian is correct
242  EXPECT(assert_equal(Hexpected1, Hactual1, 1e-8));
243  EXPECT(assert_equal(Hexpected2, Hactual2, 1e-8));
244  }
245 }
246 
247 //*************************************************************************
248 TEST (EssentialMatrixFactor2, minimization) {
249  // Here we want to optimize for E and inverse depths at the same time
250 
251  // We start with a factor graph and add constraints to it
252  // Noise sigma is 1cm, assuming metric measurements
254  for (size_t i = 0; i < 5; i++)
255  graph.emplace_shared<EssentialMatrixFactor2>(100, i, pA(i), pB(i), model2);
256 
257  // Check error at ground truth
258  Values truth;
259  truth.insert(100, trueE);
260  for (size_t i = 0; i < 5; i++) {
261  Point3 P1 = data.tracks[i].p;
262  truth.insert(i, double(baseline / P1.z()));
263  }
264  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
265 
266  // Optimize
268  // parameters.setVerbosity("ERROR");
269  LevenbergMarquardtOptimizer optimizer(graph, truth, parameters);
270  Values result = optimizer.optimize();
271 
272  // Check result
273  EssentialMatrix actual = result.at<EssentialMatrix>(100);
274  EXPECT(assert_equal(trueE, actual, 1e-1));
275  for (size_t i = 0; i < 5; i++)
276  EXPECT_DOUBLES_EQUAL(truth.at<double>(i), result.at<double>(i), 1e-1);
277 
278  // Check error at result
279  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-4);
280 }
281 
282 //*************************************************************************
283 // Below we want to optimize for an essential matrix specified in a
284 // body coordinate frame B which is rotated with respect to the camera
285 // frame C, via the rotation bRc.
286 
287 // The "true E" in the body frame is then
289 
290 //*************************************************************************
292 
293  for (size_t i = 0; i < 5; i++) {
294  EssentialMatrixFactor3 factor(100, i, pA(i), pB(i), cRb, model2);
295 
296  // Check evaluation
297  Point3 P1 = data.tracks[i].p;
298  const Point2 pi = camera2.project(P1);
299  Point2 expected(pi - pB(i));
300 
301  Matrix Hactual1, Hactual2;
302  double d(baseline / P1.z());
303  Vector actual = factor.evaluateError(bodyE, d, Hactual1, Hactual2);
304  EXPECT(assert_equal(expected, actual, 1e-7));
305 
306  // Use numerical derivatives to calculate the expected Jacobian
307  Matrix Hexpected1, Hexpected2;
308  boost::function<Vector(const EssentialMatrix&, double)> f = boost::bind(
309  &EssentialMatrixFactor3::evaluateError, &factor, _1, _2, boost::none,
310  boost::none);
311  Hexpected1 = numericalDerivative21<Vector2, EssentialMatrix, double>(f, bodyE, d);
312  Hexpected2 = numericalDerivative22<Vector2, EssentialMatrix, double>(f, bodyE, d);
313 
314  // Verify the Jacobian is correct
315  EXPECT(assert_equal(Hexpected1, Hactual1, 1e-8));
316  EXPECT(assert_equal(Hexpected2, Hactual2, 1e-8));
317  }
318 }
319 
320 //*************************************************************************
321 TEST (EssentialMatrixFactor3, minimization) {
322 
323  // As before, we start with a factor graph and add constraints to it
325  for (size_t i = 0; i < 5; i++)
326  // but now we specify the rotation bRc
327  graph.emplace_shared<EssentialMatrixFactor3>(100, i, pA(i), pB(i), cRb, model2);
328 
329  // Check error at ground truth
330  Values truth;
331  truth.insert(100, bodyE);
332  for (size_t i = 0; i < 5; i++) {
333  Point3 P1 = data.tracks[i].p;
334  truth.insert(i, double(baseline / P1.z()));
335  }
336  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
337 
338  // Optimize
340  // parameters.setVerbosity("ERROR");
341  LevenbergMarquardtOptimizer optimizer(graph, truth, parameters);
342  Values result = optimizer.optimize();
343 
344  // Check result
345  EssentialMatrix actual = result.at<EssentialMatrix>(100);
346  EXPECT(assert_equal(bodyE, actual, 1e-1));
347  for (size_t i = 0; i < 5; i++)
348  EXPECT_DOUBLES_EQUAL(truth.at<double>(i), result.at<double>(i), 1e-1);
349 
350  // Check error at result
351  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-4);
352 }
353 
354 } // namespace example1
355 
356 //*************************************************************************
357 
358 namespace example2 {
359 
360 const string filename = findExampleDataFile("5pointExample2.txt");
362 bool readOK = readBAL(filename, data);
363 Rot3 aRb = data.cameras[1].pose().rotation();
364 Point3 aTb = data.cameras[1].pose().translation();
365 EssentialMatrix trueE(aRb, Unit3(aTb));
366 
367 double baseline = 10; // actual baseline of the camera
368 
369 Point2 pA(size_t i) {
370  return data.tracks[i].measurements[0].second;
371 }
372 Point2 pB(size_t i) {
373  return data.tracks[i].measurements[1].second;
374 }
375 
376 boost::shared_ptr<Cal3Bundler> //
377 K = boost::make_shared<Cal3Bundler>(500, 0, 0);
378 PinholeCamera<Cal3Bundler> camera2(data.cameras[1].pose(), *K);
379 
380 Vector vA(size_t i) {
381  Point2 xy = K->calibrate(pA(i));
382  return EssentialMatrix::Homogeneous(xy);
383 }
384 Vector vB(size_t i) {
385  Point2 xy = K->calibrate(pB(i));
386  return EssentialMatrix::Homogeneous(xy);
387 }
388 
389 //*************************************************************************
390 TEST (EssentialMatrixFactor, extraMinimization) {
391  // Additional test with camera moving in positive X direction
392 
394  for (size_t i = 0; i < 5; i++)
396 
397  // Check error at ground truth
398  Values truth;
399  truth.insert(1, trueE);
400  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
401 
402  // Check error at initial estimate
403  Values initial;
404  EssentialMatrix initialE = trueE.retract(
405  (Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
406  initial.insert(1, initialE);
407 
408 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
409  EXPECT_DOUBLES_EQUAL(643.26, graph.error(initial), 1e-2);
410 #else
411  EXPECT_DOUBLES_EQUAL(639.84, graph.error(initial), 1e-2);
412 #endif
413 
414  // Optimize
416  LevenbergMarquardtOptimizer optimizer(graph, initial, parameters);
417  Values result = optimizer.optimize();
418 
419  // Check result
420  EssentialMatrix actual = result.at<EssentialMatrix>(1);
421  EXPECT(assert_equal(trueE, actual, 1e-1));
422 
423  // Check error at result
424  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-4);
425 
426  // Check errors individually
427  for (size_t i = 0; i < 5; i++)
428  EXPECT_DOUBLES_EQUAL(0, actual.error(vA(i), vB(i)), 1e-6);
429 
430 }
431 
432 //*************************************************************************
434  for (size_t i = 0; i < 5; i++) {
435  EssentialMatrixFactor2 factor(100, i, pA(i), pB(i), model2, K);
436 
437  // Check evaluation
438  Point3 P1 = data.tracks[i].p;
439  const Point2 pi = camera2.project(P1);
440  Point2 expected(pi - pB(i));
441 
442  Matrix Hactual1, Hactual2;
443  double d(baseline / P1.z());
444  Vector actual = factor.evaluateError(trueE, d, Hactual1, Hactual2);
445  EXPECT(assert_equal(expected, actual, 1e-7));
446 
447  // Use numerical derivatives to calculate the expected Jacobian
448  Matrix Hexpected1, Hexpected2;
449  boost::function<Vector(const EssentialMatrix&, double)> f = boost::bind(
450  &EssentialMatrixFactor2::evaluateError, &factor, _1, _2, boost::none,
451  boost::none);
452  Hexpected1 = numericalDerivative21<Vector2, EssentialMatrix, double>(f, trueE, d);
453  Hexpected2 = numericalDerivative22<Vector2, EssentialMatrix, double>(f, trueE, d);
454 
455  // Verify the Jacobian is correct
456  EXPECT(assert_equal(Hexpected1, Hactual1, 1e-6));
457  EXPECT(assert_equal(Hexpected2, Hactual2, 1e-8));
458  }
459 }
460 
461 //*************************************************************************
462 TEST (EssentialMatrixFactor2, extraMinimization) {
463  // Additional test with camera moving in positive X direction
464 
465  // We start with a factor graph and add constraints to it
466  // Noise sigma is 1, assuming pixel measurements
468  for (size_t i = 0; i < data.number_tracks(); i++)
469  graph.emplace_shared<EssentialMatrixFactor2>(100, i, pA(i), pB(i), model2, K);
470 
471  // Check error at ground truth
472  Values truth;
473  truth.insert(100, trueE);
474  for (size_t i = 0; i < data.number_tracks(); i++) {
475  Point3 P1 = data.tracks[i].p;
476  truth.insert(i, double(baseline / P1.z()));
477  }
478  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
479 
480  // Optimize
482  // parameters.setVerbosity("ERROR");
483  LevenbergMarquardtOptimizer optimizer(graph, truth, parameters);
484  Values result = optimizer.optimize();
485 
486  // Check result
487  EssentialMatrix actual = result.at<EssentialMatrix>(100);
488  EXPECT(assert_equal(trueE, actual, 1e-1));
489  for (size_t i = 0; i < data.number_tracks(); i++)
490  EXPECT_DOUBLES_EQUAL(truth.at<double>(i), result.at<double>(i), 1e-1);
491 
492  // Check error at result
493  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-4);
494 }
495 
496 //*************************************************************************
498 
499  // The "true E" in the body frame is
500  EssentialMatrix bodyE = cRb.inverse() * trueE;
501 
502  for (size_t i = 0; i < 5; i++) {
503  EssentialMatrixFactor3 factor(100, i, pA(i), pB(i), cRb, model2, K);
504 
505  // Check evaluation
506  Point3 P1 = data.tracks[i].p;
507  const Point2 pi = camera2.project(P1);
508  Point2 expected(pi - pB(i));
509 
510  Matrix Hactual1, Hactual2;
511  double d(baseline / P1.z());
512  Vector actual = factor.evaluateError(bodyE, d, Hactual1, Hactual2);
513  EXPECT(assert_equal(expected, actual, 1e-7));
514 
515  // Use numerical derivatives to calculate the expected Jacobian
516  Matrix Hexpected1, Hexpected2;
517  boost::function<Vector(const EssentialMatrix&, double)> f = boost::bind(
518  &EssentialMatrixFactor3::evaluateError, &factor, _1, _2, boost::none,
519  boost::none);
520  Hexpected1 = numericalDerivative21<Vector2, EssentialMatrix, double>(f, bodyE, d);
521  Hexpected2 = numericalDerivative22<Vector2, EssentialMatrix, double>(f, bodyE, d);
522 
523  // Verify the Jacobian is correct
524  EXPECT(assert_equal(Hexpected1, Hactual1, 1e-6));
525  EXPECT(assert_equal(Hexpected2, Hactual2, 1e-8));
526  }
527 }
528 
529 } // namespace example2
530 
531 /* ************************************************************************* */
532 int main() {
533  TestResult tr;
534  return TestRegistry::runAllTests(tr);
535 }
536 /* ************************************************************************* */
537 
#define CHECK(condition)
Definition: Test.h:109
boost::shared_ptr< Unit > shared_ptr
Definition: NoiseModel.h:601
Vector vA(size_t i)
virtual const Values & optimize()
Concept check for values that can be used in unit tests.
Define the structure for SfM data.
Definition: dataset.h:326
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Factor Graph consisting of non-linear factors.
Eigen::Matrix< double, 1, 1 > Vector1
Definition: testEvent.cpp:34
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Matrix expected
Definition: testMatrix.cpp:974
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H=boost::none) const
epipolar error, algebraic
Vector2 Point2
Definition: Point2.h:27
noiseModel::Unit::shared_ptr model2
const double baseline
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
gtsam::Point3 bX(1, 0, 0)
gtsam::Point3 bY(0, 1, 0)
leaf::MyValues values
Values initial
TEST(EssentialMatrixFactor3, extraTest)
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const override
Definition: Half.h:150
EssentialMatrix trueE(trueRotation, trueDirection)
Some functions to compute numerical derivatives.
Point2 pA(size_t i)
Matrix< float, 2, 1 > xy
Definition: LLT_solve.cpp:7
Matrix3 matrix() const
Definition: Rot3M.cpp:219
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
NonlinearFactorGraph graph
gtsam::Rot3 cRb
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
noiseModel::Isotropic::shared_ptr model1
void g(const string &key, int i)
Definition: testBTree.cpp:43
boost::shared_ptr< Cal3Bundler > K
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:311
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by an expression against finite differences.
std::vector< SfmTrack > tracks
Sparse set of points.
Definition: dataset.h:328
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
PinholeCamera< Cal3_S2 > camera2(pose2,*sharedCal)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
size_t number_tracks() const
The number of reconstructed 3D points.
Definition: dataset.h:333
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
Point2 pB(size_t i)
Test harness methods for expressions.
#define EXPECT(condition)
Definition: Test.h:151
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Point3 bZ(0, 0, 1)
static ConjugateGradientParameters parameters
Calibrated camera for which only pose is unknown.
static const Point3 P2(3.5,-8.2, 4.2)
Unit3 trueDirection(trueTranslation)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
std::vector< SfmCamera > cameras
Set of cameras.
Definition: dataset.h:327
EssentialMatrix bodyE
Rot3 trueRotation
Point2(* Project)(const Point3 &, OptionalJacobian< 2, 3 >)
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const override
boost::shared_ptr< Isotropic > shared_ptr
Definition: NoiseModel.h:541
static double error
Definition: testRot3.cpp:39
Vector3 Point3
Definition: Point3.h:35
double error(const Values &values) const
Vector evaluateError(const EssentialMatrix &E, boost::optional< Matrix & > H=boost::none) const override
vector of errors returns 1D vector
The matrix class, also used for vectors and row-vectors.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
utility functions for loading datasets
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Vector vB(size_t i)
The most common 5DOF 3D->2D calibration.
bool readBAL(const string &filename, SfmData &data)
This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfmData...
Definition: dataset.cpp:1073


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:30