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