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 std::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 
197  // add to a graph
199  graph.emplace_shared<PoseNLE>(key1, feasible1, error_gain);
200 
201  // initialize away from the ideal
202  Pose2 initPose(0.0, 2.0, 3.0);
203  Values init;
204  init.insert(key1, initPose);
205 
206  // optimize
208  ordering.push_back(key1);
210 
211  // verify
213  expected.insert(key1, feasible1);
215 }
216 
217 //******************************************************************************
218 TEST ( NonlinearEquality, allow_error_optimize_with_factors ) {
219 
220  // create a hard constraint
221  Symbol key1('x', 1);
222  Pose2 feasible1(1.0, 2.0, 3.0);
223 
224  // initialize away from the ideal
225  Values init;
226  Pose2 initPose(0.0, 2.0, 3.0);
227  init.insert(key1, initPose);
228 
229  // add nle to a graph
230  double error_gain = 500.0;
232  graph.emplace_shared<PoseNLE>(key1, feasible1, error_gain);
233 
234  // add a soft prior that conflicts
235  graph.emplace_shared<PosePrior>(key1, initPose, noiseModel::Isotropic::Sigma(3, 0.1));
236 
237  // optimize
239  ordering.push_back(key1);
241 
242  // verify
244  expected.insert(key1, feasible1);
245  EXPECT(assert_equal(expected, actual));
246 }
247 
248 //******************************************************************************
249 static SharedDiagonal hard_model = noiseModel::Constrained::All(2);
250 static SharedDiagonal soft_model = noiseModel::Isotropic::Sigma(2, 1.0);
251 
252 //******************************************************************************
253 TEST( testNonlinearEqualityConstraint, unary_basics ) {
254  Point2 pt(1.0, 2.0);
255  Symbol key1('x', 1);
256  double mu = 1000.0;
257  eq2D::UnaryEqualityConstraint constraint(pt, key, mu);
258 
259  Values config1;
260  config1.insert(key, pt);
261  EXPECT(constraint.active(config1));
262  EXPECT(assert_equal(Z_2x1, constraint.evaluateError(pt), tol));
263  EXPECT(assert_equal(Z_2x1, constraint.unwhitenedError(config1), tol));
264  EXPECT_DOUBLES_EQUAL(0.0, constraint.error(config1), tol);
265 
266  Values config2;
267  Point2 ptBad1(2.0, 2.0);
268  config2.insert(key, ptBad1);
269  EXPECT(constraint.active(config2));
270  EXPECT(
271  assert_equal(Vector2(1.0, 0.0), constraint.evaluateError(ptBad1), tol));
272  EXPECT(
273  assert_equal(Vector2(1.0, 0.0), constraint.unwhitenedError(config2), tol));
274  EXPECT_DOUBLES_EQUAL(500.0, constraint.error(config2), tol);
275 }
276 
277 //******************************************************************************
278 TEST( testNonlinearEqualityConstraint, unary_linearization ) {
279  Point2 pt(1.0, 2.0);
280  Symbol key1('x', 1);
281  double mu = 1000.0;
282  eq2D::UnaryEqualityConstraint constraint(pt, key, mu);
283 
284  Values config1;
285  config1.insert(key, pt);
286  GaussianFactor::shared_ptr actual1 = constraint.linearize(config1);
287  GaussianFactor::shared_ptr expected1(
288  new JacobianFactor(key, I_2x2, Z_2x1, hard_model));
289  EXPECT(assert_equal(*expected1, *actual1, tol));
290 
291  Values config2;
292  Point2 ptBad(2.0, 2.0);
293  config2.insert(key, ptBad);
294  GaussianFactor::shared_ptr actual2 = constraint.linearize(config2);
295  GaussianFactor::shared_ptr expected2(
296  new JacobianFactor(key, I_2x2, Vector2(-1.0, 0.0), hard_model));
297  EXPECT(assert_equal(*expected2, *actual2, tol));
298 }
299 
300 //******************************************************************************
301 TEST( testNonlinearEqualityConstraint, unary_simple_optimization ) {
302  // create a single-node graph with a soft and hard constraint to
303  // ensure that the hard constraint overrides the soft constraint
304  Point2 truth_pt(1.0, 2.0);
305  Symbol key('x', 1);
306  double mu = 10.0;
308  new eq2D::UnaryEqualityConstraint(truth_pt, key, mu));
309 
310  Point2 badPt(100.0, -200.0);
312  new simulated2D::Prior(badPt, soft_model, key));
313 
315  graph.push_back(constraint);
317 
318  Values initValues;
319  initValues.insert(key, badPt);
320 
321  // verify error values
322  EXPECT(constraint->active(initValues));
323 
325  expected.insert(key, truth_pt);
326  EXPECT(constraint->active(expected));
327  EXPECT_DOUBLES_EQUAL(0.0, constraint->error(expected), tol);
328 
329  Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
330  EXPECT(assert_equal(expected, actual, tol));
331 }
332 
333 //******************************************************************************
334 TEST( testNonlinearEqualityConstraint, odo_basics ) {
335  Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0);
336  Symbol key1('x', 1), key2('x', 2);
337  double mu = 1000.0;
338  eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu);
339 
340  Values config1;
341  config1.insert(key1, x1);
342  config1.insert(key2, x2);
343  EXPECT(constraint.active(config1));
344  EXPECT(assert_equal(Z_2x1, constraint.evaluateError(x1, x2), tol));
345  EXPECT(assert_equal(Z_2x1, constraint.unwhitenedError(config1), tol));
346  EXPECT_DOUBLES_EQUAL(0.0, constraint.error(config1), tol);
347 
348  Values config2;
349  Point2 x1bad(2.0, 2.0);
350  Point2 x2bad(2.0, 2.0);
351  config2.insert(key1, x1bad);
352  config2.insert(key2, x2bad);
353  EXPECT(constraint.active(config2));
354  EXPECT(
355  assert_equal(Vector2(-1.0, -1.0), constraint.evaluateError(x1bad, x2bad), tol));
356  EXPECT(
357  assert_equal(Vector2(-1.0, -1.0), constraint.unwhitenedError(config2), tol));
358  EXPECT_DOUBLES_EQUAL(1000.0, constraint.error(config2), tol);
359 }
360 
361 //******************************************************************************
362 TEST( testNonlinearEqualityConstraint, odo_linearization ) {
363  Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0);
364  Symbol key1('x', 1), key2('x', 2);
365  double mu = 1000.0;
366  eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu);
367 
368  Values config1;
369  config1.insert(key1, x1);
370  config1.insert(key2, x2);
371  GaussianFactor::shared_ptr actual1 = constraint.linearize(config1);
372  GaussianFactor::shared_ptr expected1(
373  new JacobianFactor(key1, -I_2x2, key2, I_2x2, Z_2x1,
374  hard_model));
375  EXPECT(assert_equal(*expected1, *actual1, tol));
376 
377  Values config2;
378  Point2 x1bad(2.0, 2.0);
379  Point2 x2bad(2.0, 2.0);
380  config2.insert(key1, x1bad);
381  config2.insert(key2, x2bad);
382  GaussianFactor::shared_ptr actual2 = constraint.linearize(config2);
383  GaussianFactor::shared_ptr expected2(
384  new JacobianFactor(key1, -I_2x2, key2, I_2x2, Vector2(1.0, 1.0),
385  hard_model));
386  EXPECT(assert_equal(*expected2, *actual2, tol));
387 }
388 
389 //******************************************************************************
390 TEST( testNonlinearEqualityConstraint, odo_simple_optimize ) {
391  // create a two-node graph, connected by an odometry constraint, with
392  // a hard prior on one variable, and a conflicting soft prior
393  // on the other variable - the constraints should override the soft constraint
394  Point2 truth_pt1(1.0, 2.0), truth_pt2(3.0, 2.0);
395  Symbol key1('x', 1), key2('x', 2);
396 
397  // hard prior on x1
399  new eq2D::UnaryEqualityConstraint(truth_pt1, key1));
400 
401  // soft prior on x2
402  Point2 badPt(100.0, -200.0);
404  new simulated2D::Prior(badPt, soft_model, key2));
405 
406  // odometry constraint
408  new eq2D::OdoEqualityConstraint(truth_pt2-truth_pt1, key1, key2));
409 
414 
415  Values initValues;
416  initValues.insert(key1, Point2(0,0));
417  initValues.insert(key2, badPt);
418 
419  Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
421  expected.insert(key1, truth_pt1);
422  expected.insert(key2, truth_pt2);
423  CHECK(assert_equal(expected, actual, tol));
424 }
425 
426 //******************************************************************************
427 TEST (testNonlinearEqualityConstraint, two_pose ) {
428  /*
429  * Determining a ground truth linear system
430  * with two poses seeing one landmark, with each pose
431  * constrained to a particular value
432  */
433 
435 
436  Symbol x1('x', 1), x2('x', 2);
437  Symbol l1('l', 1), l2('l', 2);
438  Point2 pt_x1(1.0, 1.0), pt_x2(5.0, 6.0);
441 
442  Point2 z1(0.0, 5.0);
443  SharedNoiseModel sigma(noiseModel::Isotropic::Sigma(2, 0.1));
445 
446  Point2 z2(-4.0, 0.0);
448 
450 
451  Values initialEstimate;
452  initialEstimate.insert(x1, pt_x1);
453  initialEstimate.insert(x2, Point2(0,0));
454  initialEstimate.insert(l1, Point2(1.0, 6.0)); // ground truth
455  initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame
456 
457  Values actual =
458  LevenbergMarquardtOptimizer(graph, initialEstimate).optimize();
459 
461  expected.insert(x1, pt_x1);
462  expected.insert(l1, Point2(1.0, 6.0));
463  expected.insert(l2, Point2(1.0, 6.0));
464  expected.insert(x2, Point2(5.0, 6.0));
465  CHECK(assert_equal(expected, actual, 1e-5));
466 }
467 
468 //******************************************************************************
469 TEST (testNonlinearEqualityConstraint, map_warp ) {
470  // get a graph
472 
473  // keys
474  Symbol x1('x', 1), x2('x', 2);
475  Symbol l1('l', 1), l2('l', 2);
476 
477  // constant constraint on x1
478  Point2 pose1(1.0, 1.0);
480 
481  SharedDiagonal sigma = noiseModel::Isotropic::Sigma(2, 0.1);
482 
483  // measurement from x1 to l1
484  Point2 z1(0.0, 5.0);
486 
487  // measurement from x2 to l2
488  Point2 z2(-4.0, 0.0);
490 
491  // equality constraint between l1 and l2
493 
494  // create an initial estimate
495  Values initialEstimate;
496  initialEstimate.insert(x1, Point2(1.0, 1.0));
497  initialEstimate.insert(l1, Point2(1.0, 6.0));
498  initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame
499  initialEstimate.insert(x2, Point2(0.0, 0.0)); // other pose starts at origin
500 
501  // optimize
502  Values actual =
503  LevenbergMarquardtOptimizer(graph, initialEstimate).optimize();
504 
506  expected.insert(x1, Point2(1.0, 1.0));
507  expected.insert(l1, Point2(1.0, 6.0));
508  expected.insert(l2, Point2(1.0, 6.0));
509  expected.insert(x2, Point2(5.0, 6.0));
510  CHECK(assert_equal(expected, actual, tol));
511 }
512 
513 //******************************************************************************
514 TEST (testNonlinearEqualityConstraint, stereo_constrained ) {
515 
516  // make a realistic calibration matrix
517  static double fov = 60; // degrees
518  static int w = 640, h = 480;
519  static Cal3_S2 K(fov, w, h);
520  static std::shared_ptr<Cal3_S2> shK(new Cal3_S2(K));
521 
522  // create initial estimates
523  Rot3 faceTowardsY(Point3(1, 0, 0), Point3(0, 0, -1), Point3(0, 1, 0));
524 
525  Pose3 poseLeft(faceTowardsY, Point3(0, 0, 0)); // origin, left camera
526  PinholeCamera<Cal3_S2> leftCamera(poseLeft, K);
527 
528  Pose3 poseRight(faceTowardsY, Point3(2, 0, 0)); // 2 units to the right
529  PinholeCamera<Cal3_S2> rightCamera(poseRight, K);
530 
531  Point3 landmark(1, 5, 0); //centered between the cameras, 5 units away
532 
533  // keys
534  Symbol key_x1('x', 1), key_x2('x', 2);
535  Symbol key_l1('l', 1), key_l2('l', 2);
536 
537  // create graph
539 
540  // create equality constraints for poses
541  graph.emplace_shared<NonlinearEquality<Pose3>>(key_x1, leftCamera.pose());
542  graph.emplace_shared<NonlinearEquality<Pose3>>(key_x2, rightCamera.pose());
543 
544  // create factors
545  SharedDiagonal vmodel = noiseModel::Unit::Create(2);
547  leftCamera.project(landmark), vmodel, key_x1, key_l1, shK);
549  rightCamera.project(landmark), vmodel, key_x2, key_l2, shK);
550 
551  // add equality constraint saying there is only one point
553 
554  // create initial data
555  Point3 landmark1(0.5, 5, 0);
556  Point3 landmark2(1.5, 5, 0);
557 
558  Values initValues;
559  initValues.insert(key_x1, poseLeft);
560  initValues.insert(key_x2, poseRight);
561  initValues.insert(key_l1, landmark1);
562  initValues.insert(key_l2, landmark2);
563 
564  // optimize
565  Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
566 
567  // create config
568  Values truthValues;
569  truthValues.insert(key_x1, leftCamera.pose());
570  truthValues.insert(key_x2, rightCamera.pose());
571  truthValues.insert(key_l1, landmark);
572  truthValues.insert(key_l2, landmark);
573 
574  // check if correct
575  CHECK(assert_equal(truthValues, actual, 1e-5));
576 }
577 
578 //******************************************************************************
579 int main() {
580  TestResult tr;
581  return TestRegistry::runAllTests(tr);
582 }
583 //******************************************************************************
key1
const Symbol key1('v', 1)
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
PoseNLE
NonlinearEquality< Pose2 > PoseNLE
Definition: testNonlinearEquality.cpp:43
gtsam::BetweenConstraint::shared_ptr
std::shared_ptr< BetweenConstraint< VALUE > > shared_ptr
Definition: BetweenFactor.h:168
CHECK_EXCEPTION
#define CHECK_EXCEPTION(condition, exception_name)
Definition: Test.h:118
Pose2.h
2D Pose
gtsam::BetweenConstraint
Definition: BetweenFactor.h:166
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
simulated2D::GenericPrior::shared_ptr
std::shared_ptr< GenericPrior< VALUE > > shared_ptr
Definition: simulated2D.h:133
fov
static double fov
Definition: testProjectionFactor.cpp:33
ProjectionFactor.h
Reprojection of a LANDMARK to a 2D point.
hard_model
static SharedDiagonal hard_model
Definition: testNonlinearEquality.cpp:249
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::NoiseModelFactor::error
double error(const Values &c) const override
Definition: NonlinearFactor.cpp:138
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:43
gtsam::Z_3x1
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:47
Cal3_S2.h
The most common 5DOF 3D->2D calibration.
l2
gtsam::Key l2
Definition: testLinearContainerFactor.cpp:24
TestHarness.h
PosePrior
PriorFactor< Pose2 > PosePrior
Definition: testNonlinearEquality.cpp:42
mu
double mu
Definition: testBoundingConstraint.cpp:37
b
Scalar * b
Definition: benchVecAdd.cpp:17
z1
Point2 z1
Definition: testTriangulationFactor.cpp:45
key
static Symbol key('x', 1)
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
constraint1
iq2D::PoseXInequality constraint1(key, 1.0, true, mu)
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
gtsam::GaussianFactor
Definition: GaussianFactor.h:38
pt
static const Point3 pt(1.0, 2.0, 3.0)
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
simulated2D::equality_constraints
Definition: simulated2DConstraints.h:34
GaussianBayesNet.h
Chordal Bayes Net, the result of eliminating a factor graph.
Point3.h
3D Point
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
h
const double h
Definition: testSimpleHelicopter.cpp:19
gtsam::NonlinearFactor::active
virtual bool active(const Values &) const
Definition: NonlinearFactor.h:142
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::NonlinearEquality
Definition: NonlinearEquality.h:43
gtsam::NoiseModelFactorN::unwhitenedError
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
Definition: NonlinearFactor.h:607
gtsam::PinholeBaseK< Calibration >::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
landmark2
Point2 landmark2(7.0, 1.5)
gtsam::NonlinearEquality1::shared_ptr
std::shared_ptr< NonlinearEquality1< VALUE > > shared_ptr
fixed value for variable
Definition: NonlinearEquality.h:232
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:170
Point2.h
2D Point
gtsam::Measurement
This is the base class for all measurement types.
Definition: Measurement.h:11
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")
gtsam::NoiseModelFactor::linearize
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
Definition: NonlinearFactor.cpp:152
gtsam::NonlinearEquality1
Definition: NonlinearEquality.h:209
PriorFactor.h
landmark1
Point2 landmark1(5.0, 1.5)
key2
const Symbol key2('v', 2)
x1
Pose3 x1
Definition: testPose3.cpp:663
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
DOUBLES_EQUAL
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:141
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::NonlinearEquality::error
double error(const Values &c) const override
Actual error function calculation.
Definition: NonlinearEquality.h:131
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
gtsam::GenericProjectionFactor
Definition: ProjectionFactor.h:40
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::PinholeCamera::pose
const Pose3 & pose() const
return pose
Definition: PinholeCamera.h:162
landmark
static Point3 landmark(0, 0, 5)
PinholeCamera.h
Base class for all pinhole cameras.
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
Symbol.h
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
NonlinearEquality.h
gtsam::NonlinearEquality2
Definition: NonlinearEquality.h:301
init
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:2006
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
ordering
static enum @1096 ordering
gtsam::equals
Definition: Testable.h:112
TestResult
Definition: TestResult.h:26
gtsam::NonlinearEquality::evaluateError
Vector evaluateError(const T &xj, OptionalMatrixType H) const override
Error function.
Definition: NonlinearEquality.h:142
gtsam::NonlinearEquality1::evaluateError
Vector evaluateError(const X &x1, OptionalMatrixType H) const override
g(x) with optional derivative
Definition: NonlinearEquality.h:256
simulated2D::GenericPrior
Definition: simulated2D.h:129
gtsam
traits
Definition: SFMdata.h:40
error
static double error
Definition: testRot3.cpp:37
pose1
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
gtsam::BetweenFactor::evaluateError
Vector evaluateError(const T &p1, const T &p2, OptionalMatrixType H1, OptionalMatrixType H2) const override
evaluate error, returns vector of errors size of tangent space
Definition: BetweenFactor.h:111
K
#define K
Definition: igam.h:8
main
int main()
Definition: testNonlinearEquality.cpp:579
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
TEST
TEST(NonlinearEquality, linearization)
Definition: testNonlinearEquality.cpp:49
CHECK
#define CHECK(condition)
Definition: Test.h:108
l1
gtsam::Key l1
Definition: testLinearContainerFactor.cpp:24
std
Definition: BFloat16.h:88
A1
static const double A1[]
Definition: expn.h:6
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:156
tol
static const double tol
Definition: testNonlinearEquality.cpp:40
gtsam::Z_2x1
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:46
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
soft_model
static SharedDiagonal soft_model
Definition: testNonlinearEquality.cpp:250
gtsam::NonlinearEquality::linearize
GaussianFactor::shared_ptr linearize(const Values &x) const override
Linearize is over-written, because base linearization tries to whiten.
Definition: NonlinearEquality.h:162
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
init
Definition: TutorialInplaceLU.cpp:2
gtsam::Ordering
Definition: inference/Ordering.h:33
constraint2
iq2D::PoseYInequality constraint2(key, 2.0, true, mu)
shared_poseNLE
std::shared_ptr< PoseNLE > shared_poseNLE
Definition: testNonlinearEquality.cpp:44
test_callbacks.value
value
Definition: test_callbacks.py:160
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
simulated2DConstraints.h
measurement functions and constraint definitions for simulated 2D robot
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::Pose2
Definition: Pose2.h:39
z2
static const Unit3 z2
Definition: testRotateFactor.cpp:43
gtsam::Symbol
Definition: inference/Symbol.h:37


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