testHybridNonlinearISAM.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(HybridNonlinearISAM, IncrementalElimination) {
54 
55  // Create initial factor graph
56  // * * *
57  // | | |
58  // X0 -*- X1 -*- X2
59  // \*-M0-*/
61  graph.push_back(switching.binaryFactors.at(0)); // P(X0, X1 | M0)
62  graph.push_back(switching.binaryFactors.at(1)); // P(X1, X2 | M1)
63  graph.push_back(switching.modeChain.at(0)); // P(M0)
64 
65  initial.insert<double>(X(0), 1);
66  initial.insert<double>(X(1), 2);
67  initial.insert<double>(X(2), 3);
68 
69  // Run update step
71 
72  // Check that after update we have 3 hybrid Bayes net nodes:
73  // P(X0 | X1, M0) and P(X1, X2 | M0, M1), P(M0, M1)
74  HybridGaussianISAM bayesTree = isam.bayesTree();
75  EXPECT_LONGS_EQUAL(3, bayesTree.size());
76  EXPECT(bayesTree[X(0)]->conditional()->frontals() == KeyVector{X(0)});
77  EXPECT(bayesTree[X(0)]->conditional()->parents() == KeyVector({X(1), M(0)}));
78  EXPECT(bayesTree[X(1)]->conditional()->frontals() == KeyVector({X(1), X(2)}));
79  EXPECT(bayesTree[X(1)]->conditional()->parents() == KeyVector({M(0), M(1)}));
80 
81  /********************************************************/
82  // New factor graph for incremental update.
84  initial = Values();
85 
88  graph.push_back(switching.modeChain.at(1)); // P(M0, M1)
89 
91 
92  bayesTree = isam.bayesTree();
93  // Check that after the second update we have
94  // 1 additional hybrid Bayes net node:
95  // P(X1, X2 | M0, M1)
96  EXPECT_LONGS_EQUAL(3, bayesTree.size());
97  EXPECT(bayesTree[X(2)]->conditional()->frontals() == KeyVector({X(1), X(2)}));
98  EXPECT(bayesTree[X(2)]->conditional()->parents() == KeyVector({M(0), M(1)}));
99 }
100 
101 /* ****************************************************************************/
102 // Test if we can incrementally do the inference
103 TEST(HybridNonlinearISAM, IncrementalInference) {
104  Switching switching(3);
107  Values initial;
108 
109  // Create initial factor graph
110  // * * *
111  // | | |
112  // X0 -*- X1 -*- X2
113  // | |
114  // *-M0 - * - M1
115  graph.push_back(switching.unaryFactors.at(0)); // P(X0)
116  graph.push_back(switching.binaryFactors.at(0)); // P(X0, X1 | M0)
117  graph.push_back(switching.unaryFactors.at(1)); // P(X1)
118  graph.push_back(switching.modeChain.at(0)); // P(M0)
119 
120  initial.insert<double>(X(0), 1);
121  initial.insert<double>(X(1), 2);
122 
123  // Run update step
125  HybridGaussianISAM bayesTree = isam.bayesTree();
126 
127  auto discreteConditional_m0 = bayesTree[M(0)]->conditional()->asDiscrete();
128  EXPECT(discreteConditional_m0->keys() == KeyVector({M(0)}));
129 
130  /********************************************************/
131  // New factor graph for incremental update.
133  initial = Values();
134 
135  initial.insert<double>(X(2), 3);
136 
137  graph.push_back(switching.binaryFactors.at(1)); // P(X1, X2 | M1)
138  graph.push_back(switching.unaryFactors.at(2)); // P(X2)
139  graph.push_back(switching.modeChain.at(1)); // P(M0, M1)
140 
142  bayesTree = isam.bayesTree();
143 
144  /********************************************************/
145  // Run batch elimination so we can compare results.
146  const Ordering ordering{X(0), X(1), X(2)};
147 
148  // Now we calculate the actual factors using full elimination
149  const auto [expectedHybridBayesTree, expectedRemainingGraph] =
151  .BaseEliminateable::eliminatePartialMultifrontal(ordering);
152 
153  // The densities on X(1) should be the same
154  auto x0_conditional = dynamic_pointer_cast<HybridGaussianConditional>(
155  bayesTree[X(0)]->conditional()->inner());
156  auto expected_x0_conditional =
157  dynamic_pointer_cast<HybridGaussianConditional>(
158  (*expectedHybridBayesTree)[X(0)]->conditional()->inner());
159  EXPECT(assert_equal(*x0_conditional, *expected_x0_conditional));
160 
161  // The densities on X(1) should be the same
162  auto x1_conditional = dynamic_pointer_cast<HybridGaussianConditional>(
163  bayesTree[X(1)]->conditional()->inner());
164  auto expected_x1_conditional =
165  dynamic_pointer_cast<HybridGaussianConditional>(
166  (*expectedHybridBayesTree)[X(1)]->conditional()->inner());
167  EXPECT(assert_equal(*x1_conditional, *expected_x1_conditional));
168 
169  // The densities on X(2) should be the same
170  auto x2_conditional = dynamic_pointer_cast<HybridGaussianConditional>(
171  bayesTree[X(2)]->conditional()->inner());
172  auto expected_x2_conditional =
173  dynamic_pointer_cast<HybridGaussianConditional>(
174  (*expectedHybridBayesTree)[X(2)]->conditional()->inner());
175  EXPECT(assert_equal(*x2_conditional, *expected_x2_conditional));
176 
177  // We only perform manual continuous elimination for 0,0.
178  // The other discrete probabilities on M(2) are calculated the same way
179  const Ordering discreteOrdering{M(0), M(1)};
180  HybridBayesTree::shared_ptr discreteBayesTree =
181  expectedRemainingGraph->eliminateMultifrontal(discreteOrdering);
182 
183  // Test the probability values with regression tests.
184  auto discrete = bayesTree[M(1)]->conditional()->asDiscrete();
185  EXPECT(assert_equal(0.095292, (*discrete)({{M(0), 0}, {M(1), 0}}), 1e-5));
186  EXPECT(assert_equal(0.282758, (*discrete)({{M(0), 1}, {M(1), 0}}), 1e-5));
187  EXPECT(assert_equal(0.314175, (*discrete)({{M(0), 0}, {M(1), 1}}), 1e-5));
188  EXPECT(assert_equal(0.307775, (*discrete)({{M(0), 1}, {M(1), 1}}), 1e-5));
189 
190  // Check that the clique conditional generated from incremental elimination
191  // matches that of batch elimination.
192  auto expectedConditional = (*discreteBayesTree)[M(1)]->conditional();
193  auto actualConditional = bayesTree[M(1)]->conditional();
194  EXPECT(assert_equal(*expectedConditional, *actualConditional, 1e-6));
195 }
196 
197 /* ****************************************************************************/
198 // Test if we can approximately do the inference (using pruning)
199 TEST(HybridNonlinearISAM, ApproxInference) {
200  Switching switching(4);
201  HybridNonlinearISAM incrementalHybrid;
203  Values initial;
204 
205  // Add the 3 hybrid factors, x0-x1, x1-x2, x2-x3
206  for (size_t i = 0; i < 3; i++) {
208  }
209 
210  // Add the Gaussian factors, 1 prior on X(0),
211  // 3 measurements on X(1), X(2), X(3)
212  for (size_t i = 0; i < 4; i++) {
214  initial.insert<double>(X(i), i + 1);
215  }
216 
217  // Create ordering.
219  for (size_t j = 0; j < 4; j++) {
220  ordering.push_back(X(j));
221  }
222 
223  // Now we calculate the actual factors using full elimination
224  const auto [unPrunedHybridBayesTree, unPrunedRemainingGraph] =
226  .BaseEliminateable::eliminatePartialMultifrontal(ordering);
227 
228  size_t maxNrLeaves = 5;
229  incrementalHybrid.update(graph, initial);
230  HybridGaussianISAM bayesTree = incrementalHybrid.bayesTree();
231 
232  bayesTree.prune(maxNrLeaves);
233 
234  /*
235  unPruned factor is:
236  Choice(m3)
237  0 Choice(m2)
238  0 0 Choice(m1)
239  0 0 0 Leaf 0.11267528
240  0 0 1 Leaf 0.18576102
241  0 1 Choice(m1)
242  0 1 0 Leaf 0.18754662
243  0 1 1 Leaf 0.30623871
244  1 Choice(m2)
245  1 0 Choice(m1)
246  1 0 0 Leaf 0.18576102
247  1 0 1 Leaf 0.30622428
248  1 1 Choice(m1)
249  1 1 0 Leaf 0.30623871
250  1 1 1 Leaf 0.5
251 
252  pruned factors is:
253  Choice(m3)
254  0 Choice(m2)
255  0 0 Leaf 0
256  0 1 Choice(m1)
257  0 1 0 Leaf 0.18754662
258  0 1 1 Leaf 0.30623871
259  1 Choice(m2)
260  1 0 Choice(m1)
261  1 0 0 Leaf 0
262  1 0 1 Leaf 0.30622428
263  1 1 Choice(m1)
264  1 1 0 Leaf 0.30623871
265  1 1 1 Leaf 0.5
266  */
267 
268  auto discreteConditional_m0 = *dynamic_pointer_cast<DiscreteConditional>(
269  bayesTree[M(0)]->conditional()->inner());
270  EXPECT(discreteConditional_m0.keys() == KeyVector({M(0), M(1), M(2)}));
271 
272  // Get the number of elements which are greater than 0.
273  auto count = [](const double &value, int count) {
274  return value > 0 ? count + 1 : count;
275  };
276  // Check that the number of leaves after pruning is 5.
277  EXPECT_LONGS_EQUAL(5, discreteConditional_m0.fold(count, 0));
278 
279  // Check that the hybrid nodes of the bayes net match those of the pre-pruning
280  // bayes net, at the same positions.
281  auto &unPrunedLastDensity = *dynamic_pointer_cast<HybridGaussianConditional>(
282  unPrunedHybridBayesTree->clique(X(3))->conditional()->inner());
283  auto &lastDensity = *dynamic_pointer_cast<HybridGaussianConditional>(
284  bayesTree[X(3)]->conditional()->inner());
285 
286  std::vector<std::pair<DiscreteValues, double>> assignments =
287  discreteConditional_m0.enumerate();
288  // Loop over all assignments and check the pruned components
289  for (auto &&av : assignments) {
290  const DiscreteValues &assignment = av.first;
291  const double value = av.second;
292 
293  if (value == 0.0) {
294  EXPECT(lastDensity(assignment) == nullptr);
295  } else {
296  CHECK(lastDensity(assignment));
297  EXPECT(assert_equal(*unPrunedLastDensity(assignment),
298  *lastDensity(assignment)));
299  }
300  }
301 }
302 
303 /* ****************************************************************************/
304 // Test approximate inference with an additional pruning step.
305 TEST(HybridNonlinearISAM, IncrementalApproximate) {
306  Switching switching(5);
307  HybridNonlinearISAM incrementalHybrid;
309  Values initial;
310 
311  /***** Run Round 1 *****/
312  // Add the 3 hybrid factors, x0-x1, x1-x2, x2-x3
313  for (size_t i = 0; i < 3; i++) {
315  }
316 
317  // Add the Gaussian factors, 1 prior on X(0),
318  // 3 measurements on X(1), X(2), X(3)
319  for (size_t i = 0; i < 4; i++) {
321  initial.insert<double>(X(i), i + 1);
322  }
323 
324  // TODO(Frank): no mode chain?
325 
326  // Run update with pruning
327  size_t maxComponents = 5;
328  incrementalHybrid.update(graph, initial);
329  incrementalHybrid.prune(maxComponents);
330  HybridGaussianISAM bayesTree = incrementalHybrid.bayesTree();
331 
332  // Check if we have a bayes tree with 4 hybrid nodes,
333  // each with 2, 4, 8, and 5 (pruned) leaves respetively.
334  EXPECT_LONGS_EQUAL(4, bayesTree.size());
336  2, bayesTree[X(0)]->conditional()->asHybrid()->nrComponents());
338  3, bayesTree[X(1)]->conditional()->asHybrid()->nrComponents());
340  5, bayesTree[X(2)]->conditional()->asHybrid()->nrComponents());
342  5, bayesTree[X(3)]->conditional()->asHybrid()->nrComponents());
343 
344  /***** Run Round 2 *****/
347  graph.push_back(switching.unaryFactors.at(4)); // x4 measurement
348  initial = Values();
349  initial.insert<double>(X(4), 5);
350 
351  // Run update with pruning a second time.
352  incrementalHybrid.update(graph, initial);
353  incrementalHybrid.prune(maxComponents);
354  bayesTree = incrementalHybrid.bayesTree();
355 
356  // Check if we have a bayes tree with pruned hybrid nodes,
357  // with 5 (pruned) leaves.
358  CHECK_EQUAL(5, bayesTree.size());
360  5, bayesTree[X(3)]->conditional()->asHybrid()->nrComponents());
362  5, bayesTree[X(4)]->conditional()->asHybrid()->nrComponents());
363 }
364 
365 /* ************************************************************************/
366 // A GTSAM-only test for running inference on a single-legged robot.
367 // The leg links are represented by the chain X-Y-Z-W, where X is the base and
368 // W is the foot.
369 // We use BetweenFactor<Pose2> as constraints between each of the poses.
370 TEST(HybridNonlinearISAM, NonTrivial) {
371  /*************** Run Round 1 ***************/
374 
375  // Add a prior on pose x0 at the origin.
376  // A prior factor consists of a mean and
377  // a noise model (covariance matrix)
378  Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
379  auto priorNoise = noiseModel::Diagonal::Sigmas(
380  Vector3(0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
382 
383  // create a noise model for the landmark measurements
384  auto poseNoise = noiseModel::Isotropic::Sigma(3, 0.1);
385 
386  // We model a robot's single leg as X - Y - Z - W
387  // where X is the base link and W is the foot link.
388 
389  // Add connecting poses similar to PoseFactors in GTD
390  fg.emplace_shared<BetweenFactor<Pose2>>(X(0), Y(0), Pose2(0, 1.0, 0),
391  poseNoise);
392  fg.emplace_shared<BetweenFactor<Pose2>>(Y(0), Z(0), Pose2(0, 1.0, 0),
393  poseNoise);
394  fg.emplace_shared<BetweenFactor<Pose2>>(Z(0), W(0), Pose2(0, 1.0, 0),
395  poseNoise);
396 
397  // Create initial estimate
398  Values initial;
399  initial.insert(X(0), Pose2(0.0, 0.0, 0.0));
400  initial.insert(Y(0), Pose2(0.0, 1.0, 0.0));
401  initial.insert(Z(0), Pose2(0.0, 2.0, 0.0));
402  initial.insert(W(0), Pose2(0.0, 3.0, 0.0));
403 
404  // Don't run update now since we don't have discrete variables involved.
405 
406  using PlanarMotionModel = BetweenFactor<Pose2>;
407 
408  /*************** Run Round 2 ***************/
409  // Add odometry factor with discrete modes.
410  Pose2 odometry(1.0, 0.0, 0.0);
411  auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
412  auto still = std::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, 0),
413  noise_model),
414  moving = std::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
415  noise_model);
416  std::vector<NoiseModelFactor::shared_ptr> components{moving, still};
418 
419  // Add equivalent of ImuFactor
420  fg.emplace_shared<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0, 0),
421  poseNoise);
422  // PoseFactors-like at k=1
423  fg.emplace_shared<BetweenFactor<Pose2>>(X(1), Y(1), Pose2(0, 1, 0),
424  poseNoise);
425  fg.emplace_shared<BetweenFactor<Pose2>>(Y(1), Z(1), Pose2(0, 1, 0),
426  poseNoise);
427  fg.emplace_shared<BetweenFactor<Pose2>>(Z(1), W(1), Pose2(-1, 1, 0),
428  poseNoise);
429 
430  initial.insert(X(1), Pose2(1.0, 0.0, 0.0));
431  initial.insert(Y(1), Pose2(1.0, 1.0, 0.0));
432  initial.insert(Z(1), Pose2(1.0, 2.0, 0.0));
433  // The leg link did not move so we set the expected pose accordingly.
434  initial.insert(W(1), Pose2(0.0, 3.0, 0.0));
435 
436  // Update without pruning
437  // The result is a HybridBayesNet with 1 discrete variable M(1).
438  // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1)
439  // P(X0 | X1, W1, M1) P(W1|Z1, X1, M1) P(Z1|Y1, X1, M1)
440  // P(Y1 | X1, M1)P(X1 | M1)P(M1)
441  // The MHS tree is a 1 level tree for time indices (1,) with 2 leaves.
442  inc.update(fg, initial);
443 
445  initial = Values();
446 
447  /*************** Run Round 3 ***************/
448  // Add odometry factor with discrete modes.
449  still = std::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
450  noise_model);
451  moving =
452  std::make_shared<PlanarMotionModel>(W(1), W(2), odometry, noise_model);
453  components = {moving, still};
455 
456  // Add equivalent of ImuFactor
457  fg.emplace_shared<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0, 0),
458  poseNoise);
459  // PoseFactors-like at k=1
460  fg.emplace_shared<BetweenFactor<Pose2>>(X(2), Y(2), Pose2(0, 1, 0),
461  poseNoise);
462  fg.emplace_shared<BetweenFactor<Pose2>>(Y(2), Z(2), Pose2(0, 1, 0),
463  poseNoise);
464  fg.emplace_shared<BetweenFactor<Pose2>>(Z(2), W(2), Pose2(-2, 1, 0),
465  poseNoise);
466 
467  initial.insert(X(2), Pose2(2.0, 0.0, 0.0));
468  initial.insert(Y(2), Pose2(2.0, 1.0, 0.0));
469  initial.insert(Z(2), Pose2(2.0, 2.0, 0.0));
470  initial.insert(W(2), Pose2(0.0, 3.0, 0.0));
471 
472  // Now we prune!
473  // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1)
474  // P(X0 | X1, W1, M1) P(W1|W2, Z1, X1, M1, M2)
475  // P(Z1| W2, Y1, X1, M1, M2) P(Y1 | W2, X1, M1, M2)
476  // P(X1 | W2, X2, M1, M2) P(W2|Z2, X2, M1, M2)
477  // P(Z2|Y2, X2, M1, M2) P(Y2 | X2, M1, M2)
478  // P(X2 | M1, M2) P(M1, M2)
479  // The MHS at this point should be a 2 level tree on (1, 2).
480  // 1 has 2 choices, and 2 has 4 choices.
481  inc.update(fg, initial);
482  inc.prune(2);
483 
485  initial = Values();
486 
487  /*************** Run Round 4 ***************/
488  // Add odometry factor with discrete modes.
489  still = std::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
490  noise_model);
491  moving =
492  std::make_shared<PlanarMotionModel>(W(2), W(3), odometry, noise_model);
493  components = {moving, still};
495 
496  // Add equivalent of ImuFactor
497  fg.emplace_shared<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0, 0),
498  poseNoise);
499  // PoseFactors-like at k=3
500  fg.emplace_shared<BetweenFactor<Pose2>>(X(3), Y(3), Pose2(0, 1, 0),
501  poseNoise);
502  fg.emplace_shared<BetweenFactor<Pose2>>(Y(3), Z(3), Pose2(0, 1, 0),
503  poseNoise);
504  fg.emplace_shared<BetweenFactor<Pose2>>(Z(3), W(3), Pose2(-3, 1, 0),
505  poseNoise);
506 
507  initial.insert(X(3), Pose2(3.0, 0.0, 0.0));
508  initial.insert(Y(3), Pose2(3.0, 1.0, 0.0));
509  initial.insert(Z(3), Pose2(3.0, 2.0, 0.0));
510  initial.insert(W(3), Pose2(0.0, 3.0, 0.0));
511 
512  // Keep pruning!
513  inc.update(fg, initial);
514  inc.prune(3);
515 
517  initial = Values();
518 
519  HybridGaussianISAM bayesTree = inc.bayesTree();
520 
521  // The final discrete graph should not be empty since we have eliminated
522  // all continuous variables.
523  auto discreteTree = bayesTree[M(3)]->conditional()->asDiscrete();
524  EXPECT_LONGS_EQUAL(3, discreteTree->size());
525 
526  // Test if the optimal discrete mode assignment is (1, 1, 1).
527  DiscreteFactorGraph discreteGraph;
528  discreteGraph.push_back(discreteTree);
529  DiscreteValues optimal_assignment = discreteGraph.optimize();
530 
531  DiscreteValues expected_assignment;
532  expected_assignment[M(1)] = 1;
533  expected_assignment[M(2)] = 1;
534  expected_assignment[M(3)] = 1;
535 
536  EXPECT(assert_equal(expected_assignment, optimal_assignment));
537 
538  // Test if pruning worked correctly by checking that
539  // we only have 3 leaves in the last node.
540  auto lastConditional = bayesTree[X(3)]->conditional()->asHybrid();
541  EXPECT_LONGS_EQUAL(3, lastConditional->nrComponents());
542 }
543 
544 /* ************************************************************************* */
545 int main() {
546  TestResult tr;
547  return TestRegistry::runAllTests(tr);
548 }
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
switching3::switching
const Switching switching(3)
gtsam::HybridGaussianISAM
Incremental Smoothing and Mapping (ISAM) algorithm for hybrid factor graphs.
Definition: HybridGaussianISAM.h:37
Pose2.h
2D Pose
DiscreteBayesNet.h
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::DiscreteFactorGraph
Definition: DiscreteFactorGraph.h:99
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
gtsam::HybridNonlinearISAM::prune
void prune(const size_t maxNumberLeaves)
Prune the underlying Bayes tree.
Definition: HybridNonlinearISAM.h:89
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
DiscreteFactorGraph.h
gtsam::HybridNonlinearFactorGraph
Definition: HybridNonlinearFactorGraph.h:33
gtsam::Y
GaussianFactorGraphValuePair Y
Definition: HybridGaussianProductFactor.cpp:29
initial
Values initial
Definition: OdometryOptimize.cpp:2
Switching.h
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
X
#define X
Definition: icosphere.cpp:20
GaussianBayesNet.h
Chordal Bayes Net, the result of eliminating a factor graph.
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::NonlinearISAM::bayesTree
const GaussianISAM & bayesTree() const
Definition: NonlinearISAM.h:75
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
test_motion::noise_model
auto noise_model
Definition: testHybridNonlinearFactorGraph.cpp:119
gtsam::Switching::linearizedFactorGraph
HybridGaussianFactorGraph linearizedFactorGraph() const
Get the full linear factor graph.
Definition: Switching.h:220
gtsam::NonlinearISAM::update
void update(const NonlinearFactorGraph &newFactors, const Values &initialValues)
Definition: NonlinearISAM.cpp:35
gtsam::Switching
ϕ(X(0)) .. ϕ(X(k),X(k+1)) .. ϕ(X(k);z_k) .. ϕ(M(0)) .. ϕ(M(K-3),M(K-2))
Definition: Switching.h:124
gtsam::FactorGraph::at
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:306
odometry
Pose2 odometry(2.0, 0.0, 0.0)
CHECK_EQUAL
#define CHECK_EQUAL(expected, actual)
Definition: Test.h:131
main
int main()
Definition: testHybridNonlinearISAM.cpp:545
PriorFactor.h
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::noiseModel::Isotropic
Definition: NoiseModel.h:541
gtsam::HybridNonlinearISAM::update
void update(const HybridNonlinearFactorGraph &newFactors, const Values &initialValues, const std::optional< size_t > &maxNrLeaves={}, const std::optional< Ordering > &ordering={})
Definition: HybridNonlinearISAM.cpp:36
gtsam::HybridNonlinearISAM::bayesTree
const HybridGaussianISAM & bayesTree() const
Definition: HybridNonlinearISAM.h:82
isam
NonlinearISAM isam(relinearizeInterval)
gtsam::HybridGaussianFactorGraph
Definition: HybridGaussianFactorGraph.h:106
gtsam::HybridNonlinearISAM
Definition: HybridNonlinearISAM.h:29
L
MatrixXd L
Definition: LLT_example.cpp:6
priorNoise
auto priorNoise
Definition: doc/Code/OdometryExample.cpp:6
ordering
static enum @1096 ordering
TestResult
Definition: TestResult.h:26
gtsam::Switching::modeChain
HybridNonlinearFactorGraph modeChain
Definition: Switching.h:128
Values
std::vector< float > Values
Definition: sparse_setter.cpp:45
gtsam
traits
Definition: SFMdata.h:40
gtsam::BayesTree::size
size_t size() const
Definition: BayesTree-inst.h:133
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
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
DiscreteDistribution.h
gtsam::Values
Definition: Values.h:65
gtsam::symbol_shorthand::W
Key W(std::uint64_t j)
Definition: inference/Symbol.h:170
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std
Definition: BFloat16.h:88
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
HybridNonlinearISAM.h
initial
Definition: testScenarioRunner.cpp:148
different_sigmas::prior
const auto prior
Definition: testHybridBayesNet.cpp:238
gtsam::HybridBayesTree::prune
void prune(const size_t maxNumberLeaves)
Prune the underlying Bayes tree.
Definition: HybridBayesTree.cpp:181
test_motion::components
std::vector< NoiseModelFactor::shared_ptr > components
Definition: testHybridNonlinearFactorGraph.cpp:120
gtsam::DiscreteFactorGraph::optimize
DiscreteValues optimize(OptionalOrderingType orderingType={}) const
Find the maximum probable explanation (MPE) by doing max-product.
Definition: DiscreteFactorGraph.cpp:203
gtsam::Switching::binaryFactors
HybridNonlinearFactorGraph binaryFactors
Definition: Switching.h:128
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
Z
#define Z
Definition: icosphere.cpp:21
TEST
TEST(HybridNonlinearISAM, IncrementalElimination)
Definition: testHybridNonlinearISAM.cpp:49
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::Switching::unaryFactors
HybridNonlinearFactorGraph unaryFactors
Definition: Switching.h:128
test_callbacks.value
value
Definition: test_callbacks.py:160
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::HybridNonlinearFactor
Implementation of a discrete-conditioned hybrid factor.
Definition: HybridNonlinearFactor.h:58
gtsam::HybridBayesTree::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: HybridBayesTree.h:68
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::Pose2
Definition: Pose2.h:39
HybridConditional.h
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
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


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