testHybridEstimation.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 
19 #include <gtsam/geometry/Pose2.h>
20 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/inference/Symbol.h>
35 
36 // Include for test suite
38 
39 #include <bitset>
40 
41 #include "Switching.h"
42 
43 using namespace std;
44 using namespace gtsam;
45 
48 
49 TEST(HybridEstimation, Full) {
50  size_t K = 6;
51  std::vector<double> measurements = {0, 1, 2, 2, 2, 3};
52  // Ground truth discrete seq
53  std::vector<size_t> discrete_seq = {1, 1, 0, 0, 1};
54  // Switching example of robot moving in 1D
55  // with given measurements and equal mode priors.
56  Switching switching(K, 1.0, 0.1, measurements, "1/1 1/1");
58 
59  Ordering hybridOrdering;
60  for (size_t k = 0; k < K; k++) {
61  hybridOrdering.push_back(X(k));
62  }
63  for (size_t k = 0; k < K - 1; k++) {
64  hybridOrdering.push_back(M(k));
65  }
66 
67  HybridBayesNet::shared_ptr bayesNet = graph.eliminateSequential();
68 
69  EXPECT_LONGS_EQUAL(2 * K - 1, bayesNet->size());
70 
71  HybridValues delta = bayesNet->optimize();
72 
73  Values initial = switching.linearizationPoint;
74  Values result = initial.retract(delta.continuous());
75 
76  DiscreteValues expected_discrete;
77  for (size_t k = 0; k < K - 1; k++) {
78  expected_discrete[M(k)] = discrete_seq[k];
79  }
80  EXPECT(assert_equal(expected_discrete, delta.discrete()));
81 
82  Values expected_continuous;
83  for (size_t k = 0; k < K; k++) {
84  expected_continuous.insert(X(k), measurements[k]);
85  }
86  EXPECT(assert_equal(expected_continuous, result));
87 }
88 
89 /****************************************************************************/
90 // Test approximate inference with an additional pruning step.
91 TEST(HybridEstimation, IncrementalSmoother) {
92  size_t K = 15;
93  std::vector<double> measurements = {0, 1, 2, 2, 2, 2, 3, 4, 5, 6, 6,
94  7, 8, 9, 9, 9, 10, 11, 11, 11, 11};
95  // Ground truth discrete seq
96  std::vector<size_t> discrete_seq = {1, 1, 0, 0, 0, 1, 1, 1, 1, 0,
97  1, 1, 1, 0, 0, 1, 1, 0, 0, 0};
98  // Switching example of robot moving in 1D
99  // with given measurements and equal mode priors.
100  Switching switching(K, 1.0, 0.1, measurements, "1/1 1/1");
101  HybridSmoother smoother;
103  Values initial;
104 
105  // Add the X(0) prior
106  graph.push_back(switching.nonlinearFactorGraph.at(0));
107  initial.insert(X(0), switching.linearizationPoint.at<double>(X(0)));
108 
109  HybridGaussianFactorGraph linearized;
110 
111  for (size_t k = 1; k < K; k++) {
112  // Motion Model
113  graph.push_back(switching.nonlinearFactorGraph.at(k));
114  // Measurement
115  graph.push_back(switching.nonlinearFactorGraph.at(k + K - 1));
116 
117  initial.insert(X(k), switching.linearizationPoint.at<double>(X(k)));
118 
119  linearized = *graph.linearize(initial);
120  Ordering ordering = smoother.getOrdering(linearized);
121 
122  smoother.update(linearized, 3, ordering);
123  graph.resize(0);
124  }
125 
126  HybridValues delta = smoother.hybridBayesNet().optimize();
127 
128  Values result = initial.retract(delta.continuous());
129 
130  DiscreteValues expected_discrete;
131  for (size_t k = 0; k < K - 1; k++) {
132  expected_discrete[M(k)] = discrete_seq[k];
133  }
134  EXPECT(assert_equal(expected_discrete, delta.discrete()));
135 
136  Values expected_continuous;
137  for (size_t k = 0; k < K; k++) {
138  expected_continuous.insert(X(k), measurements[k]);
139  }
140  EXPECT(assert_equal(expected_continuous, result));
141 }
142 
143 /****************************************************************************/
144 // Test approximate inference with an additional pruning step.
145 TEST(HybridEstimation, ISAM) {
146  size_t K = 15;
147  std::vector<double> measurements = {0, 1, 2, 2, 2, 2, 3, 4, 5, 6, 6,
148  7, 8, 9, 9, 9, 10, 11, 11, 11, 11};
149  // Ground truth discrete seq
150  std::vector<size_t> discrete_seq = {1, 1, 0, 0, 0, 1, 1, 1, 1, 0,
151  1, 1, 1, 0, 0, 1, 1, 0, 0, 0};
152  // Switching example of robot moving in 1D
153  // with given measurements and equal mode priors.
154  Switching switching(K, 1.0, 0.1, measurements, "1/1 1/1");
157  Values initial;
158 
159  // gttic_(Estimation);
160 
161  // Add the X(0) prior
162  graph.push_back(switching.nonlinearFactorGraph.at(0));
163  initial.insert(X(0), switching.linearizationPoint.at<double>(X(0)));
164 
165  HybridGaussianFactorGraph linearized;
166 
167  for (size_t k = 1; k < K; k++) {
168  // Motion Model
169  graph.push_back(switching.nonlinearFactorGraph.at(k));
170  // Measurement
171  graph.push_back(switching.nonlinearFactorGraph.at(k + K - 1));
172 
173  initial.insert(X(k), switching.linearizationPoint.at<double>(X(k)));
174 
175  isam.update(graph, initial, 3);
176  // isam.bayesTree().print("\n\n");
177 
178  graph.resize(0);
179  initial.clear();
180  }
181 
183  DiscreteValues assignment = isam.assignment();
184 
185  DiscreteValues expected_discrete;
186  for (size_t k = 0; k < K - 1; k++) {
187  expected_discrete[M(k)] = discrete_seq[k];
188  }
189  EXPECT(assert_equal(expected_discrete, assignment));
190 
191  Values expected_continuous;
192  for (size_t k = 0; k < K; k++) {
193  expected_continuous.insert(X(k), measurements[k]);
194  }
195  EXPECT(assert_equal(expected_continuous, result));
196 }
197 
211  size_t K, const std::vector<double>& measurements,
212  const std::vector<size_t>& discrete_seq, double measurement_sigma = 0.1,
213  double between_sigma = 1.0) {
215  Values linearizationPoint;
216 
217  // Add measurement factors
218  auto measurement_noise = noiseModel::Isotropic::Sigma(1, measurement_sigma);
219  for (size_t k = 0; k < K; k++) {
220  graph.emplace_shared<PriorFactor<double>>(X(k), measurements.at(k),
221  measurement_noise);
222  linearizationPoint.insert<double>(X(k), static_cast<double>(k + 1));
223  }
224 
226 
227  // Add "motion models".
228  auto motion_noise_model = noiseModel::Isotropic::Sigma(1, between_sigma);
229  for (size_t k = 0; k < K - 1; k++) {
230  auto motion_model = std::make_shared<MotionModel>(
231  X(k), X(k + 1), discrete_seq.at(k), motion_noise_model);
232  graph.push_back(motion_model);
233  }
234  GaussianFactorGraph::shared_ptr linear_graph =
235  graph.linearize(linearizationPoint);
236  return linear_graph;
237 }
238 
246 template <size_t K>
247 std::vector<size_t> getDiscreteSequence(size_t x) {
248  std::bitset<K - 1> seq = x;
249  std::vector<size_t> discrete_seq(K - 1);
250  for (size_t i = 0; i < K - 1; i++) {
251  // Save to discrete vector in reverse order
252  discrete_seq[K - 2 - i] = seq[i];
253  }
254  return discrete_seq;
255 }
256 
269  Ordering continuous(graph.continuousKeySet());
270  const auto [bayesNet, remainingGraph] =
271  graph.eliminatePartialSequential(continuous);
272 
273  auto last_conditional = bayesNet->at(bayesNet->size() - 1);
274  DiscreteKeys discrete_keys = last_conditional->discreteKeys();
275 
276  const std::vector<DiscreteValues> assignments =
277  DiscreteValues::CartesianProduct(discrete_keys);
278 
279  std::reverse(discrete_keys.begin(), discrete_keys.end());
280 
281  vector<VectorValues::shared_ptr> vector_values;
282  for (const DiscreteValues& assignment : assignments) {
283  VectorValues values = bayesNet->optimize(assignment);
284  vector_values.push_back(std::make_shared<VectorValues>(values));
285  }
286  DecisionTree<Key, VectorValues::shared_ptr> delta_tree(discrete_keys,
287  vector_values);
288 
289  // Get the probPrime tree with the correct leaf probabilities
290  std::vector<double> probPrimes;
291  for (const DiscreteValues& assignment : assignments) {
292  VectorValues delta = *delta_tree(assignment);
293 
294  // If VectorValues is empty, it means this is a pruned branch.
295  // Set the probPrime to 0.0.
296  if (delta.size() == 0) {
297  probPrimes.push_back(0.0);
298  continue;
299  }
300 
301  double error = graph.error({delta, assignment});
302  probPrimes.push_back(exp(-error));
303  }
304  AlgebraicDecisionTree<Key> probPrimeTree(discrete_keys, probPrimes);
305  return probPrimeTree;
306 }
307 
308 /*********************************************************************************
309  * Test for correctness of different branches of the P'(Continuous | Discrete).
310  * The values should match those of P'(Continuous) for each discrete mode.
311  ********************************************************************************/
312 TEST(HybridEstimation, Probability) {
313  constexpr size_t K = 4;
314  std::vector<double> measurements = {0, 1, 2, 2};
315  double between_sigma = 1.0, measurement_sigma = 0.1;
316 
317  // Switching example of robot moving in 1D with
318  // given measurements and equal mode priors.
319  Switching switching(K, between_sigma, measurement_sigma, measurements,
320  "1/1 1/1");
321  auto graph = switching.linearizedFactorGraph;
322 
323  // Continuous elimination
324  Ordering continuous_ordering(graph.continuousKeySet());
325  auto [bayesNet, discreteGraph] =
326  graph.eliminatePartialSequential(continuous_ordering);
327 
328  // Discrete elimination
329  Ordering discrete_ordering(graph.discreteKeySet());
330  auto discreteBayesNet = discreteGraph->eliminateSequential(discrete_ordering);
331 
332  // Add the discrete conditionals to make it a full bayes net.
333  for (auto discrete_conditional : *discreteBayesNet) {
334  bayesNet->add(discrete_conditional);
335  }
336  auto discreteConditional = discreteBayesNet->at(0)->asDiscrete();
337 
338  HybridValues hybrid_values = bayesNet->optimize();
339 
340  // This is the correct sequence as designed
341  DiscreteValues discrete_seq;
342  discrete_seq[M(0)] = 1;
343  discrete_seq[M(1)] = 1;
344  discrete_seq[M(2)] = 0;
345 
346  EXPECT(assert_equal(discrete_seq, hybrid_values.discrete()));
347 }
348 
349 /****************************************************************************/
355 TEST(HybridEstimation, ProbabilityMultifrontal) {
356  constexpr size_t K = 4;
357  std::vector<double> measurements = {0, 1, 2, 2};
358 
359  double between_sigma = 1.0, measurement_sigma = 0.1;
360 
361  // Switching example of robot moving in 1D with given measurements and equal
362  // mode priors.
363  Switching switching(K, between_sigma, measurement_sigma, measurements,
364  "1/1 1/1");
365  auto graph = switching.linearizedFactorGraph;
366 
367  // Get the tree of unnormalized probabilities for each mode sequence.
368  AlgebraicDecisionTree<Key> expected_probPrimeTree = getProbPrimeTree(graph);
369 
370  // Eliminate continuous
371  Ordering continuous_ordering(graph.continuousKeySet());
372  const auto [bayesTree, discreteGraph] =
373  graph.eliminatePartialMultifrontal(continuous_ordering);
374 
375  // Get the last continuous conditional which will have all the discrete keys
376  Key last_continuous_key =
377  continuous_ordering.at(continuous_ordering.size() - 1);
378  auto last_conditional = (*bayesTree)[last_continuous_key]->conditional();
379  DiscreteKeys discrete_keys = last_conditional->discreteKeys();
380 
381  Ordering discrete(graph.discreteKeySet());
382  auto discreteBayesTree = discreteGraph->eliminateMultifrontal(discrete);
383 
384  EXPECT_LONGS_EQUAL(1, discreteBayesTree->size());
385  // DiscreteBayesTree should have only 1 clique
386  auto discrete_clique = (*discreteBayesTree)[discrete.at(0)];
387 
388  std::set<HybridBayesTreeClique::shared_ptr> clique_set;
389  for (auto node : bayesTree->nodes()) {
390  clique_set.insert(node.second);
391  }
392 
393  // Set the root of the bayes tree as the discrete clique
394  for (auto clique : clique_set) {
395  if (clique->conditional()->parents() ==
396  discrete_clique->conditional()->frontals()) {
397  discreteBayesTree->addClique(clique, discrete_clique);
398 
399  } else {
400  // Remove the clique from the children of the parents since
401  // it will get added again in addClique.
402  auto clique_it = std::find(clique->parent()->children.begin(),
403  clique->parent()->children.end(), clique);
404  clique->parent()->children.erase(clique_it);
405  discreteBayesTree->addClique(clique, clique->parent());
406  }
407  }
408 
409  HybridValues hybrid_values = discreteBayesTree->optimize();
410 
411  // This is the correct sequence as designed
412  DiscreteValues discrete_seq;
413  discrete_seq[M(0)] = 1;
414  discrete_seq[M(1)] = 1;
415  discrete_seq[M(2)] = 0;
416 
417  EXPECT(assert_equal(discrete_seq, hybrid_values.discrete()));
418 }
419 
420 /*********************************************************************************
421  // Create a hybrid nonlinear factor graph f(x0, x1, m0; z0, z1)
422  ********************************************************************************/
425 
426  constexpr double sigma = 0.5; // measurement noise
427  const auto noise_model = noiseModel::Isotropic::Sigma(1, sigma);
428 
429  // Add "measurement" factors:
430  nfg.emplace_shared<PriorFactor<double>>(X(0), 0.0, noise_model);
431  nfg.emplace_shared<PriorFactor<double>>(X(1), 1.0, noise_model);
432 
433  // Add mixture factor:
434  DiscreteKey m(M(0), 2);
435  const auto zero_motion =
436  std::make_shared<BetweenFactor<double>>(X(0), X(1), 0, noise_model);
437  const auto one_motion =
438  std::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
440  KeyVector{X(0), X(1)}, DiscreteKeys{m},
441  std::vector<NonlinearFactor::shared_ptr>{zero_motion, one_motion});
442 
443  return nfg;
444 }
445 
446 /*********************************************************************************
447  // Create a hybrid linear factor graph f(x0, x1, m0; z0, z1)
448  ********************************************************************************/
451 
452  Values initial;
453  double z0 = 0.0, z1 = 1.0;
454  initial.insert<double>(X(0), z0);
455  initial.insert<double>(X(1), z1);
456  return nfg.linearize(initial);
457 }
458 
459 /*********************************************************************************
460  * Do hybrid elimination and do regression test on discrete conditional.
461  ********************************************************************************/
462 TEST(HybridEstimation, eliminateSequentialRegression) {
463  // Create the factor graph from the nonlinear factor graph.
465 
466  // Create expected discrete conditional on m0.
467  DiscreteKey m(M(0), 2);
468  DiscreteConditional expected(m % "0.51341712/1"); // regression
469 
470  // Eliminate into BN using one ordering
471  const Ordering ordering1{X(0), X(1), M(0)};
472  HybridBayesNet::shared_ptr bn1 = fg->eliminateSequential(ordering1);
473 
474  // Check that the discrete conditional matches the expected.
475  auto dc1 = bn1->back()->asDiscrete();
476  EXPECT(assert_equal(expected, *dc1, 1e-9));
477 
478  // Eliminate into BN using a different ordering
479  const Ordering ordering2{X(0), X(1), M(0)};
480  HybridBayesNet::shared_ptr bn2 = fg->eliminateSequential(ordering2);
481 
482  // Check that the discrete conditional matches the expected.
483  auto dc2 = bn2->back()->asDiscrete();
484  EXPECT(assert_equal(expected, *dc2, 1e-9));
485 }
486 
487 /*********************************************************************************
488  * Test for correctness via sampling.
489  *
490  * Compute the conditional P(x0, m0, x1| z0, z1)
491  * with measurements z0, z1. To do so, we:
492  * 1. Start with the corresponding Factor Graph `FG`.
493  * 2. Eliminate the factor graph into a Bayes Net `BN`.
494  * 3. Sample from the Bayes Net.
495  * 4. Check that the ratio `BN(x)/FG(x) = constant` for all samples `x`.
496  ********************************************************************************/
497 TEST(HybridEstimation, CorrectnessViaSampling) {
498  // 1. Create the factor graph from the nonlinear factor graph.
499  const auto fg = createHybridGaussianFactorGraph();
500 
501  // 2. Eliminate into BN
502  const HybridBayesNet::shared_ptr bn = fg->eliminateSequential();
503 
504  // Set up sampling
505  std::mt19937_64 rng(11);
506 
507  // Compute the log-ratio between the Bayes net and the factor graph.
508  auto compute_ratio = [&](const HybridValues& sample) -> double {
509  return bn->evaluate(sample) / fg->probPrime(sample);
510  };
511 
512  // The error evaluated by the factor graph and the Bayes net should differ by
513  // the normalizing term computed via the Bayes net determinant.
514  const HybridValues sample = bn->sample(&rng);
515  double expected_ratio = compute_ratio(sample);
516  // regression
517  EXPECT_DOUBLES_EQUAL(0.728588, expected_ratio, 1e-6);
518 
519  // 3. Do sampling
520  constexpr int num_samples = 10;
521  for (size_t i = 0; i < num_samples; i++) {
522  // Sample from the bayes net
523  const HybridValues sample = bn->sample(&rng);
524 
525  // 4. Check that the ratio is constant.
526  EXPECT_DOUBLES_EQUAL(expected_ratio, compute_ratio(sample), 1e-6);
527  }
528 }
529 
530 /****************************************************************************/
535 std::shared_ptr<GaussianMixtureFactor> mixedVarianceFactor(
536  const MixtureFactor& mf, const Values& initial, const Key& mode,
537  double noise_tight, double noise_loose, size_t d, size_t tight_index) {
539 
540  constexpr double log2pi = 1.8378770664093454835606594728112;
541  // logConstant will be of the tighter model
542  double logNormalizationConstant = log(1.0 / noise_tight);
543  double logConstant = -0.5 * d * log2pi + logNormalizationConstant;
544 
545  auto func = [&](const Assignment<Key>& assignment,
546  const GaussianFactor::shared_ptr& gf) {
547  if (assignment.at(mode) != tight_index) {
548  double factor_log_constant = -0.5 * d * log2pi + log(1.0 / noise_loose);
549 
550  GaussianFactorGraph _gfg;
551  _gfg.push_back(gf);
552  Vector c(d);
553  for (size_t i = 0; i < d; i++) {
554  c(i) = std::sqrt(2.0 * (logConstant - factor_log_constant));
555  }
556 
558  return std::make_shared<JacobianFactor>(_gfg);
559  } else {
560  return dynamic_pointer_cast<JacobianFactor>(gf);
561  }
562  };
563  auto updated_components = gmf->factors().apply(func);
564  auto updated_gmf = std::make_shared<GaussianMixtureFactor>(
565  gmf->continuousKeys(), gmf->discreteKeys(), updated_components);
566 
567  return updated_gmf;
568 }
569 
570 /****************************************************************************/
571 TEST(HybridEstimation, ModeSelection) {
573  Values initial;
574 
575  auto measurement_model = noiseModel::Isotropic::Sigma(1, 0.1);
576  auto motion_model = noiseModel::Isotropic::Sigma(1, 1.0);
577 
578  graph.emplace_shared<PriorFactor<double>>(X(0), 0.0, measurement_model);
579  graph.emplace_shared<PriorFactor<double>>(X(1), 0.0, measurement_model);
580 
581  DiscreteKeys modes;
582  modes.emplace_back(M(0), 2);
583 
584  // The size of the noise model
585  size_t d = 1;
586  double noise_tight = 0.5, noise_loose = 5.0;
587 
588  auto model0 = std::make_shared<MotionModel>(
589  X(0), X(1), 0.0, noiseModel::Isotropic::Sigma(d, noise_loose)),
590  model1 = std::make_shared<MotionModel>(
591  X(0), X(1), 0.0, noiseModel::Isotropic::Sigma(d, noise_tight));
592 
593  std::vector<NonlinearFactor::shared_ptr> components = {model0, model1};
594 
595  KeyVector keys = {X(0), X(1)};
596  MixtureFactor mf(keys, modes, components);
597 
598  initial.insert(X(0), 0.0);
599  initial.insert(X(1), 0.0);
600 
601  auto gmf =
602  mixedVarianceFactor(mf, initial, M(0), noise_tight, noise_loose, d, 1);
603  graph.add(gmf);
604 
605  auto gfg = graph.linearize(initial);
606 
607  HybridBayesNet::shared_ptr bayesNet = gfg->eliminateSequential();
608 
609  HybridValues delta = bayesNet->optimize();
610  EXPECT_LONGS_EQUAL(1, delta.discrete().at(M(0)));
611 
612  /**************************************************************/
613  HybridBayesNet bn;
614  const DiscreteKey mode{M(0), 2};
615 
616  bn.push_back(
617  GaussianConditional::sharedMeanAndStddev(Z(0), -I_1x1, X(0), Z_1x1, 0.1));
618  bn.push_back(
619  GaussianConditional::sharedMeanAndStddev(Z(0), -I_1x1, X(1), Z_1x1, 0.1));
621  {Z(0)}, {X(0), X(1)}, {mode},
622  {GaussianConditional::sharedMeanAndStddev(Z(0), I_1x1, X(0), -I_1x1, X(1),
623  Z_1x1, noise_loose),
624  GaussianConditional::sharedMeanAndStddev(Z(0), I_1x1, X(0), -I_1x1, X(1),
625  Z_1x1, noise_tight)}));
626 
628  vv.insert(Z(0), Z_1x1);
629 
630  auto fg = bn.toFactorGraph(vv);
631  auto expected_posterior = fg.eliminateSequential();
632 
633  EXPECT(assert_equal(*expected_posterior, *bayesNet, 1e-6));
634 }
635 
636 /****************************************************************************/
637 TEST(HybridEstimation, ModeSelection2) {
638  using symbol_shorthand::Z;
639 
640  // The size of the noise model
641  size_t d = 3;
642  double noise_tight = 0.5, noise_loose = 5.0;
643 
644  HybridBayesNet bn;
645  const DiscreteKey mode{M(0), 2};
646 
647  bn.push_back(
648  GaussianConditional::sharedMeanAndStddev(Z(0), -I_3x3, X(0), Z_3x1, 0.1));
649  bn.push_back(
650  GaussianConditional::sharedMeanAndStddev(Z(0), -I_3x3, X(1), Z_3x1, 0.1));
652  {Z(0)}, {X(0), X(1)}, {mode},
653  {GaussianConditional::sharedMeanAndStddev(Z(0), I_3x3, X(0), -I_3x3, X(1),
654  Z_3x1, noise_loose),
655  GaussianConditional::sharedMeanAndStddev(Z(0), I_3x3, X(0), -I_3x3, X(1),
656  Z_3x1, noise_tight)}));
657 
659  vv.insert(Z(0), Z_3x1);
660 
661  auto fg = bn.toFactorGraph(vv);
662 
663  auto expected_posterior = fg.eliminateSequential();
664 
665  // =====================================
666 
668  Values initial;
669 
670  auto measurement_model = noiseModel::Isotropic::Sigma(d, 0.1);
671  auto motion_model = noiseModel::Isotropic::Sigma(d, 1.0);
672 
673  graph.emplace_shared<PriorFactor<Vector3>>(X(0), Z_3x1, measurement_model);
674  graph.emplace_shared<PriorFactor<Vector3>>(X(1), Z_3x1, measurement_model);
675 
676  DiscreteKeys modes;
677  modes.emplace_back(M(0), 2);
678 
679  auto model0 = std::make_shared<BetweenFactor<Vector3>>(
680  X(0), X(1), Z_3x1, noiseModel::Isotropic::Sigma(d, noise_loose)),
682  X(0), X(1), Z_3x1, noiseModel::Isotropic::Sigma(d, noise_tight));
683 
684  std::vector<NonlinearFactor::shared_ptr> components = {model0, model1};
685 
686  KeyVector keys = {X(0), X(1)};
687  MixtureFactor mf(keys, modes, components);
688 
689  initial.insert<Vector3>(X(0), Z_3x1);
690  initial.insert<Vector3>(X(1), Z_3x1);
691 
692  auto gmf =
693  mixedVarianceFactor(mf, initial, M(0), noise_tight, noise_loose, d, 1);
694  graph.add(gmf);
695 
696  auto gfg = graph.linearize(initial);
697 
698  HybridBayesNet::shared_ptr bayesNet = gfg->eliminateSequential();
699 
700  EXPECT(assert_equal(*expected_posterior, *bayesNet, 1e-6));
701 }
702 
703 /* ************************************************************************* */
704 int main() {
705  TestResult tr;
706  return TestRegistry::runAllTests(tr);
707 }
708 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::HybridSmoother::hybridBayesNet
const HybridBayesNet & hybridBayesNet() const
Return the Bayes Net posterior.
Definition: HybridSmoother.cpp:147
gtsam::HybridGaussianFactorGraph::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to This
Definition: HybridGaussianFactorGraph.h:118
gtsam::HybridSmoother::update
void update(HybridGaussianFactorGraph graph, std::optional< size_t > maxNrLeaves={}, const std::optional< Ordering > given_ordering={})
Definition: HybridSmoother.cpp:59
gtsam::EliminateableFactorGraph::eliminateSequential
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Definition: EliminateableFactorGraph-inst.h:29
Pose2.h
2D Pose
DiscreteBayesNet.h
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::HybridValues
Definition: HybridValues.h:38
gtsam::GaussianFactorGraph::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactorGraph.h:82
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Z_3x1
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
HybridNonlinearFactorGraph.h
Nonlinear hybrid factor graph that uses type erasure.
main
int main()
Definition: testHybridEstimation.cpp:704
TestHarness.h
gtsam::HybridBayesNet
Definition: HybridBayesNet.h:35
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::HybridNonlinearFactorGraph
Definition: HybridNonlinearFactorGraph.h:33
gtsam::VectorValues::insert
iterator insert(const std::pair< Key, Vector > &key_value)
Definition: VectorValues.cpp:88
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
z1
Point2 z1
Definition: testTriangulationFactor.cpp:45
initial
Values initial
Definition: OdometryOptimize.cpp:2
Switching.h
gtsam::GaussianMixture
A conditional of gaussian mixtures indexed by discrete variables, as part of a Bayes Network....
Definition: GaussianMixture.h:53
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
HybridBayesNet.h
A Bayes net of Gaussian Conditionals indexed by discrete keys.
createHybridNonlinearFactorGraph
static HybridNonlinearFactorGraph createHybridNonlinearFactorGraph()
Definition: testHybridEstimation.cpp:423
log
const EIGEN_DEVICE_FUNC LogReturnType log() const
Definition: ArrayCwiseUnaryOps.h:128
gtsam::NonlinearFactorGraph::linearize
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Definition: NonlinearFactorGraph.cpp:239
X
#define X
Definition: icosphere.cpp:20
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
GaussianBayesNet.h
Chordal Bayes Net, the result of eliminating a factor graph.
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
exp
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
Definition: ArrayCwiseUnaryOps.h:97
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
result
Values result
Definition: OdometryOptimize.cpp:8
HybridSmoother.h
An incremental smoother for hybrid factor graphs.
gtsam::NonlinearISAM::update
void update(const NonlinearFactorGraph &newFactors, const Values &initialValues)
Definition: NonlinearISAM.cpp:35
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:169
specificModesFactorGraph
GaussianFactorGraph::shared_ptr specificModesFactorGraph(size_t K, const std::vector< double > &measurements, const std::vector< size_t > &discrete_seq, double measurement_sigma=0.1, double between_sigma=1.0)
A function to get a specific 1D robot motion problem as a linearized factor graph....
Definition: testHybridEstimation.cpp:210
gtsam::AlgebraicDecisionTree< Key >
gtsam::Switching
Definition: Switching.h:120
mixedVarianceFactor
std::shared_ptr< GaussianMixtureFactor > mixedVarianceFactor(const MixtureFactor &mf, const Values &initial, const Key &mode, double noise_tight, double noise_loose, size_t d, size_t tight_index)
Definition: testHybridEstimation.cpp:535
gtsam::FactorGraph::at
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:306
gtsam::HybridBayesNet::optimize
HybridValues optimize() const
Solve the HybridBayesNet by first computing the MPE of all the discrete variables and then optimizing...
Definition: HybridBayesNet.cpp:221
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
PriorFactor.h
gtsam::GaussianMixtureFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: GaussianMixtureFactor.h:51
gtsam::FactorGraph::resize
virtual void resize(size_t size)
Definition: FactorGraph.h:367
vv
static const VectorValues vv
Definition: testGaussianMixture.cpp:42
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::VectorValues
Definition: VectorValues.h:74
BetweenFactor.h
isam
NonlinearISAM isam(relinearizeInterval)
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::make_shared
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, std::shared_ptr< T > > make_shared(Args &&... args)
Definition: make_shared.h:56
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::HybridGaussianFactorGraph
Definition: HybridGaussianFactorGraph.h:104
mf
Matrix2f mf
Definition: MatrixBase_cast.cpp:2
gtsam::HybridNonlinearISAM
Definition: HybridNonlinearISAM.h:28
gtsam::NonlinearISAM::estimate
Values estimate() const
Definition: NonlinearISAM.cpp:80
Symbol.h
gtsam::Assignment< Key >
TEST
TEST(HybridEstimation, Full)
Definition: testHybridEstimation.cpp:49
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::HybridSmoother::getOrdering
Ordering getOrdering(const HybridGaussianFactorGraph &newFactors)
Definition: HybridSmoother.cpp:27
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
MixtureFactor.h
Nonlinear Mixture factor of continuous and discrete.
ordering
static enum @1096 ordering
TestResult
Definition: TestResult.h:26
JacobianFactor.h
gtsam::DecisionTree
a decision tree is a function from assignments to values.
Definition: DecisionTree.h:63
gtsam::HybridSmoother
Definition: HybridSmoother.h:27
gtsam::HybridValues::discrete
const DiscreteValues & discrete() const
Return the discrete values.
Definition: HybridValues.h:92
gtsam::HybridBayesNet::push_back
void push_back(std::shared_ptr< HybridConditional > conditional)
Add a hybrid conditional using a shared_ptr.
Definition: HybridBayesNet.h:69
gtsam::DiscreteConditional
Definition: DiscreteConditional.h:37
gtsam
traits
Definition: chartTesting.h:28
error
static double error
Definition: testRot3.cpp:37
NoiseModel.h
K
#define K
Definition: igam.h:8
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
leaf::values
leaf::MyValues values
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
gtsam::Values
Definition: Values.h:65
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std
Definition: BFloat16.h:88
gtsam::Switching::linearizationPoint
Values linearizationPoint
Definition: Switching.h:125
gtsam::HybridBayesNet::emplace_back
void emplace_back(Conditional *conditional)
Definition: HybridBayesNet.h:82
getDiscreteSequence
std::vector< size_t > getDiscreteSequence(size_t x)
Get the discrete sequence from the integer x.
Definition: testHybridEstimation.cpp:247
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::HybridNonlinearFactorGraph::linearize
std::shared_ptr< HybridGaussianFactorGraph > linearize(const Values &continuousValues) const
Linearize all the continuous factors in the HybridNonlinearFactorGraph.
Definition: HybridNonlinearFactorGraph.cpp:138
GaussianBayesTree.h
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
HybridNonlinearISAM.h
gtsam::Switching::linearizedFactorGraph
HybridGaussianFactorGraph linearizedFactorGraph
Definition: Switching.h:124
gtsam::MixtureFactor
Implementation of a discrete conditional mixture factor.
Definition: MixtureFactor.h:47
initial
Definition: testScenarioRunner.cpp:148
mode
static const DiscreteKey mode(modeKey, 2)
gtsam::ISAM
Definition: ISAM.h:31
reverse
void reverse(const MatrixType &m)
Definition: array_reverse.cpp:16
gtsam::HybridBayesNet::shared_ptr
std::shared_ptr< HybridBayesNet > shared_ptr
Definition: HybridBayesNet.h:40
getProbPrimeTree
AlgebraicDecisionTree< Key > getProbPrimeTree(const HybridGaussianFactorGraph &graph)
Helper method to get the tree of unnormalized probabilities as per the elimination scheme.
Definition: testHybridEstimation.cpp:267
func
Definition: benchGeometry.cpp:23
gtsam::HybridBayesNet::toFactorGraph
HybridGaussianFactorGraph toFactorGraph(const VectorValues &measurements) const
Definition: HybridBayesNet.cpp:359
gtsam::FactorGraph::add
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:171
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
createHybridGaussianFactorGraph
static HybridGaussianFactorGraph::shared_ptr createHybridGaussianFactorGraph()
Definition: testHybridEstimation.cpp:449
model1
noiseModel::Isotropic::shared_ptr model1
Definition: testEssentialMatrixFactor.cpp:26
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
Z
#define Z
Definition: icosphere.cpp:21
gtsam::Ordering
Definition: inference/Ordering.h:33
Eigen::seq
internal::enable_if<!(symbolic::is_symbolic< FirstType >::value||symbolic::is_symbolic< LastType >::value), ArithmeticSequence< typename internal::cleanup_index_type< FirstType >::type, Index > >::type seq(FirstType f, LastType l)
Definition: ArithmeticSequence.h:234
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Pose3.h
3D Pose
gtsam::Switching::nonlinearFactorGraph
HybridNonlinearFactorGraph nonlinearFactorGraph
Definition: Switching.h:123
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:05:58