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 
23 #include <gtsam/geometry/Pose2.h>
30 
31 #include "Switching.h"
32 
33 // Include for test suite
35 
36 using namespace std;
37 using namespace gtsam;
43 
44 /* ****************************************************************************/
45 namespace switching3 {
46 // ϕ(x0) ϕ(x1;z1) ϕ(x2;z2) ϕ(x0,x1,m0) ϕ(x1,x2,m1) ϕ(m0) ϕ(m0,m1)
47 const Switching switching(3);
49 
50 // First update graph: ϕ(x0) ϕ(x0,x1,m0) ϕ(m0)
52 
53 // Second update graph: ϕ(x1,x2,m1) ϕ(x1;z1) ϕ(x2;z2) ϕ(m0,m1)
55  lfg.at(6)};
56 } // namespace switching3
57 
58 /* ****************************************************************************/
59 // Test if we can perform elimination incrementally.
60 TEST(HybridGaussianISAM, IncrementalElimination) {
61  using namespace switching3;
63 
64  // Run first update step
66 
67  // Check that after update we have 2 hybrid Bayes net nodes:
68  // P(M0) and P(X0, X1 | M0)
69  EXPECT_LONGS_EQUAL(2, isam.size());
70  EXPECT(isam[M(0)]->conditional()->frontals() == KeyVector({M(0)}));
71  EXPECT(isam[M(0)]->conditional()->parents() == KeyVector());
72  EXPECT(isam[X(0)]->conditional()->frontals() == KeyVector({X(0), X(1)}));
73  EXPECT(isam[X(0)]->conditional()->parents() == KeyVector({M(0)}));
74 
75  /********************************************************/
76  // Run second update step
78 
79  // Check that after update we have 3 hybrid Bayes net nodes:
80  // P(X1, X2 | M0, M1) P(X1, X2 | M0, M1)
81  EXPECT_LONGS_EQUAL(3, isam.size());
82  EXPECT(isam[M(0)]->conditional()->frontals() == KeyVector({M(0), M(1)}));
83  EXPECT(isam[M(0)]->conditional()->parents() == KeyVector());
84  EXPECT(isam[X(1)]->conditional()->frontals() == KeyVector({X(1), X(2)}));
85  EXPECT(isam[X(1)]->conditional()->parents() == KeyVector({M(0), M(1)}));
86  EXPECT(isam[X(0)]->conditional()->frontals() == KeyVector{X(0)});
87  EXPECT(isam[X(0)]->conditional()->parents() == KeyVector({X(1), M(0)}));
88 }
89 
90 /* ****************************************************************************/
91 // Test if we can incrementally do the inference
92 TEST(HybridGaussianISAM, IncrementalInference) {
93  using namespace switching3;
95 
96  // Run update step
98 
99  auto discreteConditional_m0 = isam[M(0)]->conditional()->asDiscrete();
100  EXPECT(discreteConditional_m0->keys() == KeyVector({M(0)}));
101 
102  /********************************************************/
103  // Second incremental update.
104  isam.update(graph2);
105 
106  /********************************************************/
107  // Run batch elimination so we can compare results.
108  const Ordering ordering{X(0), X(1), X(2)};
109 
110  // Now we calculate the expected factors using full elimination
111  const auto [expectedHybridBayesTree, expectedRemainingGraph] =
113 
114  // The densities on X(0) should be the same
115  auto x0_conditional = dynamic_pointer_cast<HybridGaussianConditional>(
116  isam[X(0)]->conditional()->inner());
117  auto expected_x0_conditional =
118  dynamic_pointer_cast<HybridGaussianConditional>(
119  (*expectedHybridBayesTree)[X(0)]->conditional()->inner());
120  EXPECT(assert_equal(*x0_conditional, *expected_x0_conditional));
121 
122  // The densities on X(1) should be the same
123  auto x1_conditional = dynamic_pointer_cast<HybridGaussianConditional>(
124  isam[X(1)]->conditional()->inner());
125  auto expected_x1_conditional =
126  dynamic_pointer_cast<HybridGaussianConditional>(
127  (*expectedHybridBayesTree)[X(1)]->conditional()->inner());
128  EXPECT(assert_equal(*x1_conditional, *expected_x1_conditional));
129 
130  // The densities on X(2) should be the same
131  auto x2_conditional = dynamic_pointer_cast<HybridGaussianConditional>(
132  isam[X(2)]->conditional()->inner());
133  auto expected_x2_conditional =
134  dynamic_pointer_cast<HybridGaussianConditional>(
135  (*expectedHybridBayesTree)[X(2)]->conditional()->inner());
136  EXPECT(assert_equal(*x2_conditional, *expected_x2_conditional));
137 
138  // We only perform manual continuous elimination for 0,0.
139  // The other discrete probabilities on M(2) are calculated the same way
140  const Ordering discreteOrdering{M(0), M(1)};
141  HybridBayesTree::shared_ptr discreteBayesTree =
142  expectedRemainingGraph->eliminateMultifrontal(discreteOrdering);
143 
144  // Test the probability values with regression tests.
145  auto discrete = isam[M(1)]->conditional()->asDiscrete<TableDistribution>();
146  EXPECT(assert_equal(0.095292, (*discrete)({{M(0), 0}, {M(1), 0}}), 1e-5));
147  EXPECT(assert_equal(0.282758, (*discrete)({{M(0), 1}, {M(1), 0}}), 1e-5));
148  EXPECT(assert_equal(0.314175, (*discrete)({{M(0), 0}, {M(1), 1}}), 1e-5));
149  EXPECT(assert_equal(0.307775, (*discrete)({{M(0), 1}, {M(1), 1}}), 1e-5));
150 
151  // Check that the clique conditional generated from incremental elimination
152  // matches that of batch elimination.
153  auto expectedConditional = (*discreteBayesTree)[M(1)]->conditional();
154  auto actualConditional = isam[M(1)]->conditional();
155  EXPECT(assert_equal(*expectedConditional, *actualConditional, 1e-6));
156 }
157 
158 /* ****************************************************************************/
159 // Test if we can approximately do the inference
160 TEST(HybridGaussianISAM, ApproxInference) {
161  Switching switching(4);
162  HybridGaussianISAM incrementalHybrid;
164 
165  // Add the 3 hybrid factors, x0-x1, x1-x2, x2-x3
166  for (size_t i = 0; i < 3; i++) {
168  }
169 
170  // Add the Gaussian factors, 1 prior on x0,
171  // 3 measurements on x1, x2, x3
172  for (size_t i = 0; i <= 3; i++) {
174  }
175 
176  // Create ordering.
178  for (size_t j = 0; j < 4; j++) {
179  ordering.push_back(X(j));
180  }
181 
182  // Now we calculate the actual factors using full elimination
183  const auto [unPrunedHybridBayesTree, unPrunedRemainingGraph] =
185 
186  size_t maxNrLeaves = 5;
187  incrementalHybrid.update(graph1);
188 
189  incrementalHybrid.prune(maxNrLeaves);
190 
191  /*
192  unPruned factor is:
193  Choice(m3)
194  0 Choice(m2)
195  0 0 Choice(m1)
196  0 0 0 Leaf 0.11267528
197  0 0 1 Leaf 0.18576102
198  0 1 Choice(m1)
199  0 1 0 Leaf 0.18754662
200  0 1 1 Leaf 0.30623871
201  1 Choice(m2)
202  1 0 Choice(m1)
203  1 0 0 Leaf 0.18576102
204  1 0 1 Leaf 0.30622428
205  1 1 Choice(m1)
206  1 1 0 Leaf 0.30623871
207  1 1 1 Leaf 0.5
208 
209  pruned factors is:
210  Choice(m3)
211  0 Choice(m2)
212  0 0 Leaf 0
213  0 1 Choice(m1)
214  0 1 0 Leaf 0.18754662
215  0 1 1 Leaf 0.30623871
216  1 Choice(m2)
217  1 0 Choice(m1)
218  1 0 0 Leaf 0
219  1 0 1 Leaf 0.30622428
220  1 1 Choice(m1)
221  1 1 0 Leaf 0.30623871
222  1 1 1 Leaf 0.5
223  */
224 
225  auto discreteConditional_m0 = *dynamic_pointer_cast<TableDistribution>(
226  incrementalHybrid[M(0)]->conditional()->inner());
227  EXPECT(discreteConditional_m0.keys() == KeyVector({M(0), M(1), M(2)}));
228 
229  // Check that the number of leaves after pruning is 5.
230  EXPECT_LONGS_EQUAL(5, discreteConditional_m0.nrValues());
231 
232  // Check that the hybrid nodes of the bayes net match those of the pre-pruning
233  // bayes net, at the same positions.
234  auto &unPrunedLastDensity = *dynamic_pointer_cast<HybridGaussianConditional>(
235  unPrunedHybridBayesTree->clique(X(3))->conditional()->inner());
236  auto &lastDensity = *dynamic_pointer_cast<HybridGaussianConditional>(
237  incrementalHybrid[X(3)]->conditional()->inner());
238 
239  std::vector<std::pair<DiscreteValues, double>> assignments =
240  discreteConditional_m0.enumerate();
241  // Loop over all assignments and check the pruned components
242  for (auto &&av : assignments) {
243  const DiscreteValues &assignment = av.first;
244  const double value = av.second;
245 
246  if (value == 0.0) {
247  EXPECT(lastDensity(assignment) == nullptr);
248  } else {
249  CHECK(lastDensity(assignment));
250  EXPECT(assert_equal(*unPrunedLastDensity(assignment),
251  *lastDensity(assignment)));
252  }
253  }
254 }
255 
256 /* ****************************************************************************/
257 // Test approximate inference with an additional pruning step.
258 TEST(HybridGaussianISAM, IncrementalApproximate) {
259  Switching switching(5);
260  HybridGaussianISAM incrementalHybrid;
262 
263  /***** Run Round 1 *****/
264  // Add the 3 hybrid factors, x0-x1, x1-x2, x2-x3
265  for (size_t i = 0; i < 3; i++) {
267  }
268 
269  // Add the Gaussian factors, 1 prior on x0,
270  // 3 measurements on x1, x2, x3
271  for (size_t i = 0; i <= 3; i++) {
273  }
274 
275  // Run update with pruning
276  size_t maxComponents = 5;
277  incrementalHybrid.update(graph, maxComponents);
278 
279  // Check if we have a bayes tree with 4 hybrid nodes,
280  // each with 2, 4, 8, and 5 (pruned) leaves respectively.
281  EXPECT_LONGS_EQUAL(4, incrementalHybrid.size());
283  2, incrementalHybrid[X(0)]->conditional()->asHybrid()->nrComponents());
285  3, incrementalHybrid[X(1)]->conditional()->asHybrid()->nrComponents());
287  5, incrementalHybrid[X(2)]->conditional()->asHybrid()->nrComponents());
289  5, incrementalHybrid[X(3)]->conditional()->asHybrid()->nrComponents());
290 
291  /***** Run Round 2 *****/
293  graph.push_back(switching.linearBinaryFactors.at(3)); // hybrid x3-x4
295 
296  // Run update with pruning a second time.
297  incrementalHybrid.update(graph, maxComponents);
298 
299  // Check if we have a bayes tree with pruned hybrid nodes,
300  // with 5 (pruned) leaves.
301  CHECK_EQUAL(5, incrementalHybrid.size());
303  5, incrementalHybrid[X(3)]->conditional()->asHybrid()->nrComponents());
305  5, incrementalHybrid[X(4)]->conditional()->asHybrid()->nrComponents());
306 }
307 
308 /* ************************************************************************/
309 // A GTSAM-only test for running inference on a single-legged robot.
310 // The leg links are represented by the chain X-Y-Z-W, where X is the base and
311 // W is the foot.
312 // We use BetweenFactor<Pose2> as constraints between each of the poses.
313 TEST(HybridGaussianISAM, NonTrivial) {
314  /*************** Run Round 1 ***************/
316 
317  // Add a prior on pose x0 at the origin.
318  // A prior factor consists of a mean and
319  // a noise model (covariance matrix)
320  Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
321  auto priorNoise = noiseModel::Diagonal::Sigmas(
322  Vector3(0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
324 
325  // create a noise model for the landmark measurements
326  auto poseNoise = noiseModel::Isotropic::Sigma(3, 0.1);
327 
328  // We model a robot's single leg as X - Y - Z - W
329  // where X is the base link and W is the foot link.
330 
331  // Add connecting poses similar to PoseFactors in GTD
332  fg.emplace_shared<BetweenFactor<Pose2>>(X(0), Y(0), Pose2(0, 1.0, 0),
333  poseNoise);
334  fg.emplace_shared<BetweenFactor<Pose2>>(Y(0), Z(0), Pose2(0, 1.0, 0),
335  poseNoise);
336  fg.emplace_shared<BetweenFactor<Pose2>>(Z(0), W(0), Pose2(0, 1.0, 0),
337  poseNoise);
338 
339  // Create initial estimate
340  Values initial;
341  initial.insert(X(0), Pose2(0.0, 0.0, 0.0));
342  initial.insert(Y(0), Pose2(0.0, 1.0, 0.0));
343  initial.insert(Z(0), Pose2(0.0, 2.0, 0.0));
344  initial.insert(W(0), Pose2(0.0, 3.0, 0.0));
345 
348 
349  HybridGaussianISAM inc;
350 
351  // Update without pruning
352  // The result is a HybridBayesNet with no discrete variables
353  // (equivalent to a GaussianBayesNet).
354  // Factorization is:
355  // `P(X | measurements) = P(W0|Z0) P(Z0|Y0) P(Y0|X0) P(X0)`
356  inc.update(gfg);
357 
358  /*************** Run Round 2 ***************/
359  using PlanarMotionModel = BetweenFactor<Pose2>;
360 
361  // Add odometry factor with discrete modes.
362  Pose2 odometry(1.0, 0.0, 0.0);
363  auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
364  std::vector<NoiseModelFactor::shared_ptr> components;
365  components.emplace_back(
366  new PlanarMotionModel(W(0), W(1), odometry, noise_model)); // moving
367  components.emplace_back(
368  new PlanarMotionModel(W(0), W(1), Pose2(0, 0, 0), noise_model)); // still
370 
371  // Add equivalent of ImuFactor
372  fg.emplace_shared<BetweenFactor<Pose2>>(X(0), X(1), Pose2(1.0, 0.0, 0),
373  poseNoise);
374  // PoseFactors-like at k=1
375  fg.emplace_shared<BetweenFactor<Pose2>>(X(1), Y(1), Pose2(0, 1, 0),
376  poseNoise);
377  fg.emplace_shared<BetweenFactor<Pose2>>(Y(1), Z(1), Pose2(0, 1, 0),
378  poseNoise);
379  fg.emplace_shared<BetweenFactor<Pose2>>(Z(1), W(1), Pose2(-1, 1, 0),
380  poseNoise);
381 
382  initial.insert(X(1), Pose2(1.0, 0.0, 0.0));
383  initial.insert(Y(1), Pose2(1.0, 1.0, 0.0));
384  initial.insert(Z(1), Pose2(1.0, 2.0, 0.0));
385  // The leg link did not move so we set the expected pose accordingly.
386  initial.insert(W(1), Pose2(0.0, 3.0, 0.0));
387 
388  gfg = *fg.linearize(initial);
390 
391  // Update without pruning
392  // The result is a HybridBayesNet with 1 discrete variable M(1).
393  // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1)
394  // P(X0 | X1, W1, M1) P(W1|Z1, X1, M1) P(Z1|Y1, X1, M1)
395  // P(Y1 | X1, M1)P(X1 | M1)P(M1)
396  // The MHS tree is a 1 level tree for time indices (1,) with 2 leaves.
397  inc.update(gfg);
398 
399  /*************** Run Round 3 ***************/
400  // Add odometry factor with discrete modes.
401  components.clear();
402  components.emplace_back(
403  new PlanarMotionModel(W(1), W(2), odometry, noise_model)); // moving
404  components.emplace_back(
405  new PlanarMotionModel(W(1), W(2), Pose2(0, 0, 0), noise_model)); // still
407 
408  // Add equivalent of ImuFactor
409  fg.emplace_shared<BetweenFactor<Pose2>>(X(1), X(2), Pose2(1.0, 0.0, 0),
410  poseNoise);
411  // PoseFactors-like at k=1
412  fg.emplace_shared<BetweenFactor<Pose2>>(X(2), Y(2), Pose2(0, 1, 0),
413  poseNoise);
414  fg.emplace_shared<BetweenFactor<Pose2>>(Y(2), Z(2), Pose2(0, 1, 0),
415  poseNoise);
416  fg.emplace_shared<BetweenFactor<Pose2>>(Z(2), W(2), Pose2(-2, 1, 0),
417  poseNoise);
418 
419  initial.insert(X(2), Pose2(2.0, 0.0, 0.0));
420  initial.insert(Y(2), Pose2(2.0, 1.0, 0.0));
421  initial.insert(Z(2), Pose2(2.0, 2.0, 0.0));
422  initial.insert(W(2), Pose2(0.0, 3.0, 0.0));
423 
424  gfg = *fg.linearize(initial);
426 
427  // Now we prune!
428  // P(X | measurements) = P(W0|Z0, W1, M1) P(Z0|Y0, W1, M1) P(Y0|X0, W1, M1)
429  // P(X0 | X1, W1, M1) P(W1|W2, Z1, X1, M1, M2)
430  // P(Z1| W2, Y1, X1, M1, M2) P(Y1 | W2, X1, M1, M2)
431  // P(X1 | W2, X2, M1, M2) P(W2|Z2, X2, M1, M2)
432  // P(Z2|Y2, X2, M1, M2) P(Y2 | X2, M1, M2)
433  // P(X2 | M1, M2) P(M1, M2)
434  // The MHS at this point should be a 2 level tree on (1, 2).
435  // 1 has 2 choices, and 2 has 4 choices.
436  inc.update(gfg);
437  inc.prune(2);
438 
439  /*************** Run Round 4 ***************/
440  // Add odometry factor with discrete modes.
441  components.clear();
442  components.emplace_back(
443  new PlanarMotionModel(W(2), W(3), odometry, noise_model)); // moving
444  components.emplace_back(
445  new PlanarMotionModel(W(2), W(3), Pose2(0, 0, 0), noise_model)); // still
447 
448  // Add equivalent of ImuFactor
449  fg.emplace_shared<BetweenFactor<Pose2>>(X(2), X(3), Pose2(1.0, 0.0, 0),
450  poseNoise);
451  // PoseFactors-like at k=3
452  fg.emplace_shared<BetweenFactor<Pose2>>(X(3), Y(3), Pose2(0, 1, 0),
453  poseNoise);
454  fg.emplace_shared<BetweenFactor<Pose2>>(Y(3), Z(3), Pose2(0, 1, 0),
455  poseNoise);
456  fg.emplace_shared<BetweenFactor<Pose2>>(Z(3), W(3), Pose2(-3, 1, 0),
457  poseNoise);
458 
459  initial.insert(X(3), Pose2(3.0, 0.0, 0.0));
460  initial.insert(Y(3), Pose2(3.0, 1.0, 0.0));
461  initial.insert(Z(3), Pose2(3.0, 2.0, 0.0));
462  initial.insert(W(3), Pose2(0.0, 3.0, 0.0));
463 
464  gfg = *fg.linearize(initial);
466 
467  // Keep pruning!
468  inc.update(gfg, 3);
469 
470  // The final discrete graph should not be empty since we have eliminated
471  // all continuous variables.
472  auto discreteTree = inc[M(3)]->conditional()->asDiscrete();
473  EXPECT_LONGS_EQUAL(3, discreteTree->size());
474 
475  // Test if the optimal discrete mode assignment is (1, 1, 1).
476  DiscreteFactorGraph discreteGraph;
477  // discreteTree is a TableDistribution, so we convert to
478  // DecisionTreeFactor for the DiscreteFactorGraph
479  discreteGraph.push_back(discreteTree->toDecisionTreeFactor());
480  DiscreteValues optimal_assignment = discreteGraph.optimize();
481 
482  DiscreteValues expected_assignment;
483  expected_assignment[M(1)] = 1;
484  expected_assignment[M(2)] = 1;
485  expected_assignment[M(3)] = 1;
486 
487  EXPECT(assert_equal(expected_assignment, optimal_assignment));
488 
489  // Test if pruning worked correctly by checking that we only have 3 leaves in
490  // the last node.
491  auto lastConditional = inc[X(3)]->conditional()->asHybrid();
492  EXPECT_LONGS_EQUAL(3, lastConditional->nrComponents());
493 }
494 
495 /* ************************************************************************* */
496 int main() {
497  TestResult tr;
498  return TestRegistry::runAllTests(tr);
499 }
gtsam::EliminateableFactorGraph::eliminatePartialMultifrontal
std::pair< std::shared_ptr< BayesTreeType >, std::shared_ptr< FactorGraphType > > eliminatePartialMultifrontal(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Definition: EliminateableFactorGraph-inst.h:190
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
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::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
PriorFactor.h
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::TableDistribution
Definition: TableDistribution.h:39
TEST
TEST(HybridGaussianISAM, IncrementalElimination)
Definition: testHybridGaussianISAM.cpp:60
gtsam::Switching::linearUnaryFactors
HybridGaussianFactorGraph linearUnaryFactors
Definition: Switching.h:129
isam
NonlinearISAM isam(relinearizeInterval)
switching3::lfg
const HybridGaussianFactorGraph & lfg
Definition: testHybridGaussianISAM.cpp:48
HybridGaussianISAM.h
gtsam::HybridGaussianFactorGraph
Definition: HybridGaussianFactorGraph.h:106
priorNoise
auto priorNoise
Definition: doc/Code/OdometryExample.cpp:6
ordering
static enum @1096 ordering
TestResult
Definition: TestResult.h:26
switching3
Definition: testHybridGaussianISAM.cpp:45
gtsam
traits
Definition: SFMdata.h:40
gtsam::BayesTree::size
size_t size() const
Definition: BayesTree-inst.h:135
switching3::graph2
const HybridGaussianFactorGraph graph2
Definition: testHybridGaussianISAM.cpp:54
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
gtsam::Switching::linearBinaryFactors
HybridGaussianFactorGraph linearBinaryFactors
Definition: Switching.h:129
std
Definition: BFloat16.h:88
gtsam::HybridNonlinearFactorGraph::linearize
std::shared_ptr< HybridGaussianFactorGraph > linearize(const Values &continuousValues) const
Linearize all the continuous factors in the HybridNonlinearFactorGraph.
Definition: HybridNonlinearFactorGraph.cpp:139
switching3::graph1
const HybridGaussianFactorGraph graph1
Definition: testHybridGaussianISAM.cpp:51
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
initial
Definition: testScenarioRunner.cpp:148
different_sigmas::prior
const auto prior
Definition: testHybridBayesNet.cpp:240
gtsam::HybridBayesTree::prune
void prune(const size_t maxNumberLeaves)
Prune the underlying Bayes tree.
Definition: HybridBayesTree.cpp:204
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
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
Z
#define Z
Definition: icosphere.cpp:21
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::HybridGaussianISAM::update
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.
Definition: HybridGaussianISAM.cpp:123
main
int main()
Definition: testHybridGaussianISAM.cpp:496
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 Wed Mar 19 2025 03:06:50