testGaussianISAM2.cpp
Go to the documentation of this file.
1 
8 
9 #include <tests/smallExample.h>
12 #include <gtsam/geometry/Point2.h>
13 #include <gtsam/geometry/Pose2.h>
14 #include <gtsam/geometry/Pose3.h>
15 #include <gtsam/nonlinear/Values.h>
22 #include <gtsam/base/debug.h>
25 
27 
28 
29 using namespace std;
30 using namespace gtsam;
31 using std::shared_ptr;
32 
33 static const SharedNoiseModel model;
34 
35 // SETDEBUG("ISAM2 update", true);
36 // SETDEBUG("ISAM2 update verbose", true);
37 // SETDEBUG("ISAM2 recalculate", true);
38 
39 // Set up parameters
40 SharedDiagonal odoNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.1, 0.1, M_PI/100.0).finished());
41 SharedDiagonal brNoise = noiseModel::Diagonal::Sigmas((Vector(2) << M_PI/100.0, 0.1).finished());
42 
44  Values* init_values = nullptr,
45  NonlinearFactorGraph* full_graph = nullptr,
47  0, false, true,
48  ISAM2Params::CHOLESKY, true,
49  DefaultKeyFormatter, true),
50  size_t maxPoses = 10) {
51  // These variables will be reused and accumulate factors and values
52  ISAM2 isam(params);
53  Values fullinit;
54  NonlinearFactorGraph fullgraph;
55 
56  // i keeps track of the time step
57  size_t i = 0;
58 
59  // Add a prior at time 0 and update isam
60  {
61  NonlinearFactorGraph newfactors;
62  newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise);
63  fullgraph.push_back(newfactors);
64 
65  Values init;
66  init.insert((0), Pose2(0.01, 0.01, 0.01));
67  fullinit.insert((0), Pose2(0.01, 0.01, 0.01));
68 
69  isam.update(newfactors, init);
70  }
71 
72  if(i > maxPoses)
73  goto done;
74 
75  // Add odometry from time 0 to time 5
76  for( ; i<5; ++i) {
77  NonlinearFactorGraph newfactors;
78  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
79  fullgraph.push_back(newfactors);
80 
81  Values init;
82  init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
83  fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
84 
85  isam.update(newfactors, init);
86 
87  if(i > maxPoses)
88  goto done;
89  }
90 
91  if(i > maxPoses)
92  goto done;
93 
94  // Add odometry from time 5 to 6 and landmark measurement at time 5
95  {
96  NonlinearFactorGraph newfactors;
97  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
98  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise);
99  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise);
100  fullgraph.push_back(newfactors);
101 
102  Values init;
103  init.insert((i+1), Pose2(1.01, 0.01, 0.01));
104  init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
105  init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
106  fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01));
107  fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
108  fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
109 
110  isam.update(newfactors, init);
111  ++ i;
112  }
113 
114  if(i > maxPoses)
115  goto done;
116 
117  // Add odometry from time 6 to time 10
118  for( ; i<10; ++i) {
119  NonlinearFactorGraph newfactors;
120  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
121  fullgraph.push_back(newfactors);
122 
123  Values init;
124  init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
125  fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
126 
127  isam.update(newfactors, init);
128 
129  if(i > maxPoses)
130  goto done;
131  }
132 
133  if(i > maxPoses)
134  goto done;
135 
136  // Add odometry from time 10 to 11 and landmark measurement at time 10
137  {
138  NonlinearFactorGraph newfactors;
139  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
140  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
141  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
142  fullgraph.push_back(newfactors);
143 
144  Values init;
145  init.insert((i+1), Pose2(6.9, 0.1, 0.01));
146  fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01));
147 
148  isam.update(newfactors, init);
149  ++ i;
150  }
151 
152 done:
153 
154  if (full_graph)
155  *full_graph = fullgraph;
156 
157  if (init_values)
158  *init_values = fullinit;
159 
160  return isam;
161 }
162 
163 /* ************************************************************************* */
164 //TEST(ISAM2, CheckRelinearization) {
165 //
166 // typedef GaussianISAM2<Values>::Impl Impl;
167 //
168 // // Create values where indices 1 and 3 are above the threshold of 0.1
169 // VectorValues values;
170 // values.reserve(4, 10);
171 // values.push_back_preallocated(Vector2(0.09, 0.09));
172 // values.push_back_preallocated(Vector3(0.11, 0.11, 0.09));
173 // values.push_back_preallocated(Vector3(0.09, 0.09, 0.09));
174 // values.push_back_preallocated(Vector2(0.11, 0.11));
175 //
176 // // Create a permutation
177 // Permutation permutation(4);
178 // permutation[0] = 2;
179 // permutation[1] = 0;
180 // permutation[2] = 1;
181 // permutation[3] = 3;
182 //
183 // Permuted<VectorValues> permuted(permutation, values);
184 //
185 // // After permutation, the indices above the threshold are 2 and 2
186 // KeySet expected;
187 // expected.insert(2);
188 // expected.insert(3);
189 //
190 // // Indices checked by CheckRelinearization
191 // KeySet actual = Impl::CheckRelinearization(permuted, 0.1);
192 //
193 // EXPECT(assert_equal(expected, actual));
194 //}
195 
196 /* ************************************************************************* */
198 {
200  const ISAM2& isam;
202  consistent(true), isam(isam) {}
204  {
205  if(find(isam.roots().begin(), isam.roots().end(), node) == isam.roots().end())
206  {
207  if(node->parent_.expired())
208  consistent = false;
209  if(find(node->parent()->children.begin(), node->parent()->children.end(), node) == node->parent()->children.end())
210  consistent = false;
211  }
212  for(Key j: node->conditional()->frontals())
213  {
214  if(isam.nodes().at(j).get() != node.get())
215  consistent = false;
216  }
217  return 0;
218  }
219 };
220 
221 /* ************************************************************************* */
222 bool isam_check(const NonlinearFactorGraph& fullgraph, const Values& fullinit, const ISAM2& isam, Test& test, TestResult& result) {
223 
224  TestResult& result_ = result;
225  const string name_ = test.getName();
226 
227  Values actual = isam.calculateEstimate();
228  Values expected = fullinit.retract(fullgraph.linearize(fullinit)->optimize());
229 
230  bool isamEqual = assert_equal(expected, actual);
231 
232  // Check information
233  GaussianFactorGraph isamGraph(isam);
234  isamGraph.push_back(isam.roots().front()->cachedFactor_);
235  Matrix expectedHessian = fullgraph.linearize(isam.getLinearizationPoint())->augmentedHessian();
236  Matrix actualHessian = isamGraph.augmentedHessian();
237  expectedHessian.bottomRightCorner(1,1) = actualHessian.bottomRightCorner(1,1);
238  bool isamTreeEqual = assert_equal(expectedHessian, actualHessian);
239 
240  // Check consistency
241  ConsistencyVisitor visitor(isam);
242  int data; // Unused
244  bool consistent = visitor.consistent;
245 
246  // The following two checks make sure that the cached gradients are maintained and used correctly
247 
248  // Check gradient at each node
249  bool nodeGradientsOk = true;
250  for (const auto& [key, clique] : isam.nodes()) {
251  // Compute expected gradient
253  jfg.push_back(clique->conditional());
254  VectorValues expectedGradient = jfg.gradientAtZero();
255  // Compare with actual gradients
256  DenseIndex variablePosition = 0;
257  for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) {
258  const DenseIndex dim = clique->conditional()->getDim(jit);
259  Vector actual = clique->gradientContribution().segment(variablePosition, dim);
260  bool gradOk = assert_equal(expectedGradient[*jit], actual);
261  EXPECT(gradOk);
262  nodeGradientsOk = nodeGradientsOk && gradOk;
263  variablePosition += dim;
264  }
265  bool dimOk = clique->gradientContribution().rows() == variablePosition;
266  EXPECT(dimOk);
267  nodeGradientsOk = nodeGradientsOk && dimOk;
268  }
269 
270  // Check gradient
271  VectorValues expectedGradient = GaussianFactorGraph(isam).gradientAtZero();
272  VectorValues expectedGradient2 = GaussianFactorGraph(isam).gradient(VectorValues::Zero(expectedGradient));
273  VectorValues actualGradient = isam.gradientAtZero();
274  bool expectedGradOk = assert_equal(expectedGradient2, expectedGradient);
275  EXPECT(expectedGradOk);
276  bool totalGradOk = assert_equal(expectedGradient, actualGradient);
277  EXPECT(totalGradOk);
278 
279  return nodeGradientsOk && expectedGradOk && totalGradOk && isamEqual && isamTreeEqual && consistent;
280 }
281 
282 /* ************************************************************************* */
284 {
285  for(size_t i = 0; i < 10; ++i) {
286  // These variables will be reused and accumulate factors and values
287  Values fullinit;
288  NonlinearFactorGraph fullgraph;
289  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false), i);
290 
291  // Compare solutions
292  EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_));
293  }
294 }
295 
296 /* ************************************************************************* */
297 TEST(ISAM2, slamlike_solution_gaussnewton)
298 {
299  // These variables will be reused and accumulate factors and values
300  Values fullinit;
301  NonlinearFactorGraph fullgraph;
302  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
303 
304  // Compare solutions
305  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
306 }
307 
308 /* ************************************************************************* */
309 TEST(ISAM2, slamlike_solution_dogleg)
310 {
311  // These variables will be reused and accumulate factors and values
312  Values fullinit;
313  NonlinearFactorGraph fullgraph;
314  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false));
315 
316  // Compare solutions
317  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
318 }
319 
320 /* ************************************************************************* */
321 TEST(ISAM2, slamlike_solution_gaussnewton_qr)
322 {
323  // These variables will be reused and accumulate factors and values
324  Values fullinit;
325  NonlinearFactorGraph fullgraph;
326  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false, false, ISAM2Params::QR));
327 
328  // Compare solutions
329  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
330 }
331 
332 /* ************************************************************************* */
333 TEST(ISAM2, slamlike_solution_dogleg_qr)
334 {
335  // These variables will be reused and accumulate factors and values
336  Values fullinit;
337  NonlinearFactorGraph fullgraph;
338  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false, false, ISAM2Params::QR));
339 
340  // Compare solutions
341  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
342 }
343 
344 /* ************************************************************************* */
345 TEST(ISAM2, clone) {
346 
347  ISAM2 clone1;
348 
349  {
351  clone1 = isam;
352 
353  ISAM2 clone2(isam);
354 
355  // Modify original isam
358  isam.calculateEstimate<Pose2>(0).between(isam.calculateEstimate<Pose2>(10)), noiseModel::Unit::Create(3));
360 
362  }
363 
364  // This is to (perhaps unsuccessfully) try to currupt unallocated memory referenced
365  // if the references in the iSAM2 copy point to the old instance which deleted at
366  // the end of the {...} section above.
367  ISAM2 temp = createSlamlikeISAM2();
368 
370  CHECK(assert_equal(clone1, temp));
371 
372  // Check clone empty
373  ISAM2 isam;
374  clone1 = isam;
375  CHECK(assert_equal(ISAM2(), clone1));
376 }
377 
378 /* ************************************************************************* */
379 TEST(ISAM2, removeFactors)
380 {
381  // This test builds a graph in the same way as the "slamlike" test above, but
382  // then removes the 2nd-to-last landmark measurement
383 
384  // These variables will be reused and accumulate factors and values
385  Values fullinit;
386  NonlinearFactorGraph fullgraph;
387  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
388 
389  // Remove the 2nd measurement on landmark 0 (Key 100)
390  FactorIndices toRemove;
391  toRemove.push_back(12);
392  isam.update(NonlinearFactorGraph(), Values(), toRemove);
393 
394  // Remove the factor from the full system
395  fullgraph.remove(12);
396 
397  // Compare solutions
398  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
399 }
400 
401 /* ************************************************************************* */
402 TEST(ISAM2, removeVariables)
403 {
404  // These variables will be reused and accumulate factors and values
405  Values fullinit;
406  NonlinearFactorGraph fullgraph;
407  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
408 
409  // Remove the measurement on landmark 0 (Key 100)
410  FactorIndices toRemove;
411  toRemove.push_back(7);
412  toRemove.push_back(14);
413  isam.update(NonlinearFactorGraph(), Values(), toRemove);
414 
415  // Remove the factors and variable from the full system
416  fullgraph.remove(7);
417  fullgraph.remove(14);
418  fullinit.erase(100);
419 
420  // Compare solutions
421  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
422 }
423 
424 /* ************************************************************************* */
425 TEST(ISAM2, swapFactors)
426 {
427  // This test builds a graph in the same way as the "slamlike" test above, but
428  // then swaps the 2nd-to-last landmark measurement with a different one
429 
430  Values fullinit;
431  NonlinearFactorGraph fullgraph;
432  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph);
433 
434  // Remove the measurement on landmark 0 and replace with a different one
435  {
436  size_t swap_idx = isam.getFactorsUnsafe().size()-2;
437  FactorIndices toRemove;
438  toRemove.push_back(swap_idx);
439  fullgraph.remove(swap_idx);
440 
441  NonlinearFactorGraph swapfactors;
442 // swapfactors += BearingRange<Pose2,Point2>(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise; // original factor
443  swapfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 5.0, brNoise);
444  fullgraph.push_back(swapfactors);
445  isam.update(swapfactors, Values(), toRemove);
446  }
447 
448  // Compare solutions
450  EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_));
451 
452  // Check gradient at each node
453  for (const auto& [key, clique]: isam.nodes()) {
454  // Compute expected gradient
456  jfg.push_back(clique->conditional());
457  VectorValues expectedGradient = jfg.gradientAtZero();
458  // Compare with actual gradients
459  DenseIndex variablePosition = 0;
460  for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) {
461  const DenseIndex dim = clique->conditional()->getDim(jit);
462  Vector actual = clique->gradientContribution().segment(variablePosition, dim);
463  EXPECT(assert_equal(expectedGradient[*jit], actual));
464  variablePosition += dim;
465  }
466  EXPECT_LONGS_EQUAL((long)clique->gradientContribution().rows(), (long)variablePosition);
467  }
468 
469  // Check gradient
470  VectorValues expectedGradient = GaussianFactorGraph(isam).gradientAtZero();
471  VectorValues expectedGradient2 = GaussianFactorGraph(isam).gradient(VectorValues::Zero(expectedGradient));
472  VectorValues actualGradient = isam.gradientAtZero();
473  EXPECT(assert_equal(expectedGradient2, expectedGradient));
474  EXPECT(assert_equal(expectedGradient, actualGradient));
475 }
476 
477 /* ************************************************************************* */
478 TEST(ISAM2, constrained_ordering)
479 {
480  // These variables will be reused and accumulate factors and values
481  ISAM2 isam(ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
482  Values fullinit;
483  NonlinearFactorGraph fullgraph;
484 
485  // We will constrain x3 and x4 to the end
486  FastMap<Key, int> constrained;
487  constrained.insert(make_pair((3), 1));
488  constrained.insert(make_pair((4), 2));
489 
490  // i keeps track of the time step
491  size_t i = 0;
492 
493  // Add a prior at time 0 and update isam
494  {
495  NonlinearFactorGraph newfactors;
496  newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise);
497  fullgraph.push_back(newfactors);
498 
499  Values init;
500  init.insert((0), Pose2(0.01, 0.01, 0.01));
501  fullinit.insert((0), Pose2(0.01, 0.01, 0.01));
502 
503  isam.update(newfactors, init);
504  }
505 
506  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
507 
508  // Add odometry from time 0 to time 5
509  for( ; i<5; ++i) {
510  NonlinearFactorGraph newfactors;
511  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
512  fullgraph.push_back(newfactors);
513 
514  Values init;
515  init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
516  fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
517 
518  if(i >= 3)
519  isam.update(newfactors, init, FactorIndices(), constrained);
520  else
521  isam.update(newfactors, init);
522  }
523 
524  // Add odometry from time 5 to 6 and landmark measurement at time 5
525  {
526  NonlinearFactorGraph newfactors;
527  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
528  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise);
529  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise);
530  fullgraph.push_back(newfactors);
531 
532  Values init;
533  init.insert((i+1), Pose2(1.01, 0.01, 0.01));
534  init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
535  init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
536  fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01));
537  fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
538  fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
539 
540  isam.update(newfactors, init, FactorIndices(), constrained);
541  ++ i;
542  }
543 
544  // Add odometry from time 6 to time 10
545  for( ; i<10; ++i) {
546  NonlinearFactorGraph newfactors;
547  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
548  fullgraph.push_back(newfactors);
549 
550  Values init;
551  init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
552  fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
553 
554  isam.update(newfactors, init, FactorIndices(), constrained);
555  }
556 
557  // Add odometry from time 10 to 11 and landmark measurement at time 10
558  {
559  NonlinearFactorGraph newfactors;
560  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
561  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
562  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
563  fullgraph.push_back(newfactors);
564 
565  Values init;
566  init.insert((i+1), Pose2(6.9, 0.1, 0.01));
567  fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01));
568 
569  isam.update(newfactors, init, FactorIndices(), constrained);
570  ++ i;
571  }
572 
573  // Compare solutions
574  EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_));
575 
576  // Check gradient at each node
577  for (const auto& [key, clique]: isam.nodes()) {
578  // Compute expected gradient
580  jfg.push_back(clique->conditional());
581  VectorValues expectedGradient = jfg.gradientAtZero();
582  // Compare with actual gradients
583  DenseIndex variablePosition = 0;
584  for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) {
585  const DenseIndex dim = clique->conditional()->getDim(jit);
586  Vector actual = clique->gradientContribution().segment(variablePosition, dim);
587  EXPECT(assert_equal(expectedGradient[*jit], actual));
588  variablePosition += dim;
589  }
590  LONGS_EQUAL((long)clique->gradientContribution().rows(), (long)variablePosition);
591  }
592 
593  // Check gradient
594  VectorValues expectedGradient = GaussianFactorGraph(isam).gradientAtZero();
595  VectorValues expectedGradient2 = GaussianFactorGraph(isam).gradient(VectorValues::Zero(expectedGradient));
596  VectorValues actualGradient = isam.gradientAtZero();
597  EXPECT(assert_equal(expectedGradient2, expectedGradient));
598  EXPECT(assert_equal(expectedGradient, actualGradient));
599 }
600 
601 /* ************************************************************************* */
602 TEST(ISAM2, slamlike_solution_partial_relinearization_check)
603 {
604  // These variables will be reused and accumulate factors and values
605  Values fullinit;
606  NonlinearFactorGraph fullgraph;
607  ISAM2Params params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false);
608  params.enablePartialRelinearizationCheck = true;
609  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, params);
610 
611  // Compare solutions
612  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
613 }
614 
615 namespace {
616  bool checkMarginalizeLeaves(ISAM2& isam, const FastList<Key>& leafKeys) {
617  Matrix expectedAugmentedHessian, expected3AugmentedHessian;
618  KeyVector toKeep;
619  for (const auto& [key, clique]: isam.getDelta()) {
620  if(find(leafKeys.begin(), leafKeys.end(), key) == leafKeys.end()) {
621  toKeep.push_back(key);
622  }
623  }
624 
625  // Calculate expected marginal from iSAM2 tree
626  expectedAugmentedHessian = GaussianFactorGraph(isam).marginal(toKeep, EliminateQR)->augmentedHessian();
627 
628  // Calculate expected marginal from cached linear factors
629  //assert(isam.params().cacheLinearizedFactors);
630  //Matrix expected2AugmentedHessian = isam.linearFactors_.marginal(toKeep, EliminateQR)->augmentedHessian();
631 
632  // Calculate expected marginal from original nonlinear factors
633  expected3AugmentedHessian = isam.getFactorsUnsafe().linearize(isam.getLinearizationPoint())
634  ->marginal(toKeep, EliminateQR)->augmentedHessian();
635 
636  // Do marginalization
637  isam.marginalizeLeaves(leafKeys);
638 
639  // Check
640  GaussianFactorGraph actualMarginalGraph(isam);
641  Matrix actualAugmentedHessian = actualMarginalGraph.augmentedHessian();
642  //Matrix actual2AugmentedHessian = linearFactors_.augmentedHessian();
643  Matrix actual3AugmentedHessian = isam.getFactorsUnsafe().linearize(
644  isam.getLinearizationPoint())->augmentedHessian();
645  assert(actualAugmentedHessian.allFinite());
646 
647  // Check full marginalization
648  //cout << "treeEqual" << endl;
649  bool treeEqual = assert_equal(expectedAugmentedHessian, actualAugmentedHessian, 1e-6);
650  //actualAugmentedHessian.bottomRightCorner(1,1) = expected2AugmentedHessian.bottomRightCorner(1,1); bool linEqual = assert_equal(expected2AugmentedHessian, actualAugmentedHessian, 1e-6);
651  //cout << "nonlinEqual" << endl;
652  actualAugmentedHessian.bottomRightCorner(1,1) = expected3AugmentedHessian.bottomRightCorner(1,1); bool nonlinEqual = assert_equal(expected3AugmentedHessian, actualAugmentedHessian, 1e-6);
653  //bool linCorrect = assert_equal(expected3AugmentedHessian, expected2AugmentedHessian, 1e-6);
654  //actual2AugmentedHessian.bottomRightCorner(1,1) = expected3AugmentedHessian.bottomRightCorner(1,1); bool afterLinCorrect = assert_equal(expected3AugmentedHessian, actual2AugmentedHessian, 1e-6);
655  //cout << "nonlinCorrect" << endl;
656  bool afterNonlinCorrect = assert_equal(expected3AugmentedHessian, actual3AugmentedHessian, 1e-6);
657 
658  bool ok = treeEqual && /*linEqual &&*/ nonlinEqual && /*linCorrect &&*/ /*afterLinCorrect &&*/ afterNonlinCorrect;
659  return ok;
660  }
661 
662  std::optional<FastMap<Key, int>> createOrderingConstraints(const ISAM2& isam, const KeyVector& newKeys, const KeySet& marginalizableKeys)
663  {
664  if (marginalizableKeys.empty()) {
665  return {};
666  } else {
667  FastMap<Key, int> constrainedKeys = FastMap<Key, int>();
668  // Generate ordering constraints so that the marginalizable variables will be eliminated first
669  // Set all existing and new variables to Group1
670  for (const auto& key_val : isam.getDelta()) {
671  constrainedKeys.emplace(key_val.first, 1);
672  }
673  for (const auto& key : newKeys) {
674  constrainedKeys.emplace(key, 1);
675  }
676  // And then re-assign the marginalizable variables to Group0 so that they'll all be leaf nodes
677  for (const auto& key : marginalizableKeys) {
678  constrainedKeys.at(key) = 0;
679  }
680  return constrainedKeys;
681  }
682  }
683 
684  void markAffectedKeys(const Key& key, const ISAM2Clique::shared_ptr& rootClique, KeyList& additionalKeys)
685  {
686  std::stack<ISAM2Clique::shared_ptr> frontier;
687  frontier.push(rootClique);
688  // Basic DFS to find additional keys
689  while (!frontier.empty()) {
690  // Get the top of the stack
691  const ISAM2Clique::shared_ptr clique = frontier.top();
692  frontier.pop();
693  // Check if we have more keys and children to add
694  if (std::find(clique->conditional()->beginParents(), clique->conditional()->endParents(), key) !=
695  clique->conditional()->endParents()) {
696  for (Key i : clique->conditional()->frontals()) {
697  additionalKeys.push_back(i);
698  }
699  for (const ISAM2Clique::shared_ptr& child : clique->children) {
700  frontier.push(child);
701  }
702  }
703  }
704  }
705 
706  bool updateAndMarginalize(const NonlinearFactorGraph& newFactors, const Values& newValues, const KeySet& marginalizableKeys, ISAM2& isam)
707  {
708  // Force ISAM2 to put marginalizable variables at the beginning
709  auto orderingConstraints = createOrderingConstraints(isam, newValues.keys(), marginalizableKeys);
710 
711  // Mark additional keys between the marginalized keys and the leaves
712  KeyList markedKeys;
713  for (Key key : marginalizableKeys) {
714  markedKeys.push_back(key);
715  ISAM2Clique::shared_ptr clique = isam[key];
716  for (const ISAM2Clique::shared_ptr& child : clique->children) {
717  markAffectedKeys(key, child, markedKeys);
718  }
719  }
720 
721  // Update
722  isam.update(newFactors, newValues, FactorIndices{}, orderingConstraints, {}, markedKeys);
723 
724  if (!marginalizableKeys.empty()) {
725  FastList<Key> leafKeys(marginalizableKeys.begin(), marginalizableKeys.end());
726  return checkMarginalizeLeaves(isam, leafKeys);
727  }
728  else {
729  return true;
730  }
731  }
732 }
733 
734 /* ************************************************************************* */
735 TEST(ISAM2, marginalizeLeaves1) {
736  ISAM2 isam;
738  factors.addPrior(0, 0.0, model);
739 
743 
744  Values values;
745  values.insert(0, 0.0);
746  values.insert(1, 0.0);
747  values.insert(2, 0.0);
748 
749  FastMap<Key, int> constrainedKeys;
750  constrainedKeys.insert(make_pair(0, 0));
751  constrainedKeys.insert(make_pair(1, 1));
752  constrainedKeys.insert(make_pair(2, 2));
753 
754  isam.update(factors, values, FactorIndices(), constrainedKeys);
755 
756  FastList<Key> leafKeys {0};
757  EXPECT(checkMarginalizeLeaves(isam, leafKeys));
758 }
759 
760 /* ************************************************************************* */
761 TEST(ISAM2, marginalizeLeaves2) {
762  ISAM2 isam;
763 
765  factors.addPrior(0, 0.0, model);
766 
771 
772  Values values;
773  values.insert(0, 0.0);
774  values.insert(1, 0.0);
775  values.insert(2, 0.0);
776  values.insert(3, 0.0);
777 
778  FastMap<Key, int> constrainedKeys;
779  constrainedKeys.insert(make_pair(0, 0));
780  constrainedKeys.insert(make_pair(1, 1));
781  constrainedKeys.insert(make_pair(2, 2));
782  constrainedKeys.insert(make_pair(3, 3));
783 
784  isam.update(factors, values, FactorIndices(), constrainedKeys);
785 
786  FastList<Key> leafKeys {0};
787  EXPECT(checkMarginalizeLeaves(isam, leafKeys));
788 }
789 
790 /* ************************************************************************* */
791 TEST(ISAM2, marginalizeLeaves3) {
792  ISAM2 isam;
793 
795  factors.addPrior(0, 0.0, model);
796 
800 
802 
806 
807  Values values;
808  values.insert(0, 0.0);
809  values.insert(1, 0.0);
810  values.insert(2, 0.0);
811  values.insert(3, 0.0);
812  values.insert(4, 0.0);
813  values.insert(5, 0.0);
814 
815  FastMap<Key, int> constrainedKeys;
816  constrainedKeys.insert(make_pair(0, 0));
817  constrainedKeys.insert(make_pair(1, 1));
818  constrainedKeys.insert(make_pair(2, 2));
819  constrainedKeys.insert(make_pair(3, 3));
820  constrainedKeys.insert(make_pair(4, 4));
821  constrainedKeys.insert(make_pair(5, 5));
822 
823  isam.update(factors, values, FactorIndices(), constrainedKeys);
824 
825  FastList<Key> leafKeys {0};
826  EXPECT(checkMarginalizeLeaves(isam, leafKeys));
827 }
828 
829 /* ************************************************************************* */
830 TEST(ISAM2, marginalizeLeaves4) {
831  ISAM2 isam;
832 
834  factors.addPrior(0, 0.0, model);
837 
838  Values values;
839  values.insert(0, 0.0);
840  values.insert(1, 0.0);
841  values.insert(2, 0.0);
842 
843  FastMap<Key, int> constrainedKeys;
844  constrainedKeys.insert(make_pair(0, 0));
845  constrainedKeys.insert(make_pair(1, 1));
846  constrainedKeys.insert(make_pair(2, 2));
847 
848  isam.update(factors, values, FactorIndices(), constrainedKeys);
849 
850  FastList<Key> leafKeys {1};
851  EXPECT(checkMarginalizeLeaves(isam, leafKeys));
852 }
853 
854 /* ************************************************************************* */
855 TEST(ISAM2, marginalizeLeaves5)
856 {
857  // Create isam2
859 
860  // Marginalize
861  FastList<Key> marginalizeKeys {0};
862  EXPECT(checkMarginalizeLeaves(isam, marginalizeKeys));
863 }
864 
865 /* ************************************************************************* */
866 TEST(ISAM2, marginalizeLeaves6)
867 {
868  auto nm = noiseModel::Isotropic::Sigma(6, 1.0);
869 
870  int gridDim = 10;
871 
872  auto idxToKey = [gridDim](int i, int j){return i * gridDim + j;};
873 
875  Values values;
876  ISAM2 isam;
877 
878  // Create a grid of pose variables
879  for (int i = 0; i < gridDim; ++i) {
880  for (int j = 0; j < gridDim; ++j) {
881  Pose3 pose = Pose3(Rot3::Identity(), Point3(i, j, 0));
882  Key key = idxToKey(i, j);
883  // Place a prior on the first pose
884  factors.addPrior(key, Pose3(Rot3::Identity(), Point3(i, j, 0)), nm);
885  values.insert(key, pose);
886  if (i > 0) {
887  factors.emplace_shared<BetweenFactor<Pose3>>(idxToKey(i - 1, j), key, Pose3(Rot3::Identity(), Point3(1, 0, 0)),nm);
888  }
889  if (j > 0) {
890  factors.emplace_shared<BetweenFactor<Pose3>>(idxToKey(i, j - 1), key, Pose3(Rot3::Identity(), Point3(0, 1, 0)),nm);
891  }
892  }
893  }
894 
895  // Optimize the graph
896  EXPECT(updateAndMarginalize(factors, values, {}, isam));
897  auto estimate = isam.calculateBestEstimate();
898 
899  // Get the list of keys
900  std::vector<Key> key_list(gridDim * gridDim);
901  std::iota(key_list.begin(), key_list.end(), 0);
902 
903  // Shuffle the keys -> we will marginalize the keys one by one in this order
904  std::shuffle(key_list.begin(), key_list.end(), std::default_random_engine(1234));
905 
906  for (const auto& key : key_list) {
907  KeySet marginalKeys;
908  marginalKeys.insert(key);
909  EXPECT(updateAndMarginalize({}, {}, marginalKeys, isam));
910  estimate = isam.calculateBestEstimate();
911  }
912 }
913 
914 /* ************************************************************************* */
915 TEST(ISAM2, MarginalizeRoot)
916 {
917  auto nm = noiseModel::Isotropic::Sigma(6, 1.0);
918 
920  Values values;
921  ISAM2 isam;
922 
923  // Create a factor graph with one variable and a prior
924  Pose3 root = Pose3::Identity();
925  Key rootKey(0);
926  values.insert(rootKey, root);
927  factors.addPrior(rootKey, Pose3::Identity(), nm);
928 
929  // Optimize the graph
930  EXPECT(updateAndMarginalize(factors, values, {}, isam));
931  auto estimate = isam.calculateBestEstimate();
932  EXPECT(estimate.size() == 1);
933 
934  // And remove the node from the graph
935  KeySet marginalizableKeys;
936  marginalizableKeys.insert(rootKey);
937 
938  EXPECT(updateAndMarginalize({}, {}, marginalizableKeys, isam));
939 
940  estimate = isam.calculateBestEstimate();
941  EXPECT(estimate.empty());
942 }
943 
944 /* ************************************************************************* */
945 TEST(ISAM2, marginalizationSize)
946 {
947  auto nm = noiseModel::Isotropic::Sigma(6, 1.0);
948 
950  Values values;
952  params.findUnusedFactorSlots = true;
953  ISAM2 isam{params};
954 
955  // Create a pose variable
956  Key aKey(0);
957  values.insert(aKey, Pose3::Identity());
958  factors.addPrior(aKey, Pose3::Identity(), nm);
959  // Create another pose variable linked to the first
960  Pose3 b = Pose3::Identity();
961  Key bKey(1);
962  values.insert(bKey, Pose3::Identity());
963  factors.emplace_shared<BetweenFactor<Pose3>>(aKey, bKey, Pose3::Identity(), nm);
964  // Optimize the graph
965  EXPECT(updateAndMarginalize(factors, values, {}, isam));
966 
967  // Now remove a variable -> we should not see the number of factors increase
968  gtsam::KeySet to_remove;
969  to_remove.insert(aKey);
970  const auto numFactorsBefore = isam.getFactorsUnsafe().size();
971  updateAndMarginalize({}, {}, to_remove, isam);
972  EXPECT(numFactorsBefore == isam.getFactorsUnsafe().size());
973 }
974 
975 /* ************************************************************************* */
976 TEST(ISAM2, marginalCovariance)
977 {
978  // Create isam2
980 
981  // Check marginal
983  Matrix actual = isam.marginalCovariance(5);
984  EXPECT(assert_equal(expected, actual));
985 }
986 
987 /* ************************************************************************* */
988 TEST(ISAM2, calculate_nnz)
989 {
991  int expected = 241;
992  int actual = isam.roots().front()->calculate_nnz();
993 
994  EXPECT_LONGS_EQUAL(expected, actual);
995 }
996 
997 /* ************************************************************************* */
998 int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
999 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::ISAM2Params
Definition: ISAM2Params.h:136
Pose2.h
2D Pose
model
static const SharedNoiseModel model
Definition: testGaussianISAM2.cpp:33
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::ISAM2
Definition: ISAM2.h:45
gtsam::Values::keys
KeyVector keys() const
Definition: Values.cpp:218
gtsam::NonlinearISAM::getFactorsUnsafe
const NonlinearFactorGraph & getFactorsUnsafe() const
Definition: NonlinearISAM.h:81
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
treeTraversal-inst.h
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
b
Scalar * b
Definition: benchVecAdd.cpp:17
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::FastMap
Definition: FastMap.h:39
gtsam::Marginals
Definition: Marginals.h:32
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
brNoise
SharedDiagonal brNoise
Definition: testGaussianISAM2.cpp:41
gtsam::NonlinearFactorGraph::linearize
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Definition: NonlinearFactorGraph.cpp:239
gtsam::EliminateableFactorGraph::marginal
std::shared_ptr< FactorGraphType > marginal(const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Definition: EliminateableFactorGraph-inst.h:440
Ordering.h
Variable ordering for the elimination algorithm.
ConsistencyVisitor::consistent
bool consistent
Definition: testGaussianISAM2.cpp:199
GaussianBayesNet.h
Chordal Bayes Net, the result of eliminating a factor graph.
odoNoise
SharedDiagonal odoNoise
Definition: testGaussianISAM2.cpp:40
gtsam::FastSet< Key >
gtsam::ISAM2::sharedClique
Base::sharedClique sharedClique
Shared pointer to a clique.
Definition: ISAM2.h:103
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::Marginals::marginalCovariance
Matrix marginalCovariance(Key variable) const
Definition: Marginals.cpp:133
gtsam::NonlinearISAM::update
void update(const NonlinearFactorGraph &newFactors, const Values &initialValues)
Definition: NonlinearISAM.cpp:35
TestableAssertions.h
Provides additional testing facilities for common data structures.
Point2.h
2D Point
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::ISAM2DoglegParams
Definition: ISAM2Params.h:68
test
Definition: test.py:1
gtsam::GaussianFactorGraph::gradient
VectorValues gradient(const VectorValues &x0) const
Definition: GaussianFactorGraph.cpp:357
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
createSlamlikeISAM2
ISAM2 createSlamlikeISAM2(Values *init_values=nullptr, NonlinearFactorGraph *full_graph=nullptr, const ISAM2Params &params=ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false, true, ISAM2Params::CHOLESKY, true, DefaultKeyFormatter, true), size_t maxPoses=10)
Definition: testGaussianISAM2.cpp:43
gtsam::Values::retract
Values retract(const VectorValues &delta) const
Definition: Values.cpp:98
data
int data[]
Definition: Map_placement_new.cpp:1
parentData
DATA & parentData
Definition: treeTraversal-inst.h:45
gtsam::VectorValues
Definition: VectorValues.h:74
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
isam_check
bool isam_check(const NonlinearFactorGraph &fullgraph, const Values &fullinit, const ISAM2 &isam, Test &test, TestResult &result)
Definition: testGaussianISAM2.cpp:222
BetweenFactor.h
gtsam::BearingRangeFactor
Definition: sam/BearingRangeFactor.h:34
gtsam::Pose3
Definition: Pose3.h:37
gtsam::GaussianFactorGraph::gradientAtZero
virtual VectorValues gradientAtZero() const
Definition: GaussianFactorGraph.cpp:369
isam
NonlinearISAM isam(relinearizeInterval)
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::treeTraversal::DepthFirstForest
void DepthFirstForest(FOREST &forest, DATA &rootData, VISITOR_PRE &visitorPre, VISITOR_POST &visitorPost)
Definition: treeTraversal-inst.h:77
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::NonlinearFactorGraph::addPrior
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Definition: NonlinearFactorGraph.h:199
gtsam::ISAM2GaussNewtonParams
Definition: ISAM2Params.h:36
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
gtsam::FastList
Definition: FastList.h:43
init
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:1912
ConsistencyVisitor::ConsistencyVisitor
ConsistencyVisitor(const ISAM2 &isam)
Definition: testGaussianISAM2.cpp:201
TestResult
Definition: TestResult.h:26
key
const gtsam::Symbol key('X', 0)
gtsam::FactorGraph::remove
void remove(size_t i)
Definition: FactorGraph.h:371
gtsam::FactorGraph::size
size_t size() const
Definition: FactorGraph.h:297
ISAM2.h
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
gtsam::ISAM2Clique::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: ISAM2Clique.h:41
TEST
TEST(ISAM2, simple)
Definition: testGaussianISAM2.cpp:283
gtsam::GaussianFactorGraph::augmentedHessian
Matrix augmentedHessian(const Ordering &ordering) const
Definition: GaussianFactorGraph.cpp:247
Values
std::vector< float > Values
Definition: sparse_setter.cpp:45
gtsam
traits
Definition: chartTesting.h:28
Marginals.h
A class for computing marginals in a NonlinearFactorGraph.
main
int main()
Definition: testGaussianISAM2.cpp:998
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
leaf::values
leaf::MyValues values
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
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
std
Definition: BFloat16.h:88
gtsam::NonlinearISAM::marginalCovariance
Matrix marginalCovariance(Key key) const
Definition: NonlinearISAM.cpp:88
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
GaussianBayesTree.h
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.
gtsam::testing::between
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::Values::erase
void erase(Key j)
Definition: Values.cpp:210
ConsistencyVisitor::isam
const ISAM2 & isam
Definition: testGaussianISAM2.cpp:200
M_PI
#define M_PI
Definition: mconf.h:117
gtsam::NonlinearISAM::getLinearizationPoint
const Values & getLinearizationPoint() const
Definition: NonlinearISAM.h:78
aKey
Key aKey
Definition: testKey.cpp:29
simple
Definition: testJacobianFactor.cpp:34
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
smallExample.h
Create small example with two poses and one landmark.
init
Definition: TutorialInplaceLU.cpp:2
ConsistencyVisitor
Definition: testGaussianISAM2.cpp:197
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
LONGS_EQUAL
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:134
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Values.h
A non-templated config holding any types of Manifold-group elements.
ConsistencyVisitor::operator()
int operator()(const ISAM2::sharedClique &node, int &parentData)
Definition: testGaussianISAM2.cpp:203
Pose3.h
3D Pose
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
debug.h
Global debugging flags.
gtsam::Pose2
Definition: Pose2.h:39
gtsam::FactorIndices
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:36
BearingRangeFactor.h
a single factor contains both the bearing and the range to prevent handle to pair bearing and range f...
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
gtsam::EliminateQR
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: JacobianFactor.cpp:778


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:09:17