testHybridGaussianFactorGraph.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 
12 /*
13  * @file testHybridGaussianFactorGraph.cpp
14  * @date Mar 11, 2022
15  * @author Fan Jiang
16  */
17 
18 #include <CppUnitLite/Test.h>
35 #include <gtsam/inference/Key.h>
37 #include <gtsam/inference/Symbol.h>
39 
40 #include <algorithm>
41 #include <cstddef>
42 #include <functional>
43 #include <iostream>
44 #include <iterator>
45 #include <vector>
46 
47 #include "Switching.h"
48 #include "TinyHybridExample.h"
49 
50 using namespace std;
51 using namespace gtsam;
52 
59 
60 // Set up sampling
61 std::mt19937_64 kRng(42);
62 
63 /* ************************************************************************* */
65  HybridConditional conditional;
66 
68 
69  hfg.emplace_shared<JacobianFactor>(X(0), I_3x3, Z_3x1);
70 
71  // Define a gaussian mixture conditional P(x0|x1, c0) and add it to the factor
72  // graph
73  GaussianMixture gm({X(0)}, {X(1)}, DiscreteKeys(DiscreteKey{M(0), 2}),
75  M(0),
76  std::make_shared<GaussianConditional>(
77  X(0), Z_3x1, I_3x3, X(1), I_3x3),
78  std::make_shared<GaussianConditional>(
79  X(0), Vector3::Ones(), I_3x3, X(1), I_3x3)));
80  hfg.add(gm);
81 
82  EXPECT_LONGS_EQUAL(2, hfg.size());
83 }
84 
85 /* ************************************************************************* */
86 TEST(HybridGaussianFactorGraph, EliminateSequential) {
87  // Test elimination of a single variable.
89 
90  hfg.emplace_shared<JacobianFactor>(0, I_3x3, Z_3x1);
91 
93 
94  EXPECT_LONGS_EQUAL(result.first->size(), 1);
95 }
96 
97 /* ************************************************************************* */
98 TEST(HybridGaussianFactorGraph, EliminateMultifrontal) {
99  // Test multifrontal elimination
101 
102  DiscreteKey m(M(1), 2);
103 
104  // Add priors on x0 and c1
105  hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1));
106  hfg.add(DecisionTreeFactor(m, {2, 8}));
107 
109  ordering.push_back(X(0));
110  auto result = hfg.eliminatePartialMultifrontal(ordering);
111 
112  EXPECT_LONGS_EQUAL(result.first->size(), 1);
113  EXPECT_LONGS_EQUAL(result.second->size(), 1);
114 }
115 
116 /* ************************************************************************* */
117 TEST(HybridGaussianFactorGraph, eliminateFullSequentialEqualChance) {
119 
120  // Add prior on x0
121  hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1));
122 
123  // Add factor between x0 and x1
124  hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1));
125 
126  // Add a gaussian mixture factor ϕ(x1, c1)
127  DiscreteKey m1(M(1), 2);
129  M(1), std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
130  std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones()));
131  hfg.add(GaussianMixtureFactor({X(1)}, {m1}, dt));
132 
133  auto result = hfg.eliminateSequential();
134 
135  auto dc = result->at(2)->asDiscrete();
136  CHECK(dc);
137  DiscreteValues dv;
138  dv[M(1)] = 0;
139  // Regression test
140  EXPECT_DOUBLES_EQUAL(0.62245933120185448, dc->operator()(dv), 1e-3);
141 }
142 
143 /* ************************************************************************* */
144 TEST(HybridGaussianFactorGraph, eliminateFullSequentialSimple) {
146 
147  DiscreteKey m1(M(1), 2);
148 
149  // Add prior on x0
150  hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1));
151  // Add factor between x0 and x1
152  hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1));
153 
154  std::vector<GaussianFactor::shared_ptr> factors = {
155  std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
156  std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones())};
157  hfg.add(GaussianMixtureFactor({X(1)}, {m1}, factors));
158 
159  // Discrete probability table for c1
160  hfg.add(DecisionTreeFactor(m1, {2, 8}));
161  // Joint discrete probability table for c1, c2
162  hfg.add(DecisionTreeFactor({{M(1), 2}, {M(2), 2}}, "1 2 3 4"));
163 
165 
166  // There are 4 variables (2 continuous + 2 discrete) in the bayes net.
167  EXPECT_LONGS_EQUAL(4, result->size());
168 }
169 
170 /* ************************************************************************* */
171 TEST(HybridGaussianFactorGraph, eliminateFullMultifrontalSimple) {
173 
174  DiscreteKey m1(M(1), 2);
175 
176  hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1));
177  hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1));
178 
180  {X(1)}, {{M(1), 2}},
181  {std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
182  std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones())}));
183 
184  hfg.add(DecisionTreeFactor(m1, {2, 8}));
185  // TODO(Varun) Adding extra discrete variable not connected to continuous
186  // variable throws segfault
187  // hfg.add(DecisionTreeFactor({{M(1), 2}, {M(2), 2}}, "1 2 3 4"));
188 
190 
191  // The bayes tree should have 3 cliques
192  EXPECT_LONGS_EQUAL(3, result->size());
193  // GTSAM_PRINT(*result);
194  // GTSAM_PRINT(*result->marginalFactor(M(2)));
195 }
196 
197 /* ************************************************************************* */
198 TEST(HybridGaussianFactorGraph, eliminateFullMultifrontalCLG) {
200 
201  DiscreteKey m(M(1), 2);
202 
203  // Prior on x0
204  hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1));
205  // Factor between x0-x1
206  hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1));
207 
208  // Decision tree with different modes on x1
210  M(1), std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
211  std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones()));
212 
213  // Hybrid factor P(x1|c1)
214  hfg.add(GaussianMixtureFactor({X(1)}, {m}, dt));
215  // Prior factor on c1
216  hfg.add(DecisionTreeFactor(m, {2, 8}));
217 
218  // Get a constrained ordering keeping c1 last
219  auto ordering_full = HybridOrdering(hfg);
220 
221  // Returns a Hybrid Bayes Tree with distribution P(x0|x1)P(x1|c1)P(c1)
222  HybridBayesTree::shared_ptr hbt = hfg.eliminateMultifrontal(ordering_full);
223 
224  EXPECT_LONGS_EQUAL(3, hbt->size());
225 }
226 
227 /* ************************************************************************* */
228 /*
229  * This test is about how to assemble the Bayes Tree roots after we do partial
230  * elimination
231  */
232 TEST(HybridGaussianFactorGraph, eliminateFullMultifrontalTwoClique) {
234 
235  hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1));
236  hfg.add(JacobianFactor(X(1), I_3x3, X(2), -I_3x3, Z_3x1));
237 
238  {
240  {X(0)}, {{M(0), 2}},
241  {std::make_shared<JacobianFactor>(X(0), I_3x3, Z_3x1),
242  std::make_shared<JacobianFactor>(X(0), I_3x3, Vector3::Ones())}));
243 
245  M(1), std::make_shared<JacobianFactor>(X(2), I_3x3, Z_3x1),
246  std::make_shared<JacobianFactor>(X(2), I_3x3, Vector3::Ones()));
247 
248  hfg.add(GaussianMixtureFactor({X(2)}, {{M(1), 2}}, dt1));
249  }
250 
251  hfg.add(DecisionTreeFactor({{M(1), 2}, {M(2), 2}}, "1 2 3 4"));
252 
253  hfg.add(JacobianFactor(X(3), I_3x3, X(4), -I_3x3, Z_3x1));
254  hfg.add(JacobianFactor(X(4), I_3x3, X(5), -I_3x3, Z_3x1));
255 
256  {
258  M(3), std::make_shared<JacobianFactor>(X(3), I_3x3, Z_3x1),
259  std::make_shared<JacobianFactor>(X(3), I_3x3, Vector3::Ones()));
260 
261  hfg.add(GaussianMixtureFactor({X(3)}, {{M(3), 2}}, dt));
262 
264  M(2), std::make_shared<JacobianFactor>(X(5), I_3x3, Z_3x1),
265  std::make_shared<JacobianFactor>(X(5), I_3x3, Vector3::Ones()));
266 
267  hfg.add(GaussianMixtureFactor({X(5)}, {{M(2), 2}}, dt1));
268  }
269 
270  auto ordering_full =
271  Ordering::ColamdConstrainedLast(hfg, {M(0), M(1), M(2), M(3)});
272 
273  const auto [hbt, remaining] = hfg.eliminatePartialMultifrontal(ordering_full);
274 
275  // 9 cliques in the bayes tree and 0 remaining variables to eliminate.
276  EXPECT_LONGS_EQUAL(9, hbt->size());
277  EXPECT_LONGS_EQUAL(0, remaining->size());
278 
279  /*
280  (Fan) Explanation: the Junction tree will need to reeliminate to get to the
281  marginal on X(1), which is not possible because it involves eliminating
282  discrete before continuous. The solution to this, however, is in Murphy02.
283  TLDR is that this is 1. expensive and 2. inexact. nevertheless it is doable.
284  And I believe that we should do this.
285  */
286 }
287 
289  const HybridBayesTree::shared_ptr &hbt,
290  const Ordering &ordering) {
291  DotWriter dw;
292  dw.positionHints['c'] = 2;
293  dw.positionHints['x'] = 1;
294  std::cout << hfg->dot(DefaultKeyFormatter, dw);
295  std::cout << "\n";
296  hbt->dot(std::cout);
297 
298  std::cout << "\n";
299  std::cout << hfg->eliminateSequential(ordering)->dot(DefaultKeyFormatter, dw);
300 }
301 
302 /* ************************************************************************* */
303 // TODO(fan): make a graph like Varun's paper one
305  auto N = 12;
306  auto hfg = makeSwitchingChain(N);
307 
308  // X(5) will be the center, X(1-4), X(6-9)
309  // X(3), X(7)
310  // X(2), X(8)
311  // X(1), X(4), X(6), X(9)
312  // M(5) will be the center, M(1-4), M(6-8)
313  // M(3), M(7)
314  // M(1), M(4), M(2), M(6), M(8)
315  // auto ordering_full =
316  // Ordering(KeyVector{X(1), X(4), X(2), X(6), X(9), X(8), X(3), X(7),
317  // X(5),
318  // M(1), M(4), M(2), M(6), M(8), M(3), M(7), M(5)});
320 
321  {
322  std::vector<int> naturalX(N);
323  std::iota(naturalX.begin(), naturalX.end(), 1);
324  std::vector<Key> ordX;
325  std::transform(naturalX.begin(), naturalX.end(), std::back_inserter(ordX),
326  [](int x) { return X(x); });
327 
328  auto [ndX, lvls] = makeBinaryOrdering(ordX);
329  std::copy(ndX.begin(), ndX.end(), std::back_inserter(ordering));
330  // TODO(dellaert): this has no effect!
331  for (auto &l : lvls) {
332  l = -l;
333  }
334  }
335  {
336  std::vector<int> naturalC(N - 1);
337  std::iota(naturalC.begin(), naturalC.end(), 1);
338  std::vector<Key> ordC;
339  std::transform(naturalC.begin(), naturalC.end(), std::back_inserter(ordC),
340  [](int x) { return M(x); });
341 
342  // std::copy(ordC.begin(), ordC.end(), std::back_inserter(ordering));
343  const auto [ndC, lvls] = makeBinaryOrdering(ordC);
344  std::copy(ndC.begin(), ndC.end(), std::back_inserter(ordering));
345  }
346  auto ordering_full = Ordering(ordering);
347 
348  // GTSAM_PRINT(*hfg);
349  // GTSAM_PRINT(ordering_full);
350 
351  const auto [hbt, remaining] =
352  hfg->eliminatePartialMultifrontal(ordering_full);
353 
354  // 12 cliques in the bayes tree and 0 remaining variables to eliminate.
355  EXPECT_LONGS_EQUAL(12, hbt->size());
356  EXPECT_LONGS_EQUAL(0, remaining->size());
357 }
358 
359 /* ************************************************************************* */
360 // TODO(fan): make a graph like Varun's paper one
362  auto N = 11;
363  auto hfg = makeSwitchingChain(N);
364 
365  // X(5) will be the center, X(1-4), X(6-9)
366  // X(3), X(7)
367  // X(2), X(8)
368  // X(1), X(4), X(6), X(9)
369  // M(5) will be the center, M(1-4), M(6-8)
370  // M(3), M(7)
371  // M(1), M(4), M(2), M(6), M(8)
372  // auto ordering_full =
373  // Ordering(KeyVector{X(1), X(4), X(2), X(6), X(9), X(8), X(3), X(7),
374  // X(5),
375  // M(1), M(4), M(2), M(6), M(8), M(3), M(7), M(5)});
377 
378  {
379  std::vector<int> naturalX(N);
380  std::iota(naturalX.begin(), naturalX.end(), 1);
381  std::vector<Key> ordX;
382  std::transform(naturalX.begin(), naturalX.end(), std::back_inserter(ordX),
383  [](int x) { return X(x); });
384 
385  auto [ndX, lvls] = makeBinaryOrdering(ordX);
386  std::copy(ndX.begin(), ndX.end(), std::back_inserter(ordering));
387  // TODO(dellaert): this has no effect!
388  for (auto &l : lvls) {
389  l = -l;
390  }
391  }
392  {
393  std::vector<int> naturalC(N - 1);
394  std::iota(naturalC.begin(), naturalC.end(), 1);
395  std::vector<Key> ordC;
396  std::transform(naturalC.begin(), naturalC.end(), std::back_inserter(ordC),
397  [](int x) { return M(x); });
398 
399  // std::copy(ordC.begin(), ordC.end(), std::back_inserter(ordering));
400  const auto [ndC, lvls] = makeBinaryOrdering(ordC);
401  std::copy(ndC.begin(), ndC.end(), std::back_inserter(ordering));
402  }
403  auto ordering_full = Ordering(ordering);
404 
405  const auto [hbt, remaining] =
406  hfg->eliminatePartialMultifrontal(ordering_full);
407 
408  auto new_fg = makeSwitchingChain(12);
409  auto isam = HybridGaussianISAM(*hbt);
410 
411  // Run an ISAM update.
412  HybridGaussianFactorGraph factorGraph;
413  factorGraph.push_back(new_fg->at(new_fg->size() - 2));
414  factorGraph.push_back(new_fg->at(new_fg->size() - 1));
415  isam.update(factorGraph);
416 
417  // ISAM should have 12 factors after the last update
418  EXPECT_LONGS_EQUAL(12, isam.size());
419 }
420 
421 /* ************************************************************************* */
422 TEST(HybridGaussianFactorGraph, SwitchingTwoVar) {
423  const int N = 7;
424  auto hfg = makeSwitchingChain(N, X);
425  hfg->push_back(*makeSwitchingChain(N, Y, D));
426 
427  for (int t = 1; t <= N; t++) {
428  hfg->add(JacobianFactor(X(t), I_3x3, Y(t), -I_3x3, Vector3(1.0, 0.0, 0.0)));
429  }
430 
432 
433  KeyVector naturalX(N);
434  std::iota(naturalX.begin(), naturalX.end(), 1);
435  KeyVector ordX;
436  for (size_t i = 1; i <= N; i++) {
437  ordX.emplace_back(X(i));
438  ordX.emplace_back(Y(i));
439  }
440 
441  for (size_t i = 1; i <= N - 1; i++) {
442  ordX.emplace_back(M(i));
443  }
444  for (size_t i = 1; i <= N - 1; i++) {
445  ordX.emplace_back(D(i));
446  }
447 
448  {
449  DotWriter dw;
450  dw.positionHints['x'] = 1;
451  dw.positionHints['c'] = 0;
452  dw.positionHints['d'] = 3;
453  dw.positionHints['y'] = 2;
454  // std::cout << hfg->dot(DefaultKeyFormatter, dw);
455  // std::cout << "\n";
456  }
457 
458  {
459  DotWriter dw;
460  dw.positionHints['y'] = 9;
461  // dw.positionHints['c'] = 0;
462  // dw.positionHints['d'] = 3;
463  dw.positionHints['x'] = 1;
464  // std::cout << "\n";
465  // std::cout << hfg->eliminateSequential(Ordering(ordX))
466  // ->dot(DefaultKeyFormatter, dw);
467  // hfg->eliminateMultifrontal(Ordering(ordX))->dot(std::cout);
468  }
469 
470  Ordering ordering_partial;
471  for (size_t i = 1; i <= N; i++) {
472  ordering_partial.emplace_back(X(i));
473  ordering_partial.emplace_back(Y(i));
474  }
475  const auto [hbn, remaining] =
476  hfg->eliminatePartialSequential(ordering_partial);
477 
478  EXPECT_LONGS_EQUAL(14, hbn->size());
479  EXPECT_LONGS_EQUAL(11, remaining->size());
480 
481  {
482  DotWriter dw;
483  dw.positionHints['x'] = 1;
484  dw.positionHints['c'] = 0;
485  dw.positionHints['d'] = 3;
486  dw.positionHints['y'] = 2;
487  // std::cout << remaining->dot(DefaultKeyFormatter, dw);
488  // std::cout << "\n";
489  }
490 }
491 
492 /* ************************************************************************* */
495 
496  DiscreteKey c1(C(1), 2);
497 
498  hfg.add(JacobianFactor(X(0), I_3x3, Z_3x1));
499  hfg.add(JacobianFactor(X(0), I_3x3, X(1), -I_3x3, Z_3x1));
500 
502  C(1), std::make_shared<JacobianFactor>(X(1), I_3x3, Z_3x1),
503  std::make_shared<JacobianFactor>(X(1), I_3x3, Vector3::Ones()));
504 
505  hfg.add(GaussianMixtureFactor({X(1)}, {c1}, dt));
506 
507  auto result = hfg.eliminateSequential();
508 
509  HybridValues hv = result->optimize();
510 
511  EXPECT(assert_equal(hv.atDiscrete(C(1)), int(0)));
512 }
513 
514 /* ************************************************************************* */
515 // Test adding of gaussian conditional and re-elimination.
517  Switching switching(4);
519 
520  hfg.push_back(switching.linearizedFactorGraph.at(0)); // P(X1)
522  ordering.push_back(X(0));
523  HybridBayesNet::shared_ptr bayes_net = hfg.eliminateSequential(ordering);
524 
525  hfg.push_back(switching.linearizedFactorGraph.at(1)); // P(X1, X2 | M1)
526  hfg.push_back(*bayes_net);
527  hfg.push_back(switching.linearizedFactorGraph.at(2)); // P(X2, X3 | M2)
528  hfg.push_back(switching.linearizedFactorGraph.at(5)); // P(M1)
529  ordering.push_back(X(1));
530  ordering.push_back(X(2));
531  ordering.push_back(M(0));
532  ordering.push_back(M(1));
533 
534  bayes_net = hfg.eliminateSequential(ordering);
535 
536  HybridValues result = bayes_net->optimize();
537 
538  Values expected_continuous;
539  expected_continuous.insert<double>(X(0), 0);
540  expected_continuous.insert<double>(X(1), 1);
541  expected_continuous.insert<double>(X(2), 2);
542  expected_continuous.insert<double>(X(3), 4);
543  Values result_continuous =
544  switching.linearizationPoint.retract(result.continuous());
545  EXPECT(assert_equal(expected_continuous, result_continuous));
546 
547  DiscreteValues expected_discrete;
548  expected_discrete[M(0)] = 1;
549  expected_discrete[M(1)] = 1;
550  EXPECT(assert_equal(expected_discrete, result.discrete()));
551 }
552 
553 /* ****************************************************************************/
554 // Test hybrid gaussian factor graph error and unnormalized probabilities
555 TEST(HybridGaussianFactorGraph, ErrorAndProbPrime) {
556  Switching s(3);
557 
559 
560  HybridBayesNet::shared_ptr hybridBayesNet = graph.eliminateSequential();
561 
562  const HybridValues delta = hybridBayesNet->optimize();
563  const double error = graph.error(delta);
564 
565  // regression
566  EXPECT(assert_equal(1.58886, error, 1e-5));
567 
568  // Real test:
569  EXPECT(assert_equal(graph.probPrime(delta), exp(-error), 1e-7));
570 }
571 
572 /* ****************************************************************************/
573 // Test hybrid gaussian factor graph error and unnormalized probabilities
574 TEST(HybridGaussianFactorGraph, ErrorAndProbPrimeTree) {
575  Switching s(3);
576 
578 
579  HybridBayesNet::shared_ptr hybridBayesNet = graph.eliminateSequential();
580 
581  HybridValues delta = hybridBayesNet->optimize();
582  auto error_tree = graph.error(delta.continuous());
583 
584  std::vector<DiscreteKey> discrete_keys = {{M(0), 2}, {M(1), 2}};
585  std::vector<double> leaves = {0.9998558, 0.4902432, 0.5193694, 0.0097568};
586  AlgebraicDecisionTree<Key> expected_error(discrete_keys, leaves);
587 
588  // regression
589  EXPECT(assert_equal(expected_error, error_tree, 1e-7));
590 
591  auto probs = graph.probPrime(delta.continuous());
592  std::vector<double> prob_leaves = {0.36793249, 0.61247742, 0.59489556,
593  0.99029064};
594  AlgebraicDecisionTree<Key> expected_probs(discrete_keys, prob_leaves);
595 
596  // regression
597  EXPECT(assert_equal(expected_probs, probs, 1e-7));
598 }
599 
600 /* ****************************************************************************/
601 // Check that assembleGraphTree assembles Gaussian factor graphs for each
602 // assignment.
603 TEST(HybridGaussianFactorGraph, assembleGraphTree) {
604  const int num_measurements = 1;
606  num_measurements, VectorValues{{Z(0), Vector1(5.0)}});
607  EXPECT_LONGS_EQUAL(3, fg.size());
608 
609  // Assemble graph tree:
610  auto actual = fg.assembleGraphTree();
611 
612  // Create expected decision tree with two factor graphs:
613 
614  // Get mixture factor:
615  auto mixture = std::dynamic_pointer_cast<GaussianMixtureFactor>(fg.at(0));
616  CHECK(mixture);
617 
618  // Get prior factor:
619  const auto gf = std::dynamic_pointer_cast<HybridConditional>(fg.at(1));
620  CHECK(gf);
621  using GF = GaussianFactor::shared_ptr;
622  const GF prior = gf->asGaussian();
623  CHECK(prior);
624 
625  // Create DiscreteValues for both 0 and 1:
626  DiscreteValues d0{{M(0), 0}}, d1{{M(0), 1}};
627 
628  // Expected decision tree with two factor graphs:
629  // f(x0;mode=0)P(x0) and f(x0;mode=1)P(x0)
631  M(0), GaussianFactorGraph(std::vector<GF>{(*mixture)(d0), prior}),
632  GaussianFactorGraph(std::vector<GF>{(*mixture)(d1), prior})};
633 
634  EXPECT(assert_equal(expected(d0), actual(d0), 1e-5));
635  EXPECT(assert_equal(expected(d1), actual(d1), 1e-5));
636 }
637 
638 /* ****************************************************************************/
639 // Check that the factor graph unnormalized probability is proportional to the
640 // Bayes net probability for the given measurements.
641 bool ratioTest(const HybridBayesNet &bn, const VectorValues &measurements,
642  const HybridGaussianFactorGraph &fg, size_t num_samples = 100) {
643  auto compute_ratio = [&](HybridValues *sample) -> double {
644  sample->update(measurements); // update sample with given measurements:
645  return bn.evaluate(*sample) / fg.probPrime(*sample);
646  };
647 
648  HybridValues sample = bn.sample(&kRng);
649  double expected_ratio = compute_ratio(&sample);
650 
651  // Test ratios for a number of independent samples:
652  for (size_t i = 0; i < num_samples; i++) {
653  HybridValues sample = bn.sample(&kRng);
654  if (std::abs(expected_ratio - compute_ratio(&sample)) > 1e-6) return false;
655  }
656  return true;
657 }
658 
659 /* ****************************************************************************/
660 // Check that the factor graph unnormalized probability is proportional to the
661 // Bayes net probability for the given measurements.
662 bool ratioTest(const HybridBayesNet &bn, const VectorValues &measurements,
663  const HybridBayesNet &posterior, size_t num_samples = 100) {
664  auto compute_ratio = [&](HybridValues *sample) -> double {
665  sample->update(measurements); // update sample with given measurements:
666  return bn.evaluate(*sample) / posterior.evaluate(*sample);
667  };
668 
669  HybridValues sample = bn.sample(&kRng);
670  double expected_ratio = compute_ratio(&sample);
671 
672  // Test ratios for a number of independent samples:
673  for (size_t i = 0; i < num_samples; i++) {
674  HybridValues sample = bn.sample(&kRng);
675  // GTSAM_PRINT(sample);
676  // std::cout << "ratio: " << compute_ratio(&sample) << std::endl;
677  if (std::abs(expected_ratio - compute_ratio(&sample)) > 1e-6) return false;
678  }
679  return true;
680 }
681 
682 /* ****************************************************************************/
683 // Check that eliminating tiny net with 1 measurement yields correct result.
684 TEST(HybridGaussianFactorGraph, EliminateTiny1) {
685  const int num_measurements = 1;
686  const VectorValues measurements{{Z(0), Vector1(5.0)}};
687  auto bn = tiny::createHybridBayesNet(num_measurements);
688  auto fg = bn.toFactorGraph(measurements);
689  EXPECT_LONGS_EQUAL(3, fg.size());
690 
691  EXPECT(ratioTest(bn, measurements, fg));
692 
693  // Create expected Bayes Net:
694  HybridBayesNet expectedBayesNet;
695 
696  // Create Gaussian mixture on X(0).
697  using tiny::mode;
698  // regression, but mean checked to be 5.0 in both cases:
699  const auto conditional0 = std::make_shared<GaussianConditional>(
700  X(0), Vector1(14.1421), I_1x1 * 2.82843),
701  conditional1 = std::make_shared<GaussianConditional>(
702  X(0), Vector1(10.1379), I_1x1 * 2.02759);
703  expectedBayesNet.emplace_back(
704  new GaussianMixture({X(0)}, {}, {mode}, {conditional0, conditional1}));
705 
706  // Add prior on mode.
707  expectedBayesNet.emplace_back(new DiscreteConditional(mode, "74/26"));
708 
709  // Test elimination
710  const auto posterior = fg.eliminateSequential();
711  EXPECT(assert_equal(expectedBayesNet, *posterior, 0.01));
712 
713  EXPECT(ratioTest(bn, measurements, *posterior));
714 }
715 
716 /* ****************************************************************************/
717 // Check that eliminating tiny net with 1 measurement with mode order swapped
718 // yields correct result.
719 TEST(HybridGaussianFactorGraph, EliminateTiny1Swapped) {
720  const VectorValues measurements{{Z(0), Vector1(5.0)}};
721 
722  // Create mode key: 1 is low-noise, 0 is high-noise.
723  const DiscreteKey mode{M(0), 2};
724  HybridBayesNet bn;
725 
726  // Create Gaussian mixture z_0 = x0 + noise for each measurement.
728  {Z(0)}, {X(0)}, {mode},
729  {GaussianConditional::sharedMeanAndStddev(Z(0), I_1x1, X(0), Z_1x1, 3),
730  GaussianConditional::sharedMeanAndStddev(Z(0), I_1x1, X(0), Z_1x1,
731  0.5)}));
732 
733  // Create prior on X(0).
734  bn.push_back(
735  GaussianConditional::sharedMeanAndStddev(X(0), Vector1(5.0), 0.5));
736 
737  // Add prior on mode.
738  bn.emplace_back(new DiscreteConditional(mode, "1/1"));
739 
740  // bn.print();
741  auto fg = bn.toFactorGraph(measurements);
742  EXPECT_LONGS_EQUAL(3, fg.size());
743 
744  // fg.print();
745 
746  EXPECT(ratioTest(bn, measurements, fg));
747 
748  // Create expected Bayes Net:
749  HybridBayesNet expectedBayesNet;
750 
751  // Create Gaussian mixture on X(0).
752  // regression, but mean checked to be 5.0 in both cases:
753  const auto conditional0 = std::make_shared<GaussianConditional>(
754  X(0), Vector1(10.1379), I_1x1 * 2.02759),
755  conditional1 = std::make_shared<GaussianConditional>(
756  X(0), Vector1(14.1421), I_1x1 * 2.82843);
757  expectedBayesNet.emplace_back(
758  new GaussianMixture({X(0)}, {}, {mode}, {conditional0, conditional1}));
759 
760  // Add prior on mode.
761  expectedBayesNet.emplace_back(new DiscreteConditional(mode, "1/1"));
762 
763  // Test elimination
764  const auto posterior = fg.eliminateSequential();
765  // EXPECT(assert_equal(expectedBayesNet, *posterior, 0.01));
766 
767  EXPECT(ratioTest(bn, measurements, *posterior));
768 
769  // posterior->print();
770  // posterior->optimize().print();
771 }
772 
773 /* ****************************************************************************/
774 // Check that eliminating tiny net with 2 measurements yields correct result.
775 TEST(HybridGaussianFactorGraph, EliminateTiny2) {
776  // Create factor graph with 2 measurements such that posterior mean = 5.0.
777  const int num_measurements = 2;
778  const VectorValues measurements{{Z(0), Vector1(4.0)}, {Z(1), Vector1(6.0)}};
779  auto bn = tiny::createHybridBayesNet(num_measurements);
780  auto fg = bn.toFactorGraph(measurements);
781  EXPECT_LONGS_EQUAL(4, fg.size());
782 
783  // Create expected Bayes Net:
784  HybridBayesNet expectedBayesNet;
785 
786  // Create Gaussian mixture on X(0).
787  using tiny::mode;
788  // regression, but mean checked to be 5.0 in both cases:
789  const auto conditional0 = std::make_shared<GaussianConditional>(
790  X(0), Vector1(17.3205), I_1x1 * 3.4641),
791  conditional1 = std::make_shared<GaussianConditional>(
792  X(0), Vector1(10.274), I_1x1 * 2.0548);
793  expectedBayesNet.emplace_back(
794  new GaussianMixture({X(0)}, {}, {mode}, {conditional0, conditional1}));
795 
796  // Add prior on mode.
797  expectedBayesNet.emplace_back(new DiscreteConditional(mode, "23/77"));
798 
799  // Test elimination
800  const auto posterior = fg.eliminateSequential();
801  EXPECT(assert_equal(expectedBayesNet, *posterior, 0.01));
802 
803  EXPECT(ratioTest(bn, measurements, *posterior));
804 }
805 
806 /* ****************************************************************************/
807 // Test eliminating tiny net with 1 mode per measurement.
808 TEST(HybridGaussianFactorGraph, EliminateTiny22) {
809  // Create factor graph with 2 measurements such that posterior mean = 5.0.
810  const int num_measurements = 2;
811  const bool manyModes = true;
812 
813  // Create Bayes net and convert to factor graph.
814  auto bn = tiny::createHybridBayesNet(num_measurements, manyModes);
815  const VectorValues measurements{{Z(0), Vector1(4.0)}, {Z(1), Vector1(6.0)}};
816  auto fg = bn.toFactorGraph(measurements);
817  EXPECT_LONGS_EQUAL(5, fg.size());
818 
819  EXPECT(ratioTest(bn, measurements, fg));
820 
821  // Test elimination
822  const auto posterior = fg.eliminateSequential();
823 
824  EXPECT(ratioTest(bn, measurements, *posterior));
825 }
826 
827 /* ****************************************************************************/
828 // Test elimination of a switching network with one mode per measurement.
829 TEST(HybridGaussianFactorGraph, EliminateSwitchingNetwork) {
830  // Create a switching network with one mode per measurement.
831  HybridBayesNet bn;
832 
833  // NOTE: we add reverse topological so we can sample from the Bayes net.:
834 
835  // Add measurements:
836  for (size_t t : {0, 1, 2}) {
837  // Create Gaussian mixture on Z(t) conditioned on X(t) and mode N(t):
838  const auto noise_mode_t = DiscreteKey{N(t), 2};
839  bn.emplace_back(
840  new GaussianMixture({Z(t)}, {X(t)}, {noise_mode_t},
841  {GaussianConditional::sharedMeanAndStddev(
842  Z(t), I_1x1, X(t), Z_1x1, 0.5),
843  GaussianConditional::sharedMeanAndStddev(
844  Z(t), I_1x1, X(t), Z_1x1, 3.0)}));
845 
846  // Create prior on discrete mode N(t):
847  bn.emplace_back(new DiscreteConditional(noise_mode_t, "20/80"));
848  }
849 
850  // Add motion models:
851  for (size_t t : {2, 1}) {
852  // Create Gaussian mixture on X(t) conditioned on X(t-1) and mode M(t-1):
853  const auto motion_model_t = DiscreteKey{M(t), 2};
854  bn.emplace_back(
855  new GaussianMixture({X(t)}, {X(t - 1)}, {motion_model_t},
856  {GaussianConditional::sharedMeanAndStddev(
857  X(t), I_1x1, X(t - 1), Z_1x1, 0.2),
858  GaussianConditional::sharedMeanAndStddev(
859  X(t), I_1x1, X(t - 1), I_1x1, 0.2)}));
860 
861  // Create prior on motion model M(t):
862  bn.emplace_back(new DiscreteConditional(motion_model_t, "40/60"));
863  }
864 
865  // Create Gaussian prior on continuous X(0) using sharedMeanAndStddev:
866  bn.push_back(GaussianConditional::sharedMeanAndStddev(X(0), Z_1x1, 0.1));
867 
868  // Make sure we an sample from the Bayes net:
870 
871  // Create measurements consistent with moving right every time:
872  const VectorValues measurements{
873  {Z(0), Vector1(0.0)}, {Z(1), Vector1(1.0)}, {Z(2), Vector1(2.0)}};
874  const HybridGaussianFactorGraph fg = bn.toFactorGraph(measurements);
875 
876  // Factor graph is:
877  // D D
878  // | |
879  // m1 m2
880  // | |
881  // C-x0-HC-x1-HC-x2
882  // | | |
883  // HF HF HF
884  // | | |
885  // n0 n1 n2
886  // | | |
887  // D D D
888  EXPECT_LONGS_EQUAL(11, fg.size());
889  EXPECT(ratioTest(bn, measurements, fg));
890 
891  // Do elimination of X(2) only:
892  auto [bn1, fg1] = fg.eliminatePartialSequential(Ordering{X(2)});
893  fg1->push_back(*bn1);
894  EXPECT(ratioTest(bn, measurements, *fg1));
895 
896  // Create ordering that eliminates in time order, then discrete modes:
897  Ordering ordering{X(2), X(1), X(0), N(0), N(1), N(2), M(1), M(2)};
898 
899  // Do elimination:
901 
902  // Test resulting posterior Bayes net has correct size:
903  EXPECT_LONGS_EQUAL(8, posterior->size());
904 
905  // TODO(dellaert): this test fails - no idea why.
906  EXPECT(ratioTest(bn, measurements, *posterior));
907 }
908 
909 /* ************************************************************************* */
910 int main() {
911  TestResult tr;
912  return TestRegistry::runAllTests(tr);
913 }
914 /* ************************************************************************* */
Matrix3f m
HybridGaussianFactorGraph::shared_ptr makeSwitchingChain(size_t n, std::function< Key(int)> keyFunc=X, std::function< Key(int)> dKeyFunc=M)
Create a switching system chain. A switching system is a continuous system which depends on a discret...
Definition: Switching.h:51
Key M(std::uint64_t j)
A set of GaussianFactors, indexed by a set of discrete keys.
Provides additional testing facilities for common data structures.
#define CHECK(condition)
Definition: Test.h:108
A hybrid conditional in the Conditional Linear Gaussian scheme.
const char Y
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51
std::pair< KeyVector, std::vector< int > > makeBinaryOrdering(std::vector< Key > &input)
Return the ordering as a binary tree such that all parent nodes are above their children.
Definition: Switching.h:85
Key N(std::uint64_t j)
std::pair< std::shared_ptr< BayesTreeType >, std::shared_ptr< FactorGraphType > > eliminatePartialMultifrontal(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
Graphviz formatter.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Eigen::Matrix< double, 1, 1 > Vector1
Definition: testEvent.cpp:33
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:88
const ValueType at(Key j) const
Definition: Values-inl.h:204
Matrix expected
Definition: testMatrix.cpp:971
TEST(HybridGaussianFactorGraph, Creation)
size_t size() const
Definition: Factor.h:159
std::shared_ptr< This > shared_ptr
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:190
Implementation of a discrete conditional mixture factor. Implements a joint discrete-continuous facto...
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
std::pair< std::shared_ptr< BayesNetType >, std::shared_ptr< FactorGraphType > > eliminatePartialSequential(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
const Ordering HybridOrdering(const HybridGaussianFactorGraph &graph)
Return a Colamd constrained ordering where the discrete keys are eliminated after the continuous keys...
const GaussianFactorGraph factors
Definition: BFloat16.h:88
double evaluate(const HybridValues &values) const
Evaluate hybrid probability density for given HybridValues.
Key X(std::uint64_t j)
const VectorValues & continuous() const
Return the multi-dimensional vector values.
Definition: HybridValues.h:89
void update(const NonlinearFactorGraph &newFactors, const Values &initialValues)
#define N
Definition: gksort.c:12
NonlinearFactorGraph graph
Bayes network.
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
static enum @1107 ordering
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:214
A Bayes net of Gaussian Conditionals indexed by discrete keys.
Values retract(const VectorValues &delta) const
Definition: Values.cpp:98
Key Z(std::uint64_t j)
const double dt
Key D(std::uint64_t j)
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
size_t size() const
Definition: FactorGraph.h:334
HybridGaussianFactorGraph linearizedFactorGraph
Definition: Switching.h:124
#define Z
Definition: icosphere.cpp:21
static const Line3 l(Rot3(), 1, 1)
A conditional of gaussian mixtures indexed by discrete variables, as part of a Bayes Network...
Values result
void dotPrint(const HybridGaussianFactorGraph::shared_ptr &hfg, const HybridBayesTree::shared_ptr &hbt, const Ordering &ordering)
Matrix3d m1
Definition: IOFormat.cpp:2
Hybrid Bayes Tree, the result of eliminating a HybridJunctionTree.
AlgebraicDecisionTree< Key > error(const VectorValues &continuousValues) const
Compute error for each discrete assignment, and return as a tree.
#define EXPECT(condition)
Definition: Test.h:150
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
NonlinearISAM isam(relinearizeInterval)
size_t size() const
Definition: Values.h:178
std::shared_ptr< This > shared_ptr
shared_ptr to This
void push_back(std::shared_ptr< HybridConditional > conditional)
Add a hybrid conditional using a shared_ptr.
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
AlgebraicDecisionTree< Key > probPrime(const VectorValues &continuousValues) const
Compute unnormalized probability for each discrete assignment, and return as a tree.
Linearized Hybrid factor graph that uses type erasure.
void emplace_back(Conditional *conditional)
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
DotWriter is a helper class for writing graphviz .dot files.
Definition: DotWriter.h:36
traits
Definition: chartTesting.h:28
specialized key for discrete variables
bool ratioTest(const HybridBayesNet &bn, const VectorValues &measurements, const HybridGaussianFactorGraph &fg, size_t num_samples=100)
Values linearizationPoint
Definition: Switching.h:125
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
Key Y(std::uint64_t j)
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:343
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:64
const DiscreteValues & discrete() const
Return the discrete values.
Definition: HybridValues.h:92
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
HybridBayesNet createHybridBayesNet(size_t num_measurements=1, bool manyModes=false)
size_t size() const
Definition: VectorValues.h:127
void insert(Key j, const Value &val)
Definition: Values.cpp:155
static double error
Definition: testRot3.cpp:37
static const DiscreteKey mode(modeKey, 2)
HybridValues sample(const HybridValues &given, std::mt19937_64 *rng) const
Sample from an incomplete BayesNet, given missing variables.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
const GaussianMixture mixture({Z(0)}, {X(0)}, {mode}, conditionals)
#define X
Definition: icosphere.cpp:20
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
#define abs(x)
Definition: datatypes.h:17
size_t & atDiscrete(Key j)
Definition: HybridValues.h:175
Point2 t(10, 10)
std::shared_ptr< HybridBayesNet > shared_ptr
std::mt19937_64 kRng(42)
HybridGaussianFactorGraph toFactorGraph(const VectorValues &measurements) const
static HybridGaussianFactorGraph::shared_ptr createHybridGaussianFactorGraph()
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
std::map< char, double > positionHints
Definition: DotWriter.h:55


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:38:22