testHybridGaussianISAM.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
22 #include <gtsam/geometry/Pose2.h>
29 
30 #include <numeric>
31 
32 #include "Switching.h"
33 
34 // Include for test suite
36 
37 using namespace std;
38 using namespace gtsam;
46 
47 /* ****************************************************************************/
48 // Test if we can perform elimination incrementally.
49 TEST(HybridGaussianElimination, IncrementalElimination) {
50  Switching switching(3);
53 
54  // Create initial factor graph
55  // * * *
56  // | | |
57  // X0 -*- X1 -*- X2
58  // \*-M0-*/
59  graph1.push_back(switching.linearizedFactorGraph.at(0)); // P(X0)
60  graph1.push_back(switching.linearizedFactorGraph.at(1)); // P(X0, X1 | M0)
61  graph1.push_back(switching.linearizedFactorGraph.at(2)); // P(X1, X2 | M1)
62  graph1.push_back(switching.linearizedFactorGraph.at(5)); // P(M0)
63 
64  // Run update step
65  isam.update(graph1);
66 
67  // Check that after update we have 2 hybrid Bayes net nodes:
68  // P(X0 | X1, M0) and P(X1, X2 | M0, M1), P(M0, M1)
69  EXPECT_LONGS_EQUAL(3, isam.size());
70  EXPECT(isam[X(0)]->conditional()->frontals() == KeyVector{X(0)});
71  EXPECT(isam[X(0)]->conditional()->parents() == KeyVector({X(1), M(0)}));
72  EXPECT(isam[X(1)]->conditional()->frontals() == KeyVector({X(1), X(2)}));
73  EXPECT(isam[X(1)]->conditional()->parents() == KeyVector({M(0), M(1)}));
74 
75  /********************************************************/
76  // New factor graph for incremental update.
78 
79  graph1.push_back(switching.linearizedFactorGraph.at(3)); // P(X1)
80  graph2.push_back(switching.linearizedFactorGraph.at(4)); // P(X2)
81  graph2.push_back(switching.linearizedFactorGraph.at(6)); // P(M0, M1)
82 
83  isam.update(graph2);
84 
85  // Check that after the second update we have
86  // 1 additional hybrid Bayes net node:
87  // P(X1, X2 | M0, M1)
88  EXPECT_LONGS_EQUAL(3, isam.size());
89  EXPECT(isam[X(2)]->conditional()->frontals() == KeyVector({X(1), X(2)}));
90  EXPECT(isam[X(2)]->conditional()->parents() == KeyVector({M(0), M(1)}));
91 }
92 
93 /* ****************************************************************************/
94 // Test if we can incrementally do the inference
95 TEST(HybridGaussianElimination, IncrementalInference) {
96  Switching switching(3);
99 
100  // Create initial factor graph
101  // * * *
102  // | | |
103  // X0 -*- X1 -*- X2
104  // | |
105  // *-M0 - * - M1
106  graph1.push_back(switching.linearizedFactorGraph.at(0)); // P(X0)
107  graph1.push_back(switching.linearizedFactorGraph.at(1)); // P(X0, X1 | M0)
108  graph1.push_back(switching.linearizedFactorGraph.at(3)); // P(X1)
109  graph1.push_back(switching.linearizedFactorGraph.at(5)); // P(M0)
110 
111  // Run update step
112  isam.update(graph1);
113 
114  auto discreteConditional_m0 = isam[M(0)]->conditional()->asDiscrete();
115  EXPECT(discreteConditional_m0->keys() == KeyVector({M(0)}));
116 
117  /********************************************************/
118  // New factor graph for incremental update.
120 
121  graph2.push_back(switching.linearizedFactorGraph.at(2)); // P(X1, X2 | M1)
122  graph2.push_back(switching.linearizedFactorGraph.at(4)); // P(X2)
123  graph2.push_back(switching.linearizedFactorGraph.at(6)); // P(M0, M1)
124 
125  isam.update(graph2);
126 
127  /********************************************************/
128  // Run batch elimination so we can compare results.
129  const Ordering ordering {X(0), X(1), X(2)};
130 
131  // Now we calculate the expected factors using full elimination
132  const auto [expectedHybridBayesTree, expectedRemainingGraph] =
134 
135  // The densities on X(0) should be the same
136  auto x0_conditional =
137  dynamic_pointer_cast<GaussianMixture>(isam[X(0)]->conditional()->inner());
138  auto expected_x0_conditional = dynamic_pointer_cast<GaussianMixture>(
139  (*expectedHybridBayesTree)[X(0)]->conditional()->inner());
140  EXPECT(assert_equal(*x0_conditional, *expected_x0_conditional));
141 
142  // The densities on X(1) should be the same
143  auto x1_conditional =
144  dynamic_pointer_cast<GaussianMixture>(isam[X(1)]->conditional()->inner());
145  auto expected_x1_conditional = dynamic_pointer_cast<GaussianMixture>(
146  (*expectedHybridBayesTree)[X(1)]->conditional()->inner());
147  EXPECT(assert_equal(*x1_conditional, *expected_x1_conditional));
148 
149  // The densities on X(2) should be the same
150  auto x2_conditional =
151  dynamic_pointer_cast<GaussianMixture>(isam[X(2)]->conditional()->inner());
152  auto expected_x2_conditional = dynamic_pointer_cast<GaussianMixture>(
153  (*expectedHybridBayesTree)[X(2)]->conditional()->inner());
154  EXPECT(assert_equal(*x2_conditional, *expected_x2_conditional));
155 
156  // We only perform manual continuous elimination for 0,0.
157  // The other discrete probabilities on M(2) are calculated the same way
158  const Ordering discreteOrdering{M(0), M(1)};
159  HybridBayesTree::shared_ptr discreteBayesTree =
160  expectedRemainingGraph->BaseEliminateable::eliminateMultifrontal(
161  discreteOrdering);
162 
163  DiscreteValues m00;
164  m00[M(0)] = 0, m00[M(1)] = 0;
165  DiscreteConditional decisionTree =
166  *(*discreteBayesTree)[M(1)]->conditional()->asDiscrete();
167  double m00_prob = decisionTree(m00);
168 
169  auto discreteConditional = isam[M(1)]->conditional()->asDiscrete();
170 
171  // Test the probability values with regression tests.
172  DiscreteValues assignment;
173  EXPECT(assert_equal(0.0952922, m00_prob, 1e-5));
174  assignment[M(0)] = 0;
175  assignment[M(1)] = 0;
176  EXPECT(assert_equal(0.0952922, (*discreteConditional)(assignment), 1e-5));
177  assignment[M(0)] = 1;
178  assignment[M(1)] = 0;
179  EXPECT(assert_equal(0.282758, (*discreteConditional)(assignment), 1e-5));
180  assignment[M(0)] = 0;
181  assignment[M(1)] = 1;
182  EXPECT(assert_equal(0.314175, (*discreteConditional)(assignment), 1e-5));
183  assignment[M(0)] = 1;
184  assignment[M(1)] = 1;
185  EXPECT(assert_equal(0.307775, (*discreteConditional)(assignment), 1e-5));
186 
187  // Check if the clique conditional generated from incremental elimination
188  // matches that of batch elimination.
189  auto expectedChordal =
190  expectedRemainingGraph->BaseEliminateable::eliminateMultifrontal();
191  auto actualConditional = dynamic_pointer_cast<DecisionTreeFactor>(
192  isam[M(1)]->conditional()->inner());
193  // Account for the probability terms from evaluating continuous FGs
194  DiscreteKeys discrete_keys = {{M(0), 2}, {M(1), 2}};
195  vector<double> probs = {0.095292197, 0.31417524, 0.28275772, 0.30777485};
196  auto expectedConditional =
197  std::make_shared<DecisionTreeFactor>(discrete_keys, probs);
198  EXPECT(assert_equal(*expectedConditional, *actualConditional, 1e-6));
199 }
200 
201 /* ****************************************************************************/
202 // Test if we can approximately do the inference
203 TEST(HybridGaussianElimination, Approx_inference) {
204  Switching switching(4);
205  HybridGaussianISAM incrementalHybrid;
207 
208  // Add the 3 hybrid factors, x0-x1, x1-x2, x2-x3
209  for (size_t i = 1; i < 4; i++) {
210  graph1.push_back(switching.linearizedFactorGraph.at(i));
211  }
212 
213  // Add the Gaussian factors, 1 prior on X(0),
214  // 3 measurements on X(1), X(2), X(3)
215  graph1.push_back(switching.linearizedFactorGraph.at(0));
216  for (size_t i = 4; i <= 7; i++) {
217  graph1.push_back(switching.linearizedFactorGraph.at(i));
218  }
219 
220  // Create ordering.
222  for (size_t j = 0; j < 4; j++) {
223  ordering.push_back(X(j));
224  }
225 
226  // Now we calculate the actual factors using full elimination
227  const auto [unprunedHybridBayesTree, unprunedRemainingGraph] =
229 
230  size_t maxNrLeaves = 5;
231  incrementalHybrid.update(graph1);
232 
233  incrementalHybrid.prune(maxNrLeaves);
234 
235  /*
236  unpruned factor is:
237  Choice(m3)
238  0 Choice(m2)
239  0 0 Choice(m1)
240  0 0 0 Leaf 0.11267528
241  0 0 1 Leaf 0.18576102
242  0 1 Choice(m1)
243  0 1 0 Leaf 0.18754662
244  0 1 1 Leaf 0.30623871
245  1 Choice(m2)
246  1 0 Choice(m1)
247  1 0 0 Leaf 0.18576102
248  1 0 1 Leaf 0.30622428
249  1 1 Choice(m1)
250  1 1 0 Leaf 0.30623871
251  1 1 1 Leaf 0.5
252 
253  pruned factors is:
254  Choice(m3)
255  0 Choice(m2)
256  0 0 Leaf 0
257  0 1 Choice(m1)
258  0 1 0 Leaf 0.18754662
259  0 1 1 Leaf 0.30623871
260  1 Choice(m2)
261  1 0 Choice(m1)
262  1 0 0 Leaf 0
263  1 0 1 Leaf 0.30622428
264  1 1 Choice(m1)
265  1 1 0 Leaf 0.30623871
266  1 1 1 Leaf 0.5
267  */
268 
269  auto discreteConditional_m0 = *dynamic_pointer_cast<DiscreteConditional>(
270  incrementalHybrid[M(0)]->conditional()->inner());
271  EXPECT(discreteConditional_m0.keys() == KeyVector({M(0), M(1), M(2)}));
272 
273  // Get the number of elements which are greater than 0.
274  auto count = [](const double &value, int count) {
275  return value > 0 ? count + 1 : count;
276  };
277  // Check that the number of leaves after pruning is 5.
278  EXPECT_LONGS_EQUAL(5, discreteConditional_m0.fold(count, 0));
279 
280  // Check that the hybrid nodes of the bayes net match those of the pre-pruning
281  // bayes net, at the same positions.
282  auto &unprunedLastDensity = *dynamic_pointer_cast<GaussianMixture>(
283  unprunedHybridBayesTree->clique(X(3))->conditional()->inner());
284  auto &lastDensity = *dynamic_pointer_cast<GaussianMixture>(
285  incrementalHybrid[X(3)]->conditional()->inner());
286 
287  std::vector<std::pair<DiscreteValues, double>> assignments =
288  discreteConditional_m0.enumerate();
289  // Loop over all assignments and check the pruned components
290  for (auto &&av : assignments) {
291  const DiscreteValues &assignment = av.first;
292  const double value = av.second;
293 
294  if (value == 0.0) {
295  EXPECT(lastDensity(assignment) == nullptr);
296  } else {
297  CHECK(lastDensity(assignment));
298  EXPECT(assert_equal(*unprunedLastDensity(assignment),
299  *lastDensity(assignment)));
300  }
301  }
302 }
303 
304 /* ****************************************************************************/
305 // Test approximate inference with an additional pruning step.
306 TEST(HybridGaussianElimination, Incremental_approximate) {
307  Switching switching(5);
308  HybridGaussianISAM incrementalHybrid;
310 
311  /***** Run Round 1 *****/
312  // Add the 3 hybrid factors, x0-x1, x1-x2, x2-x3
313  for (size_t i = 1; i < 4; i++) {
314  graph1.push_back(switching.linearizedFactorGraph.at(i));
315  }
316 
317  // Add the Gaussian factors, 1 prior on X(0),
318  // 3 measurements on X(1), X(2), X(3)
319  graph1.push_back(switching.linearizedFactorGraph.at(0));
320  for (size_t i = 5; i <= 7; i++) {
321  graph1.push_back(switching.linearizedFactorGraph.at(i));
322  }
323 
324  // Run update with pruning
325  size_t maxComponents = 5;
326  incrementalHybrid.update(graph1);
327  incrementalHybrid.prune(maxComponents);
328 
329  // Check if we have a bayes tree with 4 hybrid nodes,
330  // each with 2, 4, 8, and 5 (pruned) leaves respetively.
331  EXPECT_LONGS_EQUAL(4, incrementalHybrid.size());
333  2, incrementalHybrid[X(0)]->conditional()->asMixture()->nrComponents());
335  3, incrementalHybrid[X(1)]->conditional()->asMixture()->nrComponents());
337  5, incrementalHybrid[X(2)]->conditional()->asMixture()->nrComponents());
339  5, incrementalHybrid[X(3)]->conditional()->asMixture()->nrComponents());
340 
341  /***** Run Round 2 *****/
343  graph2.push_back(switching.linearizedFactorGraph.at(4));
344  graph2.push_back(switching.linearizedFactorGraph.at(8));
345 
346  // Run update with pruning a second time.
347  incrementalHybrid.update(graph2);
348  incrementalHybrid.prune(maxComponents);
349 
350  // Check if we have a bayes tree with pruned hybrid nodes,
351  // with 5 (pruned) leaves.
352  CHECK_EQUAL(5, incrementalHybrid.size());
354  5, incrementalHybrid[X(3)]->conditional()->asMixture()->nrComponents());
356  5, incrementalHybrid[X(4)]->conditional()->asMixture()->nrComponents());
357 }
358 
359 /* ************************************************************************/
360 // A GTSAM-only test for running inference on a single-legged robot.
361 // The leg links are represented by the chain X-Y-Z-W, where X is the base and
362 // W is the foot.
363 // We use BetweenFactor<Pose2> as constraints between each of the poses.
364 TEST(HybridGaussianISAM, NonTrivial) {
365  /*************** Run Round 1 ***************/
367 
368  // Add a prior on pose x0 at the origin.
369  // A prior factor consists of a mean and
370  // a noise model (covariance matrix)
371  Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
372  auto priorNoise = noiseModel::Diagonal::Sigmas(
373  Vector3(0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
375 
376  // create a noise model for the landmark measurements
377  auto poseNoise = noiseModel::Isotropic::Sigma(3, 0.1);
378 
379  // We model a robot's single leg as X - Y - Z - W
380  // where X is the base link and W is the foot link.
381 
382  // Add connecting poses similar to PoseFactors in GTD
383  fg.emplace_shared<BetweenFactor<Pose2>>(X(0), Y(0), Pose2(0, 1.0, 0),
384  poseNoise);
385  fg.emplace_shared<BetweenFactor<Pose2>>(Y(0), Z(0), Pose2(0, 1.0, 0),
386  poseNoise);
387  fg.emplace_shared<BetweenFactor<Pose2>>(Z(0), W(0), Pose2(0, 1.0, 0),
388  poseNoise);
389 
390  // Create initial estimate
391  Values initial;
392  initial.insert(X(0), Pose2(0.0, 0.0, 0.0));
393  initial.insert(Y(0), Pose2(0.0, 1.0, 0.0));
394  initial.insert(Z(0), Pose2(0.0, 2.0, 0.0));
395  initial.insert(W(0), Pose2(0.0, 3.0, 0.0));
396 
397  HybridGaussianFactorGraph gfg = *fg.linearize(initial);
399 
400  HybridGaussianISAM inc;
401 
402  // Update without pruning
403  // The result is a HybridBayesNet with no discrete variables
404  // (equivalent to a GaussianBayesNet).
405  // Factorization is:
406  // `P(X | measurements) = P(W0|Z0) P(Z0|Y0) P(Y0|X0) P(X0)`
407  inc.update(gfg);
408 
409  /*************** Run Round 2 ***************/
410  using PlanarMotionModel = BetweenFactor<Pose2>;
411 
412  // Add odometry factor with discrete modes.
413  Pose2 odometry(1.0, 0.0, 0.0);
414  KeyVector contKeys = {W(0), W(1)};
415  auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
416  auto still = std::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, 0),
417  noise_model),
418  moving = std::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
419  noise_model);
420  std::vector<PlanarMotionModel::shared_ptr> components = {moving, still};
421  auto mixtureFactor = std::make_shared<MixtureFactor>(
422  contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components);
423  fg.push_back(mixtureFactor);
424 
425  // Add equivalent of ImuFactor
426  fg.emplace_shared<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0, 0),
427  poseNoise);
428  // PoseFactors-like at k=1
429  fg.emplace_shared<BetweenFactor<Pose2>>(X(1), Y(1), Pose2(0, 1, 0),
430  poseNoise);
431  fg.emplace_shared<BetweenFactor<Pose2>>(Y(1), Z(1), Pose2(0, 1, 0),
432  poseNoise);
433  fg.emplace_shared<BetweenFactor<Pose2>>(Z(1), W(1), Pose2(-1, 1, 0),
434  poseNoise);
435 
436  initial.insert(X(1), Pose2(1.0, 0.0, 0.0));
437  initial.insert(Y(1), Pose2(1.0, 1.0, 0.0));
438  initial.insert(Z(1), Pose2(1.0, 2.0, 0.0));
439  // The leg link did not move so we set the expected pose accordingly.
440  initial.insert(W(1), Pose2(0.0, 3.0, 0.0));
441 
442  gfg = *fg.linearize(initial);
444 
445  // Update without pruning
446  // The result is a HybridBayesNet with 1 discrete variable M(1).
447  // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1)
448  // P(X0 | X1, W1, M1) P(W1|Z1, X1, M1) P(Z1|Y1, X1, M1)
449  // P(Y1 | X1, M1)P(X1 | M1)P(M1)
450  // The MHS tree is a 1 level tree for time indices (1,) with 2 leaves.
451  inc.update(gfg);
452 
453  /*************** Run Round 3 ***************/
454  // Add odometry factor with discrete modes.
455  contKeys = {W(1), W(2)};
456  still = std::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
457  noise_model);
458  moving =
459  std::make_shared<PlanarMotionModel>(W(1), W(2), odometry, noise_model);
460  components = {moving, still};
461  mixtureFactor = std::make_shared<MixtureFactor>(
462  contKeys, DiscreteKeys{gtsam::DiscreteKey(M(2), 2)}, components);
463  fg.push_back(mixtureFactor);
464 
465  // Add equivalent of ImuFactor
466  fg.emplace_shared<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0, 0),
467  poseNoise);
468  // PoseFactors-like at k=1
469  fg.emplace_shared<BetweenFactor<Pose2>>(X(2), Y(2), Pose2(0, 1, 0),
470  poseNoise);
471  fg.emplace_shared<BetweenFactor<Pose2>>(Y(2), Z(2), Pose2(0, 1, 0),
472  poseNoise);
473  fg.emplace_shared<BetweenFactor<Pose2>>(Z(2), W(2), Pose2(-2, 1, 0),
474  poseNoise);
475 
476  initial.insert(X(2), Pose2(2.0, 0.0, 0.0));
477  initial.insert(Y(2), Pose2(2.0, 1.0, 0.0));
478  initial.insert(Z(2), Pose2(2.0, 2.0, 0.0));
479  initial.insert(W(2), Pose2(0.0, 3.0, 0.0));
480 
481  gfg = *fg.linearize(initial);
483 
484  // Now we prune!
485  // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1)
486  // P(X0 | X1, W1, M1) P(W1|W2, Z1, X1, M1, M2)
487  // P(Z1| W2, Y1, X1, M1, M2) P(Y1 | W2, X1, M1, M2)
488  // P(X1 | W2, X2, M1, M2) P(W2|Z2, X2, M1, M2)
489  // P(Z2|Y2, X2, M1, M2) P(Y2 | X2, M1, M2)
490  // P(X2 | M1, M2) P(M1, M2)
491  // The MHS at this point should be a 2 level tree on (1, 2).
492  // 1 has 2 choices, and 2 has 4 choices.
493  inc.update(gfg);
494  inc.prune(2);
495 
496  /*************** Run Round 4 ***************/
497  // Add odometry factor with discrete modes.
498  contKeys = {W(2), W(3)};
499  still = std::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
500  noise_model);
501  moving =
502  std::make_shared<PlanarMotionModel>(W(2), W(3), odometry, noise_model);
503  components = {moving, still};
504  mixtureFactor = std::make_shared<MixtureFactor>(
505  contKeys, DiscreteKeys{gtsam::DiscreteKey(M(3), 2)}, components);
506  fg.push_back(mixtureFactor);
507 
508  // Add equivalent of ImuFactor
509  fg.emplace_shared<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0, 0),
510  poseNoise);
511  // PoseFactors-like at k=3
512  fg.emplace_shared<BetweenFactor<Pose2>>(X(3), Y(3), Pose2(0, 1, 0),
513  poseNoise);
514  fg.emplace_shared<BetweenFactor<Pose2>>(Y(3), Z(3), Pose2(0, 1, 0),
515  poseNoise);
516  fg.emplace_shared<BetweenFactor<Pose2>>(Z(3), W(3), Pose2(-3, 1, 0),
517  poseNoise);
518 
519  initial.insert(X(3), Pose2(3.0, 0.0, 0.0));
520  initial.insert(Y(3), Pose2(3.0, 1.0, 0.0));
521  initial.insert(Z(3), Pose2(3.0, 2.0, 0.0));
522  initial.insert(W(3), Pose2(0.0, 3.0, 0.0));
523 
524  gfg = *fg.linearize(initial);
526 
527  // Keep pruning!
528  inc.update(gfg);
529  inc.prune(3);
530 
531  // The final discrete graph should not be empty since we have eliminated
532  // all continuous variables.
533  auto discreteTree = inc[M(3)]->conditional()->asDiscrete();
534  EXPECT_LONGS_EQUAL(3, discreteTree->size());
535 
536  // Test if the optimal discrete mode assignment is (1, 1, 1).
537  DiscreteFactorGraph discreteGraph;
538  discreteGraph.push_back(discreteTree);
539  DiscreteValues optimal_assignment = discreteGraph.optimize();
540 
541  DiscreteValues expected_assignment;
542  expected_assignment[M(1)] = 1;
543  expected_assignment[M(2)] = 1;
544  expected_assignment[M(3)] = 1;
545 
546  EXPECT(assert_equal(expected_assignment, optimal_assignment));
547 
548  // Test if pruning worked correctly by checking that we only have 3 leaves in
549  // the last node.
550  auto lastConditional = inc[X(3)]->conditional()->asMixture();
551  EXPECT_LONGS_EQUAL(3, lastConditional->nrComponents());
552 }
553 
554 /* ************************************************************************* */
555 int main() {
556  TestResult tr;
557  return TestRegistry::runAllTests(tr);
558 }
#define CHECK(condition)
Definition: Test.h:108
const char Y
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51
std::pair< std::shared_ptr< BayesTreeType >, std::shared_ptr< FactorGraphType > > eliminatePartialMultifrontal(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
size_t size() const
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:88
void update(const HybridGaussianFactorGraph &newFactors, const std::optional< size_t > &maxNrLeaves={}, const std::optional< Ordering > &ordering={}, const HybridBayesTree::Eliminate &function=HybridBayesTree::EliminationTraitsType::DefaultEliminate)
Perform update step with new factors.
std::shared_ptr< This > shared_ptr
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:190
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Values initial
MatrixXd L
Definition: LLT_example.cpp:6
Definition: BFloat16.h:88
Key W(std::uint64_t j)
static enum @1107 ordering
void prune(const size_t maxNumberLeaves)
Prune the underlying Bayes tree.
HybridGaussianFactorGraph linearizedFactorGraph
Definition: Switching.h:124
#define Z
Definition: icosphere.cpp:21
A conditional of gaussian mixtures indexed by discrete variables, as part of a Bayes Network...
#define EXPECT(condition)
Definition: Test.h:150
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearISAM isam(relinearizeInterval)
Linear Factor Graph where all factors are Gaussians.
NonlinearFactorGraph graph2()
traits
Definition: chartTesting.h:28
auto priorNoise
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:343
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std::shared_ptr< HybridGaussianFactorGraph > linearize(const Values &continuousValues) const
Linearize all the continuous factors in the HybridNonlinearFactorGraph.
Chordal Bayes Net, the result of eliminating a factor graph.
Pose2 odometry(2.0, 0.0, 0.0)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
2D Pose
#define X
Definition: icosphere.cpp:20
TEST(HybridGaussianElimination, IncrementalElimination)
std::ptrdiff_t j
#define CHECK_EQUAL(expected, actual)
Definition: Test.h:131
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:38:22