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 
23 #include <gtsam/geometry/Pose2.h>
30 
31 #include <numeric>
32 
33 #include "Switching.h"
34 
35 // Include for test suite
37 
38 using namespace std;
39 using namespace gtsam;
47 
48 /* ****************************************************************************/
49 // Test if we can perform elimination incrementally.
50 TEST(HybridNonlinearISAM, IncrementalElimination) {
55 
56  // Create initial factor graph
57  // * * *
58  // | | |
59  // X0 -*- X1 -*- X2
60  // \*-M0-*/
62  graph.push_back(switching.binaryFactors.at(0)); // P(X0, X1 | M0)
63  graph.push_back(switching.binaryFactors.at(1)); // P(X1, X2 | M1)
64  graph.push_back(switching.modeChain.at(0)); // P(M0)
65 
66  initial.insert<double>(X(0), 1);
67  initial.insert<double>(X(1), 2);
68  initial.insert<double>(X(2), 3);
69 
70  // Run update step
72 
73  // Check that after update we have 3 hybrid Bayes net nodes:
74  // P(X0 | X1, M0) and P(X1, X2 | M0, M1), P(M0, M1)
77  EXPECT(bayesTree[X(0)]->conditional()->frontals() == KeyVector{X(0)});
78  EXPECT(bayesTree[X(0)]->conditional()->parents() == KeyVector({X(1), M(0)}));
79  EXPECT(bayesTree[X(1)]->conditional()->frontals() == KeyVector({X(1), X(2)}));
80  EXPECT(bayesTree[X(1)]->conditional()->parents() == KeyVector({M(0), M(1)}));
81 
82  /********************************************************/
83  // New factor graph for incremental update.
85  initial = Values();
86 
89  graph.push_back(switching.modeChain.at(1)); // P(M0, M1)
90 
92 
94  // Check that after the second update we have
95  // 1 additional hybrid Bayes net node:
96  // P(X1, X2 | M0, M1)
98  EXPECT(bayesTree[X(2)]->conditional()->frontals() == KeyVector({X(1), X(2)}));
99  EXPECT(bayesTree[X(2)]->conditional()->parents() == KeyVector({M(0), M(1)}));
100 }
101 
102 /* ****************************************************************************/
103 // Test if we can incrementally do the inference
104 TEST(HybridNonlinearISAM, IncrementalInference) {
105  Switching switching(3);
108  Values initial;
109 
110  // Create initial factor graph
111  // * * *
112  // | | |
113  // X0 -*- X1 -*- X2
114  // | |
115  // *-M0 - * - M1
116  graph.push_back(switching.unaryFactors.at(0)); // P(X0)
117  graph.push_back(switching.binaryFactors.at(0)); // P(X0, X1 | M0)
118  graph.push_back(switching.unaryFactors.at(1)); // P(X1)
119  graph.push_back(switching.modeChain.at(0)); // P(M0)
120 
121  initial.insert<double>(X(0), 1);
122  initial.insert<double>(X(1), 2);
123 
124  // Run update step
127 
128  auto discreteConditional_m0 = bayesTree[M(0)]->conditional()->asDiscrete();
129  EXPECT(discreteConditional_m0->keys() == KeyVector({M(0)}));
130 
131  /********************************************************/
132  // New factor graph for incremental update.
134  initial = Values();
135 
136  initial.insert<double>(X(2), 3);
137 
138  graph.push_back(switching.binaryFactors.at(1)); // P(X1, X2 | M1)
139  graph.push_back(switching.unaryFactors.at(2)); // P(X2)
140  graph.push_back(switching.modeChain.at(1)); // P(M0, M1)
141 
144 
145  /********************************************************/
146  // Run batch elimination so we can compare results.
147  const Ordering ordering{X(0), X(1), X(2)};
148 
149  // Now we calculate the actual factors using full elimination
150  const auto [expectedHybridBayesTree, expectedRemainingGraph] =
152  .BaseEliminateable::eliminatePartialMultifrontal(ordering);
153 
154  // The densities on X(1) should be the same
155  auto x0_conditional = dynamic_pointer_cast<HybridGaussianConditional>(
156  bayesTree[X(0)]->conditional()->inner());
157  auto expected_x0_conditional =
158  dynamic_pointer_cast<HybridGaussianConditional>(
159  (*expectedHybridBayesTree)[X(0)]->conditional()->inner());
160  EXPECT(assert_equal(*x0_conditional, *expected_x0_conditional));
161 
162  // The densities on X(1) should be the same
163  auto x1_conditional = dynamic_pointer_cast<HybridGaussianConditional>(
164  bayesTree[X(1)]->conditional()->inner());
165  auto expected_x1_conditional =
166  dynamic_pointer_cast<HybridGaussianConditional>(
167  (*expectedHybridBayesTree)[X(1)]->conditional()->inner());
168  EXPECT(assert_equal(*x1_conditional, *expected_x1_conditional));
169 
170  // The densities on X(2) should be the same
171  auto x2_conditional = dynamic_pointer_cast<HybridGaussianConditional>(
172  bayesTree[X(2)]->conditional()->inner());
173  auto expected_x2_conditional =
174  dynamic_pointer_cast<HybridGaussianConditional>(
175  (*expectedHybridBayesTree)[X(2)]->conditional()->inner());
176  EXPECT(assert_equal(*x2_conditional, *expected_x2_conditional));
177 
178  // We only perform manual continuous elimination for 0,0.
179  // The other discrete probabilities on M(2) are calculated the same way
180  const Ordering discreteOrdering{M(0), M(1)};
181  HybridBayesTree::shared_ptr discreteBayesTree =
182  expectedRemainingGraph->eliminateMultifrontal(discreteOrdering);
183 
184  // Test the probability values with regression tests.
185  auto discrete = bayesTree[M(1)]->conditional()->asDiscrete();
186  EXPECT(assert_equal(0.095292, (*discrete)({{M(0), 0}, {M(1), 0}}), 1e-5));
187  EXPECT(assert_equal(0.282758, (*discrete)({{M(0), 1}, {M(1), 0}}), 1e-5));
188  EXPECT(assert_equal(0.314175, (*discrete)({{M(0), 0}, {M(1), 1}}), 1e-5));
189  EXPECT(assert_equal(0.307775, (*discrete)({{M(0), 1}, {M(1), 1}}), 1e-5));
190 
191  // Check that the clique conditional generated from incremental elimination
192  // matches that of batch elimination.
193  auto expectedConditional = (*discreteBayesTree)[M(1)]->conditional();
194  auto actualConditional = bayesTree[M(1)]->conditional();
195  EXPECT(assert_equal(*expectedConditional, *actualConditional, 1e-6));
196 }
197 
198 /* ****************************************************************************/
199 // Test if we can approximately do the inference (using pruning)
200 TEST(HybridNonlinearISAM, ApproxInference) {
201  Switching switching(4);
202  HybridNonlinearISAM incrementalHybrid;
204  Values initial;
205 
206  // Add the 3 hybrid factors, x0-x1, x1-x2, x2-x3
207  for (size_t i = 0; i < 3; i++) {
209  }
210 
211  // Add the Gaussian factors, 1 prior on X(0),
212  // 3 measurements on X(1), X(2), X(3)
213  for (size_t i = 0; i < 4; i++) {
215  initial.insert<double>(X(i), i + 1);
216  }
217 
218  // Create ordering.
220  for (size_t j = 0; j < 4; j++) {
221  ordering.push_back(X(j));
222  }
223 
224  // Now we calculate the actual factors using full elimination
225  const auto [unPrunedHybridBayesTree, unPrunedRemainingGraph] =
227  .BaseEliminateable::eliminatePartialMultifrontal(ordering);
228 
229  size_t maxNrLeaves = 5;
230  incrementalHybrid.update(graph, initial);
231  HybridGaussianISAM bayesTree = incrementalHybrid.bayesTree();
232 
233  bayesTree.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<TableDistribution>(
270  bayesTree[M(0)]->conditional()->inner());
271  EXPECT(discreteConditional_m0.keys() == KeyVector({M(0), M(1), M(2)}));
272 
273  // Check that the number of leaves after pruning is 5.
274  EXPECT_LONGS_EQUAL(5, discreteConditional_m0.nrValues());
275 
276  // Check that the hybrid nodes of the bayes net match those of the pre-pruning
277  // bayes net, at the same positions.
278  auto &unPrunedLastDensity = *dynamic_pointer_cast<HybridGaussianConditional>(
279  unPrunedHybridBayesTree->clique(X(3))->conditional()->inner());
280  auto &lastDensity = *dynamic_pointer_cast<HybridGaussianConditional>(
281  bayesTree[X(3)]->conditional()->inner());
282 
283  std::vector<std::pair<DiscreteValues, double>> assignments =
284  discreteConditional_m0.enumerate();
285  // Loop over all assignments and check the pruned components
286  for (auto &&av : assignments) {
287  const DiscreteValues &assignment = av.first;
288  const double value = av.second;
289 
290  if (value == 0.0) {
291  EXPECT(lastDensity(assignment) == nullptr);
292  } else {
293  CHECK(lastDensity(assignment));
294  EXPECT(assert_equal(*unPrunedLastDensity(assignment),
295  *lastDensity(assignment)));
296  }
297  }
298 }
299 
300 /* ****************************************************************************/
301 // Test approximate inference with an additional pruning step.
302 TEST(HybridNonlinearISAM, IncrementalApproximate) {
303  Switching switching(5);
304  HybridNonlinearISAM incrementalHybrid;
306  Values initial;
307 
308  /***** Run Round 1 *****/
309  // Add the 3 hybrid factors, x0-x1, x1-x2, x2-x3
310  for (size_t i = 0; i < 3; i++) {
312  }
313 
314  // Add the Gaussian factors, 1 prior on X(0),
315  // 3 measurements on X(1), X(2), X(3)
316  for (size_t i = 0; i < 4; i++) {
318  initial.insert<double>(X(i), i + 1);
319  }
320 
321  // TODO(Frank): no mode chain?
322 
323  // Run update with pruning
324  size_t maxComponents = 5;
325  incrementalHybrid.update(graph, initial);
326  incrementalHybrid.prune(maxComponents);
327  HybridGaussianISAM bayesTree = incrementalHybrid.bayesTree();
328 
329  // Check if we have a bayes tree with 4 hybrid nodes,
330  // each with 2, 4, 8, and 5 (pruned) leaves respetively.
333  2, bayesTree[X(0)]->conditional()->asHybrid()->nrComponents());
335  3, bayesTree[X(1)]->conditional()->asHybrid()->nrComponents());
337  5, bayesTree[X(2)]->conditional()->asHybrid()->nrComponents());
339  5, bayesTree[X(3)]->conditional()->asHybrid()->nrComponents());
340 
341  /***** Run Round 2 *****/
344  graph.push_back(switching.unaryFactors.at(4)); // x4 measurement
345  initial = Values();
346  initial.insert<double>(X(4), 5);
347 
348  // Run update with pruning a second time.
349  incrementalHybrid.update(graph, initial);
350  incrementalHybrid.prune(maxComponents);
351  bayesTree = incrementalHybrid.bayesTree();
352 
353  // Check if we have a bayes tree with pruned hybrid nodes,
354  // with 5 (pruned) leaves.
355  CHECK_EQUAL(5, bayesTree.size());
357  5, bayesTree[X(3)]->conditional()->asHybrid()->nrComponents());
359  5, bayesTree[X(4)]->conditional()->asHybrid()->nrComponents());
360 }
361 
362 /* ************************************************************************/
363 // A GTSAM-only test for running inference on a single-legged robot.
364 // The leg links are represented by the chain X-Y-Z-W, where X is the base and
365 // W is the foot.
366 // We use BetweenFactor<Pose2> as constraints between each of the poses.
367 TEST(HybridNonlinearISAM, NonTrivial) {
368  /*************** Run Round 1 ***************/
371 
372  // Add a prior on pose x0 at the origin.
373  // A prior factor consists of a mean and
374  // a noise model (covariance matrix)
375  Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
376  auto priorNoise = noiseModel::Diagonal::Sigmas(
377  Vector3(0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
379 
380  // create a noise model for the landmark measurements
381  auto poseNoise = noiseModel::Isotropic::Sigma(3, 0.1);
382 
383  // We model a robot's single leg as X - Y - Z - W
384  // where X is the base link and W is the foot link.
385 
386  // Add connecting poses similar to PoseFactors in GTD
387  fg.emplace_shared<BetweenFactor<Pose2>>(X(0), Y(0), Pose2(0, 1.0, 0),
388  poseNoise);
389  fg.emplace_shared<BetweenFactor<Pose2>>(Y(0), Z(0), Pose2(0, 1.0, 0),
390  poseNoise);
391  fg.emplace_shared<BetweenFactor<Pose2>>(Z(0), W(0), Pose2(0, 1.0, 0),
392  poseNoise);
393 
394  // Create initial estimate
395  Values initial;
396  initial.insert(X(0), Pose2(0.0, 0.0, 0.0));
397  initial.insert(Y(0), Pose2(0.0, 1.0, 0.0));
398  initial.insert(Z(0), Pose2(0.0, 2.0, 0.0));
399  initial.insert(W(0), Pose2(0.0, 3.0, 0.0));
400 
401  // Don't run update now since we don't have discrete variables involved.
402 
403  using PlanarMotionModel = BetweenFactor<Pose2>;
404 
405  /*************** Run Round 2 ***************/
406  // Add odometry factor with discrete modes.
407  Pose2 odometry(1.0, 0.0, 0.0);
408  auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
409  auto still = std::make_shared<PlanarMotionModel>(W(0), W(1), Pose2(0, 0, 0),
410  noise_model),
411  moving = std::make_shared<PlanarMotionModel>(W(0), W(1), odometry,
412  noise_model);
413  std::vector<NoiseModelFactor::shared_ptr> components{moving, still};
415 
416  // Add equivalent of ImuFactor
417  fg.emplace_shared<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0, 0),
418  poseNoise);
419  // PoseFactors-like at k=1
420  fg.emplace_shared<BetweenFactor<Pose2>>(X(1), Y(1), Pose2(0, 1, 0),
421  poseNoise);
422  fg.emplace_shared<BetweenFactor<Pose2>>(Y(1), Z(1), Pose2(0, 1, 0),
423  poseNoise);
424  fg.emplace_shared<BetweenFactor<Pose2>>(Z(1), W(1), Pose2(-1, 1, 0),
425  poseNoise);
426 
427  initial.insert(X(1), Pose2(1.0, 0.0, 0.0));
428  initial.insert(Y(1), Pose2(1.0, 1.0, 0.0));
429  initial.insert(Z(1), Pose2(1.0, 2.0, 0.0));
430  // The leg link did not move so we set the expected pose accordingly.
431  initial.insert(W(1), Pose2(0.0, 3.0, 0.0));
432 
433  // Update without pruning
434  // The result is a HybridBayesNet with 1 discrete variable M(1).
435  // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1)
436  // P(X0 | X1, W1, M1) P(W1|Z1, X1, M1) P(Z1|Y1, X1, M1)
437  // P(Y1 | X1, M1)P(X1 | M1)P(M1)
438  // The MHS tree is a 1 level tree for time indices (1,) with 2 leaves.
439  inc.update(fg, initial);
440 
442  initial = Values();
443 
444  /*************** Run Round 3 ***************/
445  // Add odometry factor with discrete modes.
446  still = std::make_shared<PlanarMotionModel>(W(1), W(2), Pose2(0, 0, 0),
447  noise_model);
448  moving =
449  std::make_shared<PlanarMotionModel>(W(1), W(2), odometry, noise_model);
450  components = {moving, still};
452 
453  // Add equivalent of ImuFactor
454  fg.emplace_shared<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0, 0),
455  poseNoise);
456  // PoseFactors-like at k=1
457  fg.emplace_shared<BetweenFactor<Pose2>>(X(2), Y(2), Pose2(0, 1, 0),
458  poseNoise);
459  fg.emplace_shared<BetweenFactor<Pose2>>(Y(2), Z(2), Pose2(0, 1, 0),
460  poseNoise);
461  fg.emplace_shared<BetweenFactor<Pose2>>(Z(2), W(2), Pose2(-2, 1, 0),
462  poseNoise);
463 
464  initial.insert(X(2), Pose2(2.0, 0.0, 0.0));
465  initial.insert(Y(2), Pose2(2.0, 1.0, 0.0));
466  initial.insert(Z(2), Pose2(2.0, 2.0, 0.0));
467  initial.insert(W(2), Pose2(0.0, 3.0, 0.0));
468 
469  // Now we prune!
470  // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1)
471  // P(X0 | X1, W1, M1) P(W1|W2, Z1, X1, M1, M2)
472  // P(Z1| W2, Y1, X1, M1, M2) P(Y1 | W2, X1, M1, M2)
473  // P(X1 | W2, X2, M1, M2) P(W2|Z2, X2, M1, M2)
474  // P(Z2|Y2, X2, M1, M2) P(Y2 | X2, M1, M2)
475  // P(X2 | M1, M2) P(M1, M2)
476  // The MHS at this point should be a 2 level tree on (1, 2).
477  // 1 has 2 choices, and 2 has 4 choices.
478  inc.update(fg, initial);
479  inc.prune(2);
480 
482  initial = Values();
483 
484  /*************** Run Round 4 ***************/
485  // Add odometry factor with discrete modes.
486  still = std::make_shared<PlanarMotionModel>(W(2), W(3), Pose2(0, 0, 0),
487  noise_model);
488  moving =
489  std::make_shared<PlanarMotionModel>(W(2), W(3), odometry, noise_model);
490  components = {moving, still};
492 
493  // Add equivalent of ImuFactor
494  fg.emplace_shared<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0, 0),
495  poseNoise);
496  // PoseFactors-like at k=3
497  fg.emplace_shared<BetweenFactor<Pose2>>(X(3), Y(3), Pose2(0, 1, 0),
498  poseNoise);
499  fg.emplace_shared<BetweenFactor<Pose2>>(Y(3), Z(3), Pose2(0, 1, 0),
500  poseNoise);
501  fg.emplace_shared<BetweenFactor<Pose2>>(Z(3), W(3), Pose2(-3, 1, 0),
502  poseNoise);
503 
504  initial.insert(X(3), Pose2(3.0, 0.0, 0.0));
505  initial.insert(Y(3), Pose2(3.0, 1.0, 0.0));
506  initial.insert(Z(3), Pose2(3.0, 2.0, 0.0));
507  initial.insert(W(3), Pose2(0.0, 3.0, 0.0));
508 
509  // Keep pruning!
510  inc.update(fg, initial);
511  inc.prune(3);
512 
514  initial = Values();
515 
517 
518  // The final discrete graph should not be empty since we have eliminated
519  // all continuous variables.
520  auto discreteTree =
521  bayesTree[M(3)]->conditional()->asDiscrete<TableDistribution>();
522  EXPECT_LONGS_EQUAL(3, discreteTree->size());
523 
524  // Test if the optimal discrete mode assignment is (1, 1, 1).
525  DiscreteFactorGraph discreteGraph;
526  discreteGraph.push_back(discreteTree->toDecisionTreeFactor());
527  DiscreteValues optimal_assignment = discreteGraph.optimize();
528 
529  DiscreteValues expected_assignment;
530  expected_assignment[M(1)] = 1;
531  expected_assignment[M(2)] = 1;
532  expected_assignment[M(3)] = 1;
533 
534  EXPECT(assert_equal(expected_assignment, optimal_assignment));
535 
536  // Test if pruning worked correctly by checking that
537  // we only have 3 leaves in the last node.
538  auto lastConditional = bayesTree[X(3)]->conditional()->asHybrid();
539  EXPECT_LONGS_EQUAL(3, lastConditional->nrComponents());
540 }
541 
542 /* ************************************************************************* */
543 int main() {
544  TestResult tr;
545  return TestRegistry::runAllTests(tr);
546 }
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
switching3::switching
const Switching switching(3)
TableDistribution.h
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
asia::bayesTree
static const DiscreteBayesTree bayesTree
Definition: testDiscreteSearch.cpp:40
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:120
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:543
PriorFactor.h
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::TableDistribution
Definition: TableDistribution.h:39
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:37
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:135
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:240
test_motion::components
std::vector< NoiseModelFactor::shared_ptr > components
Definition: testHybridNonlinearFactorGraph.cpp:121
gtsam::DiscreteFactorGraph::optimize
DiscreteValues optimize(OptionalOrderingType orderingType={}) const
Find the maximum probable explanation (MPE) by doing max-product.
Definition: DiscreteFactorGraph.cpp:187
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:50
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::Switching::unaryFactors
HybridNonlinearFactorGraph unaryFactors
Definition: Switching.h:128
test_callbacks.value
value
Definition: test_callbacks.py:162
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 Fri Mar 28 2025 03:07:03