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 #include <cassert>
29 
30 using namespace std;
31 using namespace gtsam;
32 using std::shared_ptr;
33 
34 static const SharedNoiseModel model;
35 
36 // SETDEBUG("ISAM2 update", true);
37 // SETDEBUG("ISAM2 update verbose", true);
38 // SETDEBUG("ISAM2 recalculate", true);
39 
40 // Set up parameters
41 SharedDiagonal odoNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.1, 0.1, M_PI/100.0).finished());
42 SharedDiagonal brNoise = noiseModel::Diagonal::Sigmas((Vector(2) << M_PI/100.0, 0.1).finished());
43 
45  Values* init_values = nullptr,
46  NonlinearFactorGraph* full_graph = nullptr,
48  0, false, true,
49  ISAM2Params::CHOLESKY, true,
50  DefaultKeyFormatter, true),
51  size_t maxPoses = 10) {
52  // These variables will be reused and accumulate factors and values
53  ISAM2 isam(params);
54  Values fullinit;
55  NonlinearFactorGraph fullgraph;
56 
57  // i keeps track of the time step
58  size_t i = 0;
59 
60  // Add a prior at time 0 and update isam
61  {
62  NonlinearFactorGraph newfactors;
63  newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise);
64  fullgraph.push_back(newfactors);
65 
66  Values init;
67  init.insert((0), Pose2(0.01, 0.01, 0.01));
68  fullinit.insert((0), Pose2(0.01, 0.01, 0.01));
69 
70  isam.update(newfactors, init);
71  }
72 
73  if(i > maxPoses)
74  goto done;
75 
76  // Add odometry from time 0 to time 5
77  for( ; i<5; ++i) {
78  NonlinearFactorGraph newfactors;
79  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
80  fullgraph.push_back(newfactors);
81 
82  Values init;
83  init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
84  fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
85 
86  isam.update(newfactors, init);
87 
88  if(i > maxPoses)
89  goto done;
90  }
91 
92  if(i > maxPoses)
93  goto done;
94 
95  // Add odometry from time 5 to 6 and landmark measurement at time 5
96  {
97  NonlinearFactorGraph newfactors;
98  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
99  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise);
100  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise);
101  fullgraph.push_back(newfactors);
102 
103  Values init;
104  init.insert((i+1), Pose2(1.01, 0.01, 0.01));
105  init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
106  init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
107  fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01));
108  fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
109  fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
110 
111  isam.update(newfactors, init);
112  ++ i;
113  }
114 
115  if(i > maxPoses)
116  goto done;
117 
118  // Add odometry from time 6 to time 10
119  for( ; i<10; ++i) {
120  NonlinearFactorGraph newfactors;
121  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
122  fullgraph.push_back(newfactors);
123 
124  Values init;
125  init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
126  fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
127 
128  isam.update(newfactors, init);
129 
130  if(i > maxPoses)
131  goto done;
132  }
133 
134  if(i > maxPoses)
135  goto done;
136 
137  // Add odometry from time 10 to 11 and landmark measurement at time 10
138  {
139  NonlinearFactorGraph newfactors;
140  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
141  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
142  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
143  fullgraph.push_back(newfactors);
144 
145  Values init;
146  init.insert((i+1), Pose2(6.9, 0.1, 0.01));
147  fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01));
148 
149  isam.update(newfactors, init);
150  ++ i;
151  }
152 
153 done:
154 
155  if (full_graph)
156  *full_graph = fullgraph;
157 
158  if (init_values)
159  *init_values = fullinit;
160 
161  return isam;
162 }
163 
164 /* ************************************************************************* */
165 //TEST(ISAM2, CheckRelinearization) {
166 //
167 // typedef GaussianISAM2<Values>::Impl Impl;
168 //
169 // // Create values where indices 1 and 3 are above the threshold of 0.1
170 // VectorValues values;
171 // values.reserve(4, 10);
172 // values.push_back_preallocated(Vector2(0.09, 0.09));
173 // values.push_back_preallocated(Vector3(0.11, 0.11, 0.09));
174 // values.push_back_preallocated(Vector3(0.09, 0.09, 0.09));
175 // values.push_back_preallocated(Vector2(0.11, 0.11));
176 //
177 // // Create a permutation
178 // Permutation permutation(4);
179 // permutation[0] = 2;
180 // permutation[1] = 0;
181 // permutation[2] = 1;
182 // permutation[3] = 3;
183 //
184 // Permuted<VectorValues> permuted(permutation, values);
185 //
186 // // After permutation, the indices above the threshold are 2 and 2
187 // KeySet expected;
188 // expected.insert(2);
189 // expected.insert(3);
190 //
191 // // Indices checked by CheckRelinearization
192 // KeySet actual = Impl::CheckRelinearization(permuted, 0.1);
193 //
194 // EXPECT(assert_equal(expected, actual));
195 //}
196 
197 /* ************************************************************************* */
199 {
201  const ISAM2& isam;
203  consistent(true), isam(isam) {}
205  {
206  if(find(isam.roots().begin(), isam.roots().end(), node) == isam.roots().end())
207  {
208  if(node->parent_.expired())
209  consistent = false;
210  if(find(node->parent()->children.begin(), node->parent()->children.end(), node) == node->parent()->children.end())
211  consistent = false;
212  }
213  for(Key j: node->conditional()->frontals())
214  {
215  if(isam.nodes().at(j).get() != node.get())
216  consistent = false;
217  }
218  return 0;
219  }
220 };
221 
222 /* ************************************************************************* */
223 bool isam_check(const NonlinearFactorGraph& fullgraph, const Values& fullinit, const ISAM2& isam, Test& test, TestResult& result) {
224 
225  TestResult& result_ = result;
226  const string name_ = test.getName();
227 
228  Values actual = isam.calculateEstimate();
229  Values expected = fullinit.retract(fullgraph.linearize(fullinit)->optimize());
230 
231  bool isamEqual = assert_equal(expected, actual);
232 
233  // Check information
234  GaussianFactorGraph isamGraph(isam);
235  isamGraph.push_back(isam.roots().front()->cachedFactor_);
236  Matrix expectedHessian = fullgraph.linearize(isam.getLinearizationPoint())->augmentedHessian();
237  Matrix actualHessian = isamGraph.augmentedHessian();
238  expectedHessian.bottomRightCorner(1,1) = actualHessian.bottomRightCorner(1,1);
239  bool isamTreeEqual = assert_equal(expectedHessian, actualHessian);
240 
241  // Check consistency
242  ConsistencyVisitor visitor(isam);
243  int data; // Unused
245  bool consistent = visitor.consistent;
246 
247  // The following two checks make sure that the cached gradients are maintained and used correctly
248 
249  // Check gradient at each node
250  bool nodeGradientsOk = true;
251  for (const auto& [key, clique] : isam.nodes()) {
252  // Compute expected gradient
254  jfg.push_back(clique->conditional());
255  VectorValues expectedGradient = jfg.gradientAtZero();
256  // Compare with actual gradients
257  DenseIndex variablePosition = 0;
258  for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) {
259  const DenseIndex dim = clique->conditional()->getDim(jit);
260  Vector actual = clique->gradientContribution().segment(variablePosition, dim);
261  bool gradOk = assert_equal(expectedGradient[*jit], actual);
262  EXPECT(gradOk);
263  nodeGradientsOk = nodeGradientsOk && gradOk;
264  variablePosition += dim;
265  }
266  bool dimOk = clique->gradientContribution().rows() == variablePosition;
267  EXPECT(dimOk);
268  nodeGradientsOk = nodeGradientsOk && dimOk;
269  }
270 
271  // Check gradient
272  VectorValues expectedGradient = GaussianFactorGraph(isam).gradientAtZero();
273  VectorValues expectedGradient2 = GaussianFactorGraph(isam).gradient(VectorValues::Zero(expectedGradient));
274  VectorValues actualGradient = isam.gradientAtZero();
275  bool expectedGradOk = assert_equal(expectedGradient2, expectedGradient);
276  EXPECT(expectedGradOk);
277  bool totalGradOk = assert_equal(expectedGradient, actualGradient);
278  EXPECT(totalGradOk);
279 
280  return nodeGradientsOk && expectedGradOk && totalGradOk && isamEqual && isamTreeEqual && consistent;
281 }
282 
283 /* ************************************************************************* */
285 {
286  for(size_t i = 0; i < 10; ++i) {
287  // These variables will be reused and accumulate factors and values
288  Values fullinit;
289  NonlinearFactorGraph fullgraph;
290  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false), i);
291 
292  // Compare solutions
293  EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_));
294  }
295 }
296 
297 /* ************************************************************************* */
298 TEST(ISAM2, slamlike_solution_gaussnewton)
299 {
300  // These variables will be reused and accumulate factors and values
301  Values fullinit;
302  NonlinearFactorGraph fullgraph;
303  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
304 
305  // Compare solutions
306  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
307 }
308 
309 /* ************************************************************************* */
310 TEST(ISAM2, slamlike_solution_dogleg)
311 {
312  // These variables will be reused and accumulate factors and values
313  Values fullinit;
314  NonlinearFactorGraph fullgraph;
315  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false));
316 
317  // Compare solutions
318  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
319 }
320 
321 /* ************************************************************************* */
322 TEST(ISAM2, slamlike_solution_gaussnewton_qr)
323 {
324  // These variables will be reused and accumulate factors and values
325  Values fullinit;
326  NonlinearFactorGraph fullgraph;
327  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false, false, ISAM2Params::QR));
328 
329  // Compare solutions
330  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
331 }
332 
333 /* ************************************************************************* */
334 TEST(ISAM2, slamlike_solution_dogleg_qr)
335 {
336  // These variables will be reused and accumulate factors and values
337  Values fullinit;
338  NonlinearFactorGraph fullgraph;
339  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false, false, ISAM2Params::QR));
340 
341  // Compare solutions
342  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
343 }
344 
345 /* ************************************************************************* */
346 TEST(ISAM2, clone) {
347 
348  ISAM2 clone1;
349 
350  {
352  clone1 = isam;
353 
354  ISAM2 clone2(isam);
355 
356  // Modify original isam
359  isam.calculateEstimate<Pose2>(0).between(isam.calculateEstimate<Pose2>(10)), noiseModel::Unit::Create(3));
361 
363  }
364 
365  // This is to (perhaps unsuccessfully) try to currupt unallocated memory referenced
366  // if the references in the iSAM2 copy point to the old instance which deleted at
367  // the end of the {...} section above.
368  ISAM2 temp = createSlamlikeISAM2();
369 
371  CHECK(assert_equal(clone1, temp));
372 
373  // Check clone empty
374  ISAM2 isam;
375  clone1 = isam;
376  CHECK(assert_equal(ISAM2(), clone1));
377 }
378 
379 /* ************************************************************************* */
380 TEST(ISAM2, removeFactors)
381 {
382  // This test builds a graph in the same way as the "slamlike" test above, but
383  // then removes the 2nd-to-last landmark measurement
384 
385  // These variables will be reused and accumulate factors and values
386  Values fullinit;
387  NonlinearFactorGraph fullgraph;
388  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
389 
390  // Remove the 2nd measurement on landmark 0 (Key 100)
391  FactorIndices toRemove;
392  toRemove.push_back(12);
393  isam.update(NonlinearFactorGraph(), Values(), toRemove);
394 
395  // Remove the factor from the full system
396  fullgraph.remove(12);
397 
398  // Compare solutions
399  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
400 }
401 
402 /* ************************************************************************* */
403 TEST(ISAM2, removeVariables)
404 {
405  // These variables will be reused and accumulate factors and values
406  Values fullinit;
407  NonlinearFactorGraph fullgraph;
408  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
409 
410  // Remove the measurement on landmark 0 (Key 100)
411  FactorIndices toRemove;
412  toRemove.push_back(7);
413  toRemove.push_back(14);
414  isam.update(NonlinearFactorGraph(), Values(), toRemove);
415 
416  // Remove the factors and variable from the full system
417  fullgraph.remove(7);
418  fullgraph.remove(14);
419  fullinit.erase(100);
420 
421  // Compare solutions
422  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
423 }
424 
425 /* ************************************************************************* */
426 TEST(ISAM2, swapFactors)
427 {
428  // This test builds a graph in the same way as the "slamlike" test above, but
429  // then swaps the 2nd-to-last landmark measurement with a different one
430 
431  Values fullinit;
432  NonlinearFactorGraph fullgraph;
433  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph);
434 
435  // Remove the measurement on landmark 0 and replace with a different one
436  {
437  size_t swap_idx = isam.getFactorsUnsafe().size()-2;
438  FactorIndices toRemove;
439  toRemove.push_back(swap_idx);
440  fullgraph.remove(swap_idx);
441 
442  NonlinearFactorGraph swapfactors;
443 // swapfactors += BearingRange<Pose2,Point2>(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise; // original factor
444  swapfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 5.0, brNoise);
445  fullgraph.push_back(swapfactors);
446  isam.update(swapfactors, Values(), toRemove);
447  }
448 
449  // Compare solutions
451  EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_));
452 
453  // Check gradient at each node
454  for (const auto& [key, clique]: isam.nodes()) {
455  // Compute expected gradient
457  jfg.push_back(clique->conditional());
458  VectorValues expectedGradient = jfg.gradientAtZero();
459  // Compare with actual gradients
460  DenseIndex variablePosition = 0;
461  for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) {
462  const DenseIndex dim = clique->conditional()->getDim(jit);
463  Vector actual = clique->gradientContribution().segment(variablePosition, dim);
464  EXPECT(assert_equal(expectedGradient[*jit], actual));
465  variablePosition += dim;
466  }
467  EXPECT_LONGS_EQUAL((long)clique->gradientContribution().rows(), (long)variablePosition);
468  }
469 
470  // Check gradient
471  VectorValues expectedGradient = GaussianFactorGraph(isam).gradientAtZero();
472  VectorValues expectedGradient2 = GaussianFactorGraph(isam).gradient(VectorValues::Zero(expectedGradient));
473  VectorValues actualGradient = isam.gradientAtZero();
474  EXPECT(assert_equal(expectedGradient2, expectedGradient));
475  EXPECT(assert_equal(expectedGradient, actualGradient));
476 }
477 
478 /* ************************************************************************* */
479 TEST(ISAM2, constrained_ordering)
480 {
481  // These variables will be reused and accumulate factors and values
482  ISAM2 isam(ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
483  Values fullinit;
484  NonlinearFactorGraph fullgraph;
485 
486  // We will constrain x3 and x4 to the end
487  FastMap<Key, int> constrained;
488  constrained.insert(make_pair((3), 1));
489  constrained.insert(make_pair((4), 2));
490 
491  // i keeps track of the time step
492  size_t i = 0;
493 
494  // Add a prior at time 0 and update isam
495  {
496  NonlinearFactorGraph newfactors;
497  newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise);
498  fullgraph.push_back(newfactors);
499 
500  Values init;
501  init.insert((0), Pose2(0.01, 0.01, 0.01));
502  fullinit.insert((0), Pose2(0.01, 0.01, 0.01));
503 
504  isam.update(newfactors, init);
505  }
506 
507  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
508 
509  // Add odometry from time 0 to time 5
510  for( ; i<5; ++i) {
511  NonlinearFactorGraph newfactors;
512  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
513  fullgraph.push_back(newfactors);
514 
515  Values init;
516  init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
517  fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
518 
519  if(i >= 3)
520  isam.update(newfactors, init, FactorIndices(), constrained);
521  else
522  isam.update(newfactors, init);
523  }
524 
525  // Add odometry from time 5 to 6 and landmark measurement at time 5
526  {
527  NonlinearFactorGraph newfactors;
528  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
529  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise);
530  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise);
531  fullgraph.push_back(newfactors);
532 
533  Values init;
534  init.insert((i+1), Pose2(1.01, 0.01, 0.01));
535  init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
536  init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
537  fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01));
538  fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
539  fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
540 
541  isam.update(newfactors, init, FactorIndices(), constrained);
542  ++ i;
543  }
544 
545  // Add odometry from time 6 to time 10
546  for( ; i<10; ++i) {
547  NonlinearFactorGraph newfactors;
548  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
549  fullgraph.push_back(newfactors);
550 
551  Values init;
552  init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
553  fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
554 
555  isam.update(newfactors, init, FactorIndices(), constrained);
556  }
557 
558  // Add odometry from time 10 to 11 and landmark measurement at time 10
559  {
560  NonlinearFactorGraph newfactors;
561  newfactors.emplace_shared<BetweenFactor<Pose2>>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
562  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
563  newfactors.emplace_shared<BearingRangeFactor<Pose2, Point2>>(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
564  fullgraph.push_back(newfactors);
565 
566  Values init;
567  init.insert((i+1), Pose2(6.9, 0.1, 0.01));
568  fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01));
569 
570  isam.update(newfactors, init, FactorIndices(), constrained);
571  ++ i;
572  }
573 
574  // Compare solutions
575  EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_));
576 
577  // Check gradient at each node
578  for (const auto& [key, clique]: isam.nodes()) {
579  // Compute expected gradient
581  jfg.push_back(clique->conditional());
582  VectorValues expectedGradient = jfg.gradientAtZero();
583  // Compare with actual gradients
584  DenseIndex variablePosition = 0;
585  for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) {
586  const DenseIndex dim = clique->conditional()->getDim(jit);
587  Vector actual = clique->gradientContribution().segment(variablePosition, dim);
588  EXPECT(assert_equal(expectedGradient[*jit], actual));
589  variablePosition += dim;
590  }
591  LONGS_EQUAL((long)clique->gradientContribution().rows(), (long)variablePosition);
592  }
593 
594  // Check gradient
595  VectorValues expectedGradient = GaussianFactorGraph(isam).gradientAtZero();
596  VectorValues expectedGradient2 = GaussianFactorGraph(isam).gradient(VectorValues::Zero(expectedGradient));
597  VectorValues actualGradient = isam.gradientAtZero();
598  EXPECT(assert_equal(expectedGradient2, expectedGradient));
599  EXPECT(assert_equal(expectedGradient, actualGradient));
600 }
601 
602 /* ************************************************************************* */
603 TEST(ISAM2, slamlike_solution_partial_relinearization_check)
604 {
605  // These variables will be reused and accumulate factors and values
606  Values fullinit;
607  NonlinearFactorGraph fullgraph;
608  ISAM2Params params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false);
609  params.enablePartialRelinearizationCheck = true;
610  ISAM2 isam = createSlamlikeISAM2(&fullinit, &fullgraph, params);
611 
612  // Compare solutions
613  CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
614 }
615 
616 namespace {
617  bool checkMarginalizeLeaves(ISAM2& isam, const FastList<Key>& leafKeys) {
618  Matrix expectedAugmentedHessian, expected3AugmentedHessian;
619  KeyVector toKeep;
620  for (const auto& [key, clique]: isam.getDelta()) {
621  if(find(leafKeys.begin(), leafKeys.end(), key) == leafKeys.end()) {
622  toKeep.push_back(key);
623  }
624  }
625 
626  // Calculate expected marginal from iSAM2 tree
627  expectedAugmentedHessian = GaussianFactorGraph(isam).marginal(toKeep, EliminateQR)->augmentedHessian();
628 
629  // Calculate expected marginal from cached linear factors
630  //assert(isam.params().cacheLinearizedFactors);
631  //Matrix expected2AugmentedHessian = isam.linearFactors_.marginal(toKeep, EliminateQR)->augmentedHessian();
632 
633  // Calculate expected marginal from original nonlinear factors
634  expected3AugmentedHessian = isam.getFactorsUnsafe().linearize(isam.getLinearizationPoint())
635  ->marginal(toKeep, EliminateQR)->augmentedHessian();
636 
637  // Do marginalization
638  isam.marginalizeLeaves(leafKeys);
639 
640  // Check
641  GaussianFactorGraph actualMarginalGraph(isam);
642  Matrix actualAugmentedHessian = actualMarginalGraph.augmentedHessian();
643  //Matrix actual2AugmentedHessian = linearFactors_.augmentedHessian();
644  Matrix actual3AugmentedHessian = isam.getFactorsUnsafe().linearize(
645  isam.getLinearizationPoint())->augmentedHessian();
646  assert(actualAugmentedHessian.allFinite());
647 
648  // Check full marginalization
649  //cout << "treeEqual" << endl;
650  bool treeEqual = assert_equal(expectedAugmentedHessian, actualAugmentedHessian, 1e-6);
651  //actualAugmentedHessian.bottomRightCorner(1,1) = expected2AugmentedHessian.bottomRightCorner(1,1); bool linEqual = assert_equal(expected2AugmentedHessian, actualAugmentedHessian, 1e-6);
652  //cout << "nonlinEqual" << endl;
653  actualAugmentedHessian.bottomRightCorner(1,1) = expected3AugmentedHessian.bottomRightCorner(1,1); bool nonlinEqual = assert_equal(expected3AugmentedHessian, actualAugmentedHessian, 1e-6);
654  //bool linCorrect = assert_equal(expected3AugmentedHessian, expected2AugmentedHessian, 1e-6);
655  //actual2AugmentedHessian.bottomRightCorner(1,1) = expected3AugmentedHessian.bottomRightCorner(1,1); bool afterLinCorrect = assert_equal(expected3AugmentedHessian, actual2AugmentedHessian, 1e-6);
656  //cout << "nonlinCorrect" << endl;
657  bool afterNonlinCorrect = assert_equal(expected3AugmentedHessian, actual3AugmentedHessian, 1e-6);
658 
659  bool ok = treeEqual && /*linEqual &&*/ nonlinEqual && /*linCorrect &&*/ /*afterLinCorrect &&*/ afterNonlinCorrect;
660  return ok;
661  }
662 
663  std::optional<FastMap<Key, int>> createOrderingConstraints(const ISAM2& isam, const KeyVector& newKeys, const KeySet& marginalizableKeys)
664  {
665  if (marginalizableKeys.empty()) {
666  return {};
667  } else {
668  FastMap<Key, int> constrainedKeys = FastMap<Key, int>();
669  // Generate ordering constraints so that the marginalizable variables will be eliminated first
670  // Set all existing and new variables to Group1
671  for (const auto& key_val : isam.getDelta()) {
672  constrainedKeys.emplace(key_val.first, 1);
673  }
674  for (const auto& key : newKeys) {
675  constrainedKeys.emplace(key, 1);
676  }
677  // And then re-assign the marginalizable variables to Group0 so that they'll all be leaf nodes
678  for (const auto& key : marginalizableKeys) {
679  constrainedKeys.at(key) = 0;
680  }
681  return constrainedKeys;
682  }
683  }
684 
685  void markAffectedKeys(const Key& key, const ISAM2Clique::shared_ptr& rootClique, KeyList& additionalKeys)
686  {
687  std::stack<ISAM2Clique::shared_ptr> frontier;
688  frontier.push(rootClique);
689  // Basic DFS to find additional keys
690  while (!frontier.empty()) {
691  // Get the top of the stack
692  const ISAM2Clique::shared_ptr clique = frontier.top();
693  frontier.pop();
694  // Check if we have more keys and children to add
695  if (std::find(clique->conditional()->beginParents(), clique->conditional()->endParents(), key) !=
696  clique->conditional()->endParents()) {
697  for (Key i : clique->conditional()->frontals()) {
698  additionalKeys.push_back(i);
699  }
700  for (const ISAM2Clique::shared_ptr& child : clique->children) {
701  frontier.push(child);
702  }
703  }
704  }
705  }
706 
707  bool updateAndMarginalize(const NonlinearFactorGraph& newFactors, const Values& newValues, const KeySet& marginalizableKeys, ISAM2& isam)
708  {
709  // Force ISAM2 to put marginalizable variables at the beginning
710  auto orderingConstraints = createOrderingConstraints(isam, newValues.keys(), marginalizableKeys);
711 
712  // Mark additional keys between the marginalized keys and the leaves
713  KeyList markedKeys;
714  for (Key key : marginalizableKeys) {
715  markedKeys.push_back(key);
716  ISAM2Clique::shared_ptr clique = isam[key];
717  for (const ISAM2Clique::shared_ptr& child : clique->children) {
718  markAffectedKeys(key, child, markedKeys);
719  }
720  }
721 
722  // Update
723  isam.update(newFactors, newValues, FactorIndices{}, orderingConstraints, {}, markedKeys);
724 
725  if (!marginalizableKeys.empty()) {
726  FastList<Key> leafKeys(marginalizableKeys.begin(), marginalizableKeys.end());
727  return checkMarginalizeLeaves(isam, leafKeys);
728  }
729  else {
730  return true;
731  }
732  }
733 }
734 
735 /* ************************************************************************* */
736 TEST(ISAM2, marginalizeLeaves1) {
737  ISAM2 isam;
739  factors.addPrior(0, 0.0, model);
740 
744 
745  Values values;
746  values.insert(0, 0.0);
747  values.insert(1, 0.0);
748  values.insert(2, 0.0);
749 
750  FastMap<Key, int> constrainedKeys;
751  constrainedKeys.insert(make_pair(0, 0));
752  constrainedKeys.insert(make_pair(1, 1));
753  constrainedKeys.insert(make_pair(2, 2));
754 
755  isam.update(factors, values, FactorIndices(), constrainedKeys);
756 
757  FastList<Key> leafKeys {0};
758  EXPECT(checkMarginalizeLeaves(isam, leafKeys));
759 }
760 
761 /* ************************************************************************* */
762 TEST(ISAM2, marginalizeLeaves2) {
763  ISAM2 isam;
764 
766  factors.addPrior(0, 0.0, model);
767 
772 
773  Values values;
774  values.insert(0, 0.0);
775  values.insert(1, 0.0);
776  values.insert(2, 0.0);
777  values.insert(3, 0.0);
778 
779  FastMap<Key, int> constrainedKeys;
780  constrainedKeys.insert(make_pair(0, 0));
781  constrainedKeys.insert(make_pair(1, 1));
782  constrainedKeys.insert(make_pair(2, 2));
783  constrainedKeys.insert(make_pair(3, 3));
784 
785  isam.update(factors, values, FactorIndices(), constrainedKeys);
786 
787  FastList<Key> leafKeys {0};
788  EXPECT(checkMarginalizeLeaves(isam, leafKeys));
789 }
790 
791 /* ************************************************************************* */
792 TEST(ISAM2, marginalizeLeaves3) {
793  ISAM2 isam;
794 
796  factors.addPrior(0, 0.0, model);
797 
801 
803 
807 
808  Values values;
809  values.insert(0, 0.0);
810  values.insert(1, 0.0);
811  values.insert(2, 0.0);
812  values.insert(3, 0.0);
813  values.insert(4, 0.0);
814  values.insert(5, 0.0);
815 
816  FastMap<Key, int> constrainedKeys;
817  constrainedKeys.insert(make_pair(0, 0));
818  constrainedKeys.insert(make_pair(1, 1));
819  constrainedKeys.insert(make_pair(2, 2));
820  constrainedKeys.insert(make_pair(3, 3));
821  constrainedKeys.insert(make_pair(4, 4));
822  constrainedKeys.insert(make_pair(5, 5));
823 
824  isam.update(factors, values, FactorIndices(), constrainedKeys);
825 
826  FastList<Key> leafKeys {0};
827  EXPECT(checkMarginalizeLeaves(isam, leafKeys));
828 }
829 
830 /* ************************************************************************* */
831 TEST(ISAM2, marginalizeLeaves4) {
832  ISAM2 isam;
833 
835  factors.addPrior(0, 0.0, model);
838 
839  Values values;
840  values.insert(0, 0.0);
841  values.insert(1, 0.0);
842  values.insert(2, 0.0);
843 
844  FastMap<Key, int> constrainedKeys;
845  constrainedKeys.insert(make_pair(0, 0));
846  constrainedKeys.insert(make_pair(1, 1));
847  constrainedKeys.insert(make_pair(2, 2));
848 
849  isam.update(factors, values, FactorIndices(), constrainedKeys);
850 
851  FastList<Key> leafKeys {1};
852  EXPECT(checkMarginalizeLeaves(isam, leafKeys));
853 }
854 
855 /* ************************************************************************* */
856 TEST(ISAM2, marginalizeLeaves5)
857 {
858  // Create isam2
860 
861  // Marginalize
862  FastList<Key> marginalizeKeys {0};
863  EXPECT(checkMarginalizeLeaves(isam, marginalizeKeys));
864 }
865 
866 /* ************************************************************************* */
867 TEST(ISAM2, marginalizeLeaves6)
868 {
869  auto nm = noiseModel::Isotropic::Sigma(6, 1.0);
870 
871  int gridDim = 10;
872 
873  auto idxToKey = [gridDim](int i, int j){return i * gridDim + j;};
874 
876  Values values;
877  ISAM2 isam;
878 
879  // Create a grid of pose variables
880  for (int i = 0; i < gridDim; ++i) {
881  for (int j = 0; j < gridDim; ++j) {
882  Pose3 pose = Pose3(Rot3::Identity(), Point3(i, j, 0));
883  Key key = idxToKey(i, j);
884  // Place a prior on the first pose
885  factors.addPrior(key, Pose3(Rot3::Identity(), Point3(i, j, 0)), nm);
886  values.insert(key, pose);
887  if (i > 0) {
888  factors.emplace_shared<BetweenFactor<Pose3>>(idxToKey(i - 1, j), key, Pose3(Rot3::Identity(), Point3(1, 0, 0)),nm);
889  }
890  if (j > 0) {
891  factors.emplace_shared<BetweenFactor<Pose3>>(idxToKey(i, j - 1), key, Pose3(Rot3::Identity(), Point3(0, 1, 0)),nm);
892  }
893  }
894  }
895 
896  // Optimize the graph
897  EXPECT(updateAndMarginalize(factors, values, {}, isam));
898  auto estimate = isam.calculateBestEstimate();
899 
900  // Get the list of keys
901  std::vector<Key> key_list(gridDim * gridDim);
902  std::iota(key_list.begin(), key_list.end(), 0);
903 
904  // Shuffle the keys -> we will marginalize the keys one by one in this order
905  std::shuffle(key_list.begin(), key_list.end(), std::default_random_engine(1234));
906 
907  for (const auto& key : key_list) {
908  KeySet marginalKeys;
909  marginalKeys.insert(key);
910  EXPECT(updateAndMarginalize({}, {}, marginalKeys, isam));
911  estimate = isam.calculateBestEstimate();
912  }
913 }
914 
915 /* ************************************************************************* */
916 TEST(ISAM2, MarginalizeRoot)
917 {
918  auto nm = noiseModel::Isotropic::Sigma(6, 1.0);
919 
921  Values values;
922  ISAM2 isam;
923 
924  // Create a factor graph with one variable and a prior
925  Pose3 root = Pose3::Identity();
926  Key rootKey(0);
927  values.insert(rootKey, root);
928  factors.addPrior(rootKey, Pose3::Identity(), nm);
929 
930  // Optimize the graph
931  EXPECT(updateAndMarginalize(factors, values, {}, isam));
932  auto estimate = isam.calculateBestEstimate();
933  EXPECT(estimate.size() == 1);
934 
935  // And remove the node from the graph
936  KeySet marginalizableKeys;
937  marginalizableKeys.insert(rootKey);
938 
939  EXPECT(updateAndMarginalize({}, {}, marginalizableKeys, isam));
940 
941  estimate = isam.calculateBestEstimate();
942  EXPECT(estimate.empty());
943 }
944 
945 /* ************************************************************************* */
946 TEST(ISAM2, marginalizationSize)
947 {
948  auto nm = noiseModel::Isotropic::Sigma(6, 1.0);
949 
951  Values values;
953  params.findUnusedFactorSlots = true;
954  ISAM2 isam{params};
955 
956  // Create a pose variable
957  Key aKey(0);
958  values.insert(aKey, Pose3::Identity());
959  factors.addPrior(aKey, Pose3::Identity(), nm);
960  // Create another pose variable linked to the first
961  Pose3 b = Pose3::Identity();
962  Key bKey(1);
963  values.insert(bKey, Pose3::Identity());
964  factors.emplace_shared<BetweenFactor<Pose3>>(aKey, bKey, Pose3::Identity(), nm);
965  // Optimize the graph
966  EXPECT(updateAndMarginalize(factors, values, {}, isam));
967 
968  // Now remove a variable -> we should not see the number of factors increase
969  gtsam::KeySet to_remove;
970  to_remove.insert(aKey);
971  const auto numFactorsBefore = isam.getFactorsUnsafe().size();
972  updateAndMarginalize({}, {}, to_remove, isam);
973  EXPECT(numFactorsBefore == isam.getFactorsUnsafe().size());
974 }
975 
976 /* ************************************************************************* */
977 TEST(ISAM2, marginalCovariance)
978 {
979  // Create isam2
981 
982  // Check marginal
984  Matrix actual = isam.marginalCovariance(5);
985  EXPECT(assert_equal(expected, actual));
986 }
987 
988 /* ************************************************************************* */
989 TEST(ISAM2, calculate_nnz)
990 {
992  int expected = 241;
993  int actual = isam.roots().front()->calculate_nnz();
994 
995  EXPECT_LONGS_EQUAL(expected, actual);
996 }
997 
998 class FixActiveFactor : public NoiseModelFactorN<Vector2> {
1001 
1002 public:
1003  FixActiveFactor(const gtsam::Key& key, const bool active)
1004  : Base(nullptr, key), is_active_(active) {}
1005 
1006  virtual bool active(const gtsam::Values &values) const override {
1007  return is_active_;
1008  }
1009 
1010  virtual Vector
1012  Base::OptionalMatrixTypeT<Vector2> H = nullptr) const override {
1013  if (H) {
1014  *H = Vector2::Identity();
1015  }
1016  return Vector2::Zero();
1017  }
1018 };
1019 
1020 TEST(ActiveFactorTesting, Issue1596) {
1021  // Issue1596: When a derived Nonlinear Factor is not active, the linearization returns a nullptr (NonlinearFactor.cpp:156), which
1022  // causes an error when `EliminateSymbolic` is called (SymbolicFactor-inst.h:45) due to not checking if the factor is nullptr.
1023  const gtsam::Key key{Symbol('x', 0)};
1024 
1025  ISAM2 isam;
1026  Values values;
1028 
1029  // Insert an active factor
1030  values.insert<Vector2>(key, Vector2::Zero());
1032 
1033  // No problem here
1034  isam.update(graph, values);
1035 
1037 
1038  // Inserting a factor that is never active
1040 
1041  // This call throws the error if the pointer is not validated on (SymbolicFactor-inst.h:45)
1042  isam.update(graph);
1043 
1044  // If the bug is fixed, this line is reached.
1045  EXPECT(isam.getFactorsUnsafe().size() == 2);
1046 }
1047 
1048 /* ************************************************************************* */
1050 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
H
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Definition: gnuplot_common_settings.hh:74
gtsam::ISAM2Params
Definition: ISAM2Params.h:136
Pose2.h
2D Pose
model
static const SharedNoiseModel model
Definition: testGaussianISAM2.cpp:34
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:219
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
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
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:42
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
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.
gtsam::Factor
Definition: Factor.h:70
ConsistencyVisitor::consistent
bool consistent
Definition: testGaussianISAM2.cpp:200
GaussianBayesNet.h
Chordal Bayes Net, the result of eliminating a factor graph.
odoNoise
SharedDiagonal odoNoise
Definition: testGaussianISAM2.cpp:41
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:39
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
FixActiveFactor::active
virtual bool active(const gtsam::Values &values) const override
Definition: testGaussianISAM2.cpp:1006
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:44
gtsam::Values::retract
Values retract(const VectorValues &delta) const
Definition: Values.cpp:99
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:223
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::NoiseModelFactorN
Definition: NonlinearFactor.h:432
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:764
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
FixActiveFactor::is_active_
bool is_active_
Definition: testGaussianISAM2.cpp:1000
gtsam::HybridValues::insert
void insert(Key j, const Vector &value)
Definition: HybridValues.cpp:85
Vector2
Definition: test_operator_overloading.cpp:18
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::FastList
Definition: FastList.h:43
init
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:2006
ConsistencyVisitor::ConsistencyVisitor
ConsistencyVisitor(const ISAM2 &isam)
Definition: testGaussianISAM2.cpp:202
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:284
gtsam::GaussianFactorGraph::augmentedHessian
Matrix augmentedHessian(const Ordering &ordering) const
Definition: GaussianFactorGraph.cpp:247
FixActiveFactor
Definition: testGaussianISAM2.cpp:998
Values
std::vector< float > Values
Definition: sparse_setter.cpp:45
gtsam
traits
Definition: SFMdata.h:40
Marginals.h
A class for computing marginals in a NonlinearFactorGraph.
main
int main()
Definition: testGaussianISAM2.cpp:1049
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
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:156
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:41
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::Values::erase
void erase(Key j)
Definition: Values.cpp:211
ConsistencyVisitor::isam
const ISAM2 & isam
Definition: testGaussianISAM2.cpp:201
FixActiveFactor::evaluateError
virtual Vector evaluateError(const Vector2 &x, Base::OptionalMatrixTypeT< Vector2 > H=nullptr) const override
Definition: testGaussianISAM2.cpp:1011
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
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
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:198
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:204
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
FixActiveFactor::FixActiveFactor
FixActiveFactor(const gtsam::Key &key, const bool active)
Definition: testGaussianISAM2.cpp:1003
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::Symbol
Definition: inference/Symbol.h:37
gtsam::FactorIndices
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:37
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:779


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