testNonlinearEquality.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
12 /*
13  * @file testNonlinearEquality.cpp
14  * @author Alex Cunningham
15  */
16 
18 
25 #include <gtsam/inference/Symbol.h>
26 #include <gtsam/geometry/Point2.h>
27 #include <gtsam/geometry/Pose2.h>
28 #include <gtsam/geometry/Point3.h>
29 #include <gtsam/geometry/Pose3.h>
30 #include <gtsam/geometry/Cal3_S2.h>
32 
34 
35 using namespace std;
36 using namespace gtsam;
37 
39 
40 static const double tol = 1e-5;
41 
44 typedef boost::shared_ptr<PoseNLE> shared_poseNLE;
45 
46 static Symbol key('x', 1);
47 
48 //******************************************************************************
49 TEST ( NonlinearEquality, linearization ) {
50  Pose2 value = Pose2(2.1, 1.0, 2.0);
51  Values linearize;
52  linearize.insert(key, value);
53 
54  // create a nonlinear equality constraint
55  shared_poseNLE nle(new PoseNLE(key, value));
56 
57  // check linearize
58  SharedDiagonal constraintModel = noiseModel::Constrained::All(3);
59  JacobianFactor expLF(key, I_3x3, Z_3x1, constraintModel);
60  GaussianFactor::shared_ptr actualLF = nle->linearize(linearize);
61  EXPECT(assert_equal((const GaussianFactor&)expLF, *actualLF));
62 }
63 
64 //******************************************************************************
65 TEST ( NonlinearEquality, linearization_pose ) {
66 
67  Symbol key('x', 1);
68  Pose2 value;
69  Values config;
70  config.insert(key, value);
71 
72  // create a nonlinear equality constraint
73  shared_poseNLE nle(new PoseNLE(key, value));
74 
75  GaussianFactor::shared_ptr actualLF = nle->linearize(config);
76  EXPECT(true);
77 }
78 
79 //******************************************************************************
80 TEST ( NonlinearEquality, linearization_fail ) {
81  Pose2 value = Pose2(2.1, 1.0, 2.0);
82  Pose2 wrong = Pose2(2.1, 3.0, 4.0);
83  Values bad_linearize;
84  bad_linearize.insert(key, wrong);
85 
86  // create a nonlinear equality constraint
87  shared_poseNLE nle(new PoseNLE(key, value));
88 
89  // check linearize to ensure that it fails for bad linearization points
90  CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument);
91 }
92 
93 //******************************************************************************
94 TEST ( NonlinearEquality, linearization_fail_pose ) {
95 
96  Symbol key('x', 1);
97  Pose2 value(2.0, 1.0, 2.0), wrong(2.0, 3.0, 4.0);
98  Values bad_linearize;
99  bad_linearize.insert(key, wrong);
100 
101  // create a nonlinear equality constraint
102  shared_poseNLE nle(new PoseNLE(key, value));
103 
104  // check linearize to ensure that it fails for bad linearization points
105  CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument);
106 }
107 
108 //******************************************************************************
109 TEST ( NonlinearEquality, linearization_fail_pose_origin ) {
110 
111  Symbol key('x', 1);
112  Pose2 value, wrong(2.0, 3.0, 4.0);
113  Values bad_linearize;
114  bad_linearize.insert(key, wrong);
115 
116  // create a nonlinear equality constraint
117  shared_poseNLE nle(new PoseNLE(key, value));
118 
119  // check linearize to ensure that it fails for bad linearization points
120  CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument);
121 }
122 
123 //******************************************************************************
125  Pose2 value = Pose2(2.1, 1.0, 2.0);
126  Pose2 wrong = Pose2(2.1, 3.0, 4.0);
127  Values feasible, bad_linearize;
128  feasible.insert(key, value);
129  bad_linearize.insert(key, wrong);
130 
131  // create a nonlinear equality constraint
132  shared_poseNLE nle(new PoseNLE(key, value));
133 
134  // check error function outputs
135  Vector actual = nle->unwhitenedError(feasible);
136  EXPECT(assert_equal(actual, Z_3x1));
137 
138  actual = nle->unwhitenedError(bad_linearize);
139  EXPECT(
140  assert_equal(actual, Vector::Constant(3, std::numeric_limits<double>::infinity())));
141 }
142 
143 //******************************************************************************
145  Pose2 value1 = Pose2(2.1, 1.0, 2.0);
146  Pose2 value2 = Pose2(2.1, 3.0, 4.0);
147 
148  // create some constraints to compare
149  shared_poseNLE nle1(new PoseNLE(key, value1));
150  shared_poseNLE nle2(new PoseNLE(key, value1));
151  shared_poseNLE nle3(new PoseNLE(key, value2));
152 
153  // verify
154  EXPECT(nle1->equals(*nle2));
155  // basic equality = true
156  EXPECT(nle2->equals(*nle1));
157  // test symmetry of equals()
158  EXPECT(!nle1->equals(*nle3));
159  // test config
160 }
161 
162 //******************************************************************************
163 TEST ( NonlinearEquality, allow_error_pose ) {
164  Symbol key1('x', 1);
165  Pose2 feasible1(1.0, 2.0, 3.0);
166  double error_gain = 500.0;
167  PoseNLE nle(key1, feasible1, error_gain);
168 
169  // the unwhitened error should provide logmap to the feasible state
170  Pose2 badPoint1(0.0, 2.0, 3.0);
171  Vector actVec = nle.evaluateError(badPoint1);
172  Vector expVec = Vector3(-0.989992, -0.14112, 0.0);
173  EXPECT(assert_equal(expVec, actVec, 1e-5));
174 
175  // the actual error should have a gain on it
176  Values config;
177  config.insert(key1, badPoint1);
178  double actError = nle.error(config);
179  DOUBLES_EQUAL(500.0, actError, 1e-9);
180 
181  // check linearization
182  GaussianFactor::shared_ptr actLinFactor = nle.linearize(config);
183  Matrix A1 = I_3x3;
184  Vector b = expVec;
185  SharedDiagonal model = noiseModel::Constrained::All(3);
186  GaussianFactor::shared_ptr expLinFactor(
187  new JacobianFactor(key1, A1, b, model));
188  EXPECT(assert_equal(*expLinFactor, *actLinFactor, 1e-5));
189 }
190 
191 //******************************************************************************
192 TEST ( NonlinearEquality, allow_error_optimize ) {
193  Symbol key1('x', 1);
194  Pose2 feasible1(1.0, 2.0, 3.0);
195  double error_gain = 500.0;
196  PoseNLE nle(key1, feasible1, error_gain);
197 
198  // add to a graph
200  graph += nle;
201 
202  // initialize away from the ideal
203  Pose2 initPose(0.0, 2.0, 3.0);
204  Values init;
205  init.insert(key1, initPose);
206 
207  // optimize
209  ordering.push_back(key1);
210  Values result = LevenbergMarquardtOptimizer(graph, init, ordering).optimize();
211 
212  // verify
214  expected.insert(key1, feasible1);
215  EXPECT(assert_equal(expected, result));
216 }
217 
218 //******************************************************************************
219 TEST ( NonlinearEquality, allow_error_optimize_with_factors ) {
220 
221  // create a hard constraint
222  Symbol key1('x', 1);
223  Pose2 feasible1(1.0, 2.0, 3.0);
224 
225  // initialize away from the ideal
226  Values init;
227  Pose2 initPose(0.0, 2.0, 3.0);
228  init.insert(key1, initPose);
229 
230  double error_gain = 500.0;
231  PoseNLE nle(key1, feasible1, error_gain);
232 
233  // create a soft prior that conflicts
234  PosePrior prior(key1, initPose, noiseModel::Isotropic::Sigma(3, 0.1));
235 
236  // add to a graph
238  graph += nle;
239  graph += prior;
240 
241  // optimize
243  ordering.push_back(key1);
244  Values actual = LevenbergMarquardtOptimizer(graph, init, ordering).optimize();
245 
246  // verify
248  expected.insert(key1, feasible1);
249  EXPECT(assert_equal(expected, actual));
250 }
251 
252 //******************************************************************************
253 static SharedDiagonal hard_model = noiseModel::Constrained::All(2);
254 static SharedDiagonal soft_model = noiseModel::Isotropic::Sigma(2, 1.0);
255 
256 //******************************************************************************
257 TEST( testNonlinearEqualityConstraint, unary_basics ) {
258  Point2 pt(1.0, 2.0);
259  Symbol key1('x', 1);
260  double mu = 1000.0;
261  eq2D::UnaryEqualityConstraint constraint(pt, key, mu);
262 
263  Values config1;
264  config1.insert(key, pt);
265  EXPECT(constraint.active(config1));
266  EXPECT(assert_equal(Z_2x1, constraint.evaluateError(pt), tol));
267  EXPECT(assert_equal(Z_2x1, constraint.unwhitenedError(config1), tol));
268  EXPECT_DOUBLES_EQUAL(0.0, constraint.error(config1), tol);
269 
270  Values config2;
271  Point2 ptBad1(2.0, 2.0);
272  config2.insert(key, ptBad1);
273  EXPECT(constraint.active(config2));
274  EXPECT(
275  assert_equal(Vector2(1.0, 0.0), constraint.evaluateError(ptBad1), tol));
276  EXPECT(
277  assert_equal(Vector2(1.0, 0.0), constraint.unwhitenedError(config2), tol));
278  EXPECT_DOUBLES_EQUAL(500.0, constraint.error(config2), tol);
279 }
280 
281 //******************************************************************************
282 TEST( testNonlinearEqualityConstraint, unary_linearization ) {
283  Point2 pt(1.0, 2.0);
284  Symbol key1('x', 1);
285  double mu = 1000.0;
286  eq2D::UnaryEqualityConstraint constraint(pt, key, mu);
287 
288  Values config1;
289  config1.insert(key, pt);
290  GaussianFactor::shared_ptr actual1 = constraint.linearize(config1);
291  GaussianFactor::shared_ptr expected1(
292  new JacobianFactor(key, I_2x2, Z_2x1, hard_model));
293  EXPECT(assert_equal(*expected1, *actual1, tol));
294 
295  Values config2;
296  Point2 ptBad(2.0, 2.0);
297  config2.insert(key, ptBad);
298  GaussianFactor::shared_ptr actual2 = constraint.linearize(config2);
299  GaussianFactor::shared_ptr expected2(
300  new JacobianFactor(key, I_2x2, Vector2(-1.0, 0.0), hard_model));
301  EXPECT(assert_equal(*expected2, *actual2, tol));
302 }
303 
304 //******************************************************************************
305 TEST( testNonlinearEqualityConstraint, unary_simple_optimization ) {
306  // create a single-node graph with a soft and hard constraint to
307  // ensure that the hard constraint overrides the soft constraint
308  Point2 truth_pt(1.0, 2.0);
309  Symbol key('x', 1);
310  double mu = 10.0;
312  new eq2D::UnaryEqualityConstraint(truth_pt, key, mu));
313 
314  Point2 badPt(100.0, -200.0);
316  new simulated2D::Prior(badPt, soft_model, key));
317 
319  graph.push_back(constraint);
320  graph.push_back(factor);
321 
322  Values initValues;
323  initValues.insert(key, badPt);
324 
325  // verify error values
326  EXPECT(constraint->active(initValues));
327 
329  expected.insert(key, truth_pt);
330  EXPECT(constraint->active(expected));
331  EXPECT_DOUBLES_EQUAL(0.0, constraint->error(expected), tol);
332 
333  Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
334  EXPECT(assert_equal(expected, actual, tol));
335 }
336 
337 //******************************************************************************
338 TEST( testNonlinearEqualityConstraint, odo_basics ) {
339  Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0);
340  Symbol key1('x', 1), key2('x', 2);
341  double mu = 1000.0;
342  eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu);
343 
344  Values config1;
345  config1.insert(key1, x1);
346  config1.insert(key2, x2);
347  EXPECT(constraint.active(config1));
348  EXPECT(assert_equal(Z_2x1, constraint.evaluateError(x1, x2), tol));
349  EXPECT(assert_equal(Z_2x1, constraint.unwhitenedError(config1), tol));
350  EXPECT_DOUBLES_EQUAL(0.0, constraint.error(config1), tol);
351 
352  Values config2;
353  Point2 x1bad(2.0, 2.0);
354  Point2 x2bad(2.0, 2.0);
355  config2.insert(key1, x1bad);
356  config2.insert(key2, x2bad);
357  EXPECT(constraint.active(config2));
358  EXPECT(
359  assert_equal(Vector2(-1.0, -1.0), constraint.evaluateError(x1bad, x2bad), tol));
360  EXPECT(
361  assert_equal(Vector2(-1.0, -1.0), constraint.unwhitenedError(config2), tol));
362  EXPECT_DOUBLES_EQUAL(1000.0, constraint.error(config2), tol);
363 }
364 
365 //******************************************************************************
366 TEST( testNonlinearEqualityConstraint, odo_linearization ) {
367  Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0);
368  Symbol key1('x', 1), key2('x', 2);
369  double mu = 1000.0;
370  eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu);
371 
372  Values config1;
373  config1.insert(key1, x1);
374  config1.insert(key2, x2);
375  GaussianFactor::shared_ptr actual1 = constraint.linearize(config1);
376  GaussianFactor::shared_ptr expected1(
377  new JacobianFactor(key1, -I_2x2, key2, I_2x2, Z_2x1,
378  hard_model));
379  EXPECT(assert_equal(*expected1, *actual1, tol));
380 
381  Values config2;
382  Point2 x1bad(2.0, 2.0);
383  Point2 x2bad(2.0, 2.0);
384  config2.insert(key1, x1bad);
385  config2.insert(key2, x2bad);
386  GaussianFactor::shared_ptr actual2 = constraint.linearize(config2);
387  GaussianFactor::shared_ptr expected2(
388  new JacobianFactor(key1, -I_2x2, key2, I_2x2, Vector2(1.0, 1.0),
389  hard_model));
390  EXPECT(assert_equal(*expected2, *actual2, tol));
391 }
392 
393 //******************************************************************************
394 TEST( testNonlinearEqualityConstraint, odo_simple_optimize ) {
395  // create a two-node graph, connected by an odometry constraint, with
396  // a hard prior on one variable, and a conflicting soft prior
397  // on the other variable - the constraints should override the soft constraint
398  Point2 truth_pt1(1.0, 2.0), truth_pt2(3.0, 2.0);
399  Symbol key1('x', 1), key2('x', 2);
400 
401  // hard prior on x1
403  new eq2D::UnaryEqualityConstraint(truth_pt1, key1));
404 
405  // soft prior on x2
406  Point2 badPt(100.0, -200.0);
408  new simulated2D::Prior(badPt, soft_model, key2));
409 
410  // odometry constraint
412  new eq2D::OdoEqualityConstraint(truth_pt2-truth_pt1, key1, key2));
413 
415  graph.push_back(constraint1);
416  graph.push_back(constraint2);
417  graph.push_back(factor);
418 
419  Values initValues;
420  initValues.insert(key1, Point2(0,0));
421  initValues.insert(key2, badPt);
422 
423  Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
425  expected.insert(key1, truth_pt1);
426  expected.insert(key2, truth_pt2);
427  CHECK(assert_equal(expected, actual, tol));
428 }
429 
430 //******************************************************************************
431 TEST (testNonlinearEqualityConstraint, two_pose ) {
432  /*
433  * Determining a ground truth linear system
434  * with two poses seeing one landmark, with each pose
435  * constrained to a particular value
436  */
437 
439 
440  Symbol x1('x', 1), x2('x', 2);
441  Symbol l1('l', 1), l2('l', 2);
442  Point2 pt_x1(1.0, 1.0), pt_x2(5.0, 6.0);
443  graph += eq2D::UnaryEqualityConstraint(pt_x1, x1);
444  graph += eq2D::UnaryEqualityConstraint(pt_x2, x2);
445 
446  Point2 z1(0.0, 5.0);
447  SharedNoiseModel sigma(noiseModel::Isotropic::Sigma(2, 0.1));
448  graph += simulated2D::Measurement(z1, sigma, x1, l1);
449 
450  Point2 z2(-4.0, 0.0);
451  graph += simulated2D::Measurement(z2, sigma, x2, l2);
452 
453  graph += eq2D::PointEqualityConstraint(l1, l2);
454 
455  Values initialEstimate;
456  initialEstimate.insert(x1, pt_x1);
457  initialEstimate.insert(x2, Point2(0,0));
458  initialEstimate.insert(l1, Point2(1.0, 6.0)); // ground truth
459  initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame
460 
461  Values actual =
462  LevenbergMarquardtOptimizer(graph, initialEstimate).optimize();
463 
465  expected.insert(x1, pt_x1);
466  expected.insert(l1, Point2(1.0, 6.0));
467  expected.insert(l2, Point2(1.0, 6.0));
468  expected.insert(x2, Point2(5.0, 6.0));
469  CHECK(assert_equal(expected, actual, 1e-5));
470 }
471 
472 //******************************************************************************
473 TEST (testNonlinearEqualityConstraint, map_warp ) {
474  // get a graph
476 
477  // keys
478  Symbol x1('x', 1), x2('x', 2);
479  Symbol l1('l', 1), l2('l', 2);
480 
481  // constant constraint on x1
482  Point2 pose1(1.0, 1.0);
483  graph += eq2D::UnaryEqualityConstraint(pose1, x1);
484 
485  SharedDiagonal sigma = noiseModel::Isotropic::Sigma(2, 0.1);
486 
487  // measurement from x1 to l1
488  Point2 z1(0.0, 5.0);
489  graph += simulated2D::Measurement(z1, sigma, x1, l1);
490 
491  // measurement from x2 to l2
492  Point2 z2(-4.0, 0.0);
493  graph += simulated2D::Measurement(z2, sigma, x2, l2);
494 
495  // equality constraint between l1 and l2
496  graph += eq2D::PointEqualityConstraint(l1, l2);
497 
498  // create an initial estimate
499  Values initialEstimate;
500  initialEstimate.insert(x1, Point2(1.0, 1.0));
501  initialEstimate.insert(l1, Point2(1.0, 6.0));
502  initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame
503  initialEstimate.insert(x2, Point2(0.0, 0.0)); // other pose starts at origin
504 
505  // optimize
506  Values actual =
507  LevenbergMarquardtOptimizer(graph, initialEstimate).optimize();
508 
510  expected.insert(x1, Point2(1.0, 1.0));
511  expected.insert(l1, Point2(1.0, 6.0));
512  expected.insert(l2, Point2(1.0, 6.0));
513  expected.insert(x2, Point2(5.0, 6.0));
514  CHECK(assert_equal(expected, actual, tol));
515 }
516 
517 //******************************************************************************
518 TEST (testNonlinearEqualityConstraint, stereo_constrained ) {
519 
520  // make a realistic calibration matrix
521  static double fov = 60; // degrees
522  static int w = 640, h = 480;
523  static Cal3_S2 K(fov, w, h);
524  static boost::shared_ptr<Cal3_S2> shK(new Cal3_S2(K));
525 
526  // create initial estimates
527  Rot3 faceTowardsY(Point3(1, 0, 0), Point3(0, 0, -1), Point3(0, 1, 0));
528 
529  Pose3 poseLeft(faceTowardsY, Point3(0, 0, 0)); // origin, left camera
530  PinholeCamera<Cal3_S2> leftCamera(poseLeft, K);
531 
532  Pose3 poseRight(faceTowardsY, Point3(2, 0, 0)); // 2 units to the right
533  PinholeCamera<Cal3_S2> rightCamera(poseRight, K);
534 
535  Point3 landmark(1, 5, 0); //centered between the cameras, 5 units away
536 
537  // keys
538  Symbol key_x1('x', 1), key_x2('x', 2);
539  Symbol key_l1('l', 1), key_l2('l', 2);
540 
541  // create graph
543 
544  // create equality constraints for poses
545  graph += NonlinearEquality<Pose3>(key_x1, leftCamera.pose());
546  graph += NonlinearEquality<Pose3>(key_x2, rightCamera.pose());
547 
548  // create factors
549  SharedDiagonal vmodel = noiseModel::Unit::Create(2);
551  leftCamera.project(landmark), vmodel, key_x1, key_l1, shK);
553  rightCamera.project(landmark), vmodel, key_x2, key_l2, shK);
554 
555  // add equality constraint saying there is only one point
556  graph += NonlinearEquality2<Point3>(key_l1, key_l2);
557 
558  // create initial data
559  Point3 landmark1(0.5, 5, 0);
560  Point3 landmark2(1.5, 5, 0);
561 
562  Values initValues;
563  initValues.insert(key_x1, poseLeft);
564  initValues.insert(key_x2, poseRight);
565  initValues.insert(key_l1, landmark1);
566  initValues.insert(key_l2, landmark2);
567 
568  // optimize
569  Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
570 
571  // create config
572  Values truthValues;
573  truthValues.insert(key_x1, leftCamera.pose());
574  truthValues.insert(key_x2, rightCamera.pose());
575  truthValues.insert(key_l1, landmark);
576  truthValues.insert(key_l2, landmark);
577 
578  // check if correct
579  CHECK(assert_equal(truthValues, actual, 1e-5));
580 }
581 
582 //******************************************************************************
583 int main() {
584  TestResult tr;
585  return TestRegistry::runAllTests(tr);
586 }
587 //******************************************************************************
boost::shared_ptr< NonlinearEquality1< VALUE > > shared_ptr
fixed value for variable
iq2D::PoseXInequality constraint1(key, 1.0, true, mu)
NonlinearEquality1< Point2 > UnaryEqualityConstraint
#define CHECK(condition)
Definition: Test.h:109
boost::shared_ptr< GaussianFactor > linearize(const Values &x) const override
double error(const Values &c) const override
const Pose3 & pose() const
return pose
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
virtual const Values & optimize()
Scalar * b
Definition: benchVecAdd.cpp:17
NonlinearEquality< Pose2 > PoseNLE
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Factor Graph consisting of non-linear factors.
boost::shared_ptr< PoseNLE > shared_poseNLE
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:87
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
static enum @843 ordering
Matrix expected
Definition: testMatrix.cpp:974
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:142
Vector2 Point2
Definition: Point2.h:27
iq2D::PoseYInequality constraint2(key, 2.0, true, mu)
double mu
static const double sigma
boost::shared_ptr< BetweenConstraint< VALUE > > shared_ptr
static SharedDiagonal soft_model
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
gtsam::Key l2
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Definition: Half.h:150
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Vector evaluateError(const T &xj, boost::optional< Matrix & > H=boost::none) const override
static const Point3 pt(1.0, 2.0, 3.0)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
#define CHECK_EXCEPTION(condition, exception_name)
Definition: Test.h:119
NonlinearFactorGraph graph
Point2 landmark1(5.0, 1.5)
TEST(NonlinearEquality, linearization)
static const double tol
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
Point2 z2
virtual bool active(const Values &) const
static Point3 landmark(0, 0, 5)
const Symbol key1('v', 1)
GaussianFactor::shared_ptr linearize(const Values &x) const override
Base class for all pinhole cameras.
static Symbol key('x', 1)
Point2 landmark2(7.0, 1.5)
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
NonlinearEquality2< Point2 > PointEqualityConstraint
Vector evaluateError(const X &x1, boost::optional< Matrix & > H=boost::none) const override
GenericMeasurement< Point2, Point2 > Measurement
Definition: simulated2D.h:263
#define EXPECT(condition)
Definition: Test.h:151
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Basic bearing factor from 2D measurement.
RowVector3d w
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
gtsam::Key l1
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
const double h
Point2 z1
Eigen::Vector2d Vector2
Definition: Vector.h:42
Pose3 x1
Definition: testPose3.cpp:588
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:1460
const Symbol key2('v', 2)
3D Point
PriorFactor< Pose2 > PosePrior
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
static double fov
Chordal Bayes Net, the result of eliminating a factor graph.
static double error
Definition: testRot3.cpp:39
Vector3 Point3
Definition: Point3.h:35
double error(const Values &c) const override
boost::shared_ptr< GenericPrior< VALUE > > shared_ptr
Definition: simulated2D.h:131
static SharedDiagonal hard_model
2D Pose
Vector evaluateError(const T &p1, const T &p2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
evaluate error, returns vector of errors size of tangent space
2D Point
3D Pose
int main()
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:45
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
The most common 5DOF 3D->2D calibration.
measurement functions and constraint definitions for simulated 2D robot


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:48:17