testHybridBayesTree.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
23 
24 #include "Switching.h"
25 
26 // Include for test suite
28 
29 using namespace std;
30 using namespace gtsam;
34 
35 /* ****************************************************************************/
36 // Test multifrontal optimize
37 TEST(HybridBayesTree, OptimizeMultifrontal) {
38  Switching s(4);
39 
40  HybridBayesTree::shared_ptr hybridBayesTree =
42  HybridValues delta = hybridBayesTree->optimize();
43 
44  VectorValues expectedValues;
45  expectedValues.insert(X(0), -0.999904 * Vector1::Ones());
46  expectedValues.insert(X(1), -0.99029 * Vector1::Ones());
47  expectedValues.insert(X(2), -1.00971 * Vector1::Ones());
48  expectedValues.insert(X(3), -1.0001 * Vector1::Ones());
49 
50  EXPECT(assert_equal(expectedValues, delta.continuous(), 1e-5));
51 }
52 
53 /* ****************************************************************************/
54 // Test for optimizing a HybridBayesTree with a given assignment.
55 TEST(HybridBayesTree, OptimizeAssignment) {
56  Switching s(4);
57 
60 
61  // Add the 3 hybrid factors, x1-x2, x2-x3, x3-x4
62  for (size_t i = 1; i < 4; i++) {
64  }
65 
66  // Add the Gaussian factors, 1 prior on X(1),
67  // 3 measurements on X(2), X(3), X(4)
68  graph1.push_back(s.linearizedFactorGraph.at(0));
69  for (size_t i = 4; i <= 7; i++) {
71  }
72 
73  // Add the discrete factors
74  for (size_t i = 7; i <= 9; i++) {
76  }
77 
78  isam.update(graph1);
79 
80  DiscreteValues assignment;
81  assignment[M(0)] = 1;
82  assignment[M(1)] = 1;
83  assignment[M(2)] = 1;
84 
85  VectorValues delta = isam.optimize(assignment);
86 
87  // The linearization point has the same value as the key index,
88  // e.g. X(1) = 1, X(2) = 2,
89  // but the factors specify X(k) = k-1, so delta should be -1.
90  VectorValues expected_delta;
91  expected_delta.insert(make_pair(X(0), -Vector1::Ones()));
92  expected_delta.insert(make_pair(X(1), -Vector1::Ones()));
93  expected_delta.insert(make_pair(X(2), -Vector1::Ones()));
94  expected_delta.insert(make_pair(X(3), -Vector1::Ones()));
95 
96  EXPECT(assert_equal(expected_delta, delta));
97 
98  // Create ordering.
100  for (size_t k = 0; k < s.K; k++) ordering.push_back(X(k));
101 
102  const auto [hybridBayesNet, remainingFactorGraph] =
104 
105  GaussianBayesNet gbn = hybridBayesNet->choose(assignment);
107 
108  EXPECT(assert_equal(expected, delta));
109 }
110 
111 /* ****************************************************************************/
112 // Test for optimizing a HybridBayesTree.
113 TEST(HybridBayesTree, Optimize) {
114  Switching s(4);
115 
118 
119  // Add the 3 hybrid factors, x1-x2, x2-x3, x3-x4
120  for (size_t i = 1; i < 4; i++) {
121  graph1.push_back(s.linearizedFactorGraph.at(i));
122  }
123 
124  // Add the Gaussian factors, 1 prior on X(0),
125  // 3 measurements on X(2), X(3), X(4)
126  graph1.push_back(s.linearizedFactorGraph.at(0));
127  for (size_t i = 4; i <= 6; i++) {
128  graph1.push_back(s.linearizedFactorGraph.at(i));
129  }
130 
131  // Add the discrete factors
132  for (size_t i = 7; i <= 9; i++) {
133  graph1.push_back(s.linearizedFactorGraph.at(i));
134  }
135 
136  isam.update(graph1);
137 
138  HybridValues delta = isam.optimize();
139 
140  // Create ordering.
142  for (size_t k = 0; k < s.K; k++) ordering.push_back(X(k));
143 
144  const auto [hybridBayesNet, remainingFactorGraph] =
146 
148  for (auto&& f : *remainingFactorGraph) {
149  auto discreteFactor = dynamic_pointer_cast<DecisionTreeFactor>(f);
150  assert(discreteFactor);
151  dfg.push_back(discreteFactor);
152  }
153 
154  // Add the probabilities for each branch
155  DiscreteKeys discrete_keys = {{M(0), 2}, {M(1), 2}, {M(2), 2}};
156  vector<double> probs = {0.012519475, 0.041280228, 0.075018647, 0.081663656,
157  0.037152205, 0.12248971, 0.07349729, 0.08};
158  dfg.emplace_shared<DecisionTreeFactor>(discrete_keys, probs);
159 
160  DiscreteValues expectedMPE = dfg.optimize();
161  VectorValues expectedValues = hybridBayesNet->optimize(expectedMPE);
162 
163  EXPECT(assert_equal(expectedMPE, delta.discrete()));
164  EXPECT(assert_equal(expectedValues, delta.continuous()));
165 }
166 
167 /* ****************************************************************************/
168 // Test for choosing a GaussianBayesTree from a HybridBayesTree.
170  Switching s(4);
171 
174 
175  // Add the 3 hybrid factors, x1-x2, x2-x3, x3-x4
176  for (size_t i = 1; i < 4; i++) {
177  graph1.push_back(s.linearizedFactorGraph.at(i));
178  }
179 
180  // Add the Gaussian factors, 1 prior on X(0),
181  // 3 measurements on X(2), X(3), X(4)
182  graph1.push_back(s.linearizedFactorGraph.at(0));
183  for (size_t i = 4; i <= 6; i++) {
184  graph1.push_back(s.linearizedFactorGraph.at(i));
185  }
186 
187  // Add the discrete factors
188  for (size_t i = 7; i <= 9; i++) {
189  graph1.push_back(s.linearizedFactorGraph.at(i));
190  }
191 
192  isam.update(graph1);
193 
194  DiscreteValues assignment;
195  assignment[M(0)] = 1;
196  assignment[M(1)] = 1;
197  assignment[M(2)] = 1;
198 
199  GaussianBayesTree gbt = isam.choose(assignment);
200 
201  // Specify ordering so it matches that of HybridGaussianISAM.
202  Ordering ordering(KeyVector{X(0), X(1), X(2), X(3), M(0), M(1), M(2)});
204 
205  auto expected_gbt = bayesTree->choose(assignment);
206 
207  EXPECT(assert_equal(expected_gbt, gbt));
208 }
209 
210 /* ************************************************************************* */
211 int main() {
212  TestResult tr;
213  return TestRegistry::runAllTests(tr);
214 }
215 /* ************************************************************************* */
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
static int runAllTests(TestResult &result)
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.
Matrix expected
Definition: testMatrix.cpp:971
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
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
static const GaussianBayesNet gbn
Definition: BFloat16.h:88
iterator insert(const std::pair< Key, Vector > &key_value)
const VectorValues & continuous() const
Return the multi-dimensional vector values.
Definition: HybridValues.h:89
DiscreteValues optimize(OptionalOrderingType orderingType={}) const
Find the maximum probable explanation (MPE) by doing max-product.
TEST(HybridBayesTree, OptimizeMultifrontal)
static enum @1107 ordering
GaussianBayesTree choose(const DiscreteValues &assignment) const
Get the Gaussian Bayes Tree which corresponds to a specific discrete value assignment.
int main()
HybridGaussianFactorGraph linearizedFactorGraph
Definition: Switching.h:124
VectorValues optimize() const
Hybrid Bayes Tree, the result of eliminating a HybridJunctionTree.
#define EXPECT(condition)
Definition: Test.h:150
HybridValues optimize() const
Optimize the hybrid Bayes tree by computing the MPE for the current set of discrete variables and usi...
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
NonlinearISAM isam(relinearizeInterval)
traits
Definition: chartTesting.h:28
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:343
const DiscreteValues & discrete() const
Return the discrete values.
Definition: HybridValues.h:92
std::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
#define X
Definition: icosphere.cpp:20
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41


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