24 #include <boost/assign/std/vector.hpp> 32 using namespace gtsam;
39 const int nrNodes = 15;
40 const size_t nrStates = 2;
43 vector<DiscreteKey>
key;
44 for (
int i = 0;
i < nrNodes;
i++) {
51 bayesNet.
add(key[14] %
"1/3");
53 bayesNet.
add(key[13] | key[14] =
"1/3 3/1");
54 bayesNet.
add(key[12] | key[14] =
"3/1 3/1");
56 bayesNet.
add((key[11] | key[13], key[14]) =
"1/4 2/3 3/2 4/1");
57 bayesNet.
add((key[10] | key[13], key[14]) =
"1/4 3/2 2/3 4/1");
58 bayesNet.
add((key[9] | key[12], key[14]) =
"4/1 2/3 F 1/4");
59 bayesNet.
add((key[8] | key[12], key[14]) =
"T 1/4 3/2 4/1");
61 bayesNet.
add((key[7] | key[11], key[13]) =
"1/4 2/3 3/2 4/1");
62 bayesNet.
add((key[6] | key[11], key[13]) =
"1/4 3/2 2/3 4/1");
63 bayesNet.
add((key[5] | key[10], key[13]) =
"4/1 2/3 3/2 1/4");
64 bayesNet.
add((key[4] | key[10], key[13]) =
"2/3 1/4 3/2 4/1");
66 bayesNet.
add((key[3] | key[9], key[12]) =
"1/4 2/3 3/2 4/1");
67 bayesNet.
add((key[2] | key[9], key[12]) =
"1/4 8/2 2/3 4/1");
68 bayesNet.
add((key[1] | key[8], key[12]) =
"4/1 2/3 3/2 1/4");
69 bayesNet.
add((key[0] | key[8], key[12]) =
"2/3 1/4 3/2 4/1");
73 bayesNet.
saveGraph(
"/tmp/discreteBayesNet.dot");
80 bayesTree->saveGraph(
"/tmp/discreteBayesTree.dot");
84 for (
size_t i : {13, 14, 9, 3, 2, 8, 1, 0, 10, 5, 4}) {
85 auto clique_i = (*bayesTree)[
i];
89 auto R = bayesTree->roots().front();
93 key[0] & key[1] & key[2] & key[3] & key[4] & key[5] & key[6] & key[7] &
94 key[8] & key[9] & key[10] & key[11] & key[12] & key[13] & key[14]);
95 for (
size_t i = 0;
i < allPosbValues.size(); ++
i) {
98 double actual = bayesTree->evaluate(x);
104 double joint_12_14 = 0, joint_9_12_14 = 0, joint_8_12_14 = 0, joint_8_12 = 0,
105 joint82 = 0, joint12 = 0, joint24 = 0, joint45 = 0, joint46 = 0,
106 joint_4_11 = 0, joint_11_13 = 0, joint_11_13_14 = 0,
107 joint_11_12_13_14 = 0, joint_9_11_12_13 = 0, joint_8_11_12_13 = 0;
108 for (
size_t i = 0;
i < allPosbValues.size(); ++
i) {
110 double px = bayesTree->evaluate(x);
111 for (
size_t i = 0;
i < 15;
i++)
112 if (x[
i]) marginals[
i] +=
px;
113 if (x[12] && x[14]) {
115 if (x[9]) joint_9_12_14 +=
px;
116 if (x[8]) joint_8_12_14 +=
px;
118 if (x[8] && x[12]) joint_8_12 +=
px;
120 if (x[8]) joint82 +=
px;
121 if (x[1]) joint12 +=
px;
124 if (x[2]) joint24 +=
px;
125 if (x[5]) joint45 +=
px;
126 if (x[6]) joint46 +=
px;
127 if (x[11]) joint_4_11 +=
px;
129 if (x[11] && x[13]) {
131 if (x[8] && x[12]) joint_8_11_12_13 +=
px;
132 if (x[9] && x[12]) joint_9_11_12_13 +=
px;
134 joint_11_13_14 +=
px;
136 joint_11_12_13_14 +=
px;
144 auto clique = (*bayesTree)[0];
150 clique = (*bayesTree)[9];
156 clique = (*bayesTree)[11];
162 clique = (*bayesTree)[9];
168 clique = (*bayesTree)[8];
173 clique = (*bayesTree)[2];
178 clique = (*bayesTree)[0];
183 DiscreteBayesTree::Nodes cliques = bayesTree->nodes();
184 for (
auto clique : cliques) {
187 clique.second->conditional_->printSignature();
188 shortcut.
print(
"shortcut:");
194 for (
size_t i = 0;
i < 15;
i++) {
196 double actual = (*marginalFactor)(all1);
TEST_UNSAFE(DiscreteBayesTree, ThinTree)
std::vector< Assignment< L > > cartesianProduct(const std::vector< std::pair< L, size_t > > &keys)
Get Cartesian product consisting all possible configurations.
static int runAllTests(TestResult &result)
boost::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
#define DOUBLES_EQUAL(expected, actual, threshold)
Rot2 R(Rot2::fromAngle(0.1))
void add(const Signature &s)
std::pair< Key, size_t > DiscreteKey
RealScalar RealScalar * px
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Discrete Bayes Tree, the result of eliminating a DiscreteJunctionTree.
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
boost::shared_ptr< DiscreteFactor > shared_ptr
shared_ptr to this class
#define LONGS_EQUAL(expected, actual)
typedef and functions to augment Eigen's VectorXd
void saveGraph(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
#define EXPECT_LONGS_EQUAL(expected, actual)
boost::shared_ptr< This > shared_ptr
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
double evaluate(const DiscreteConditional::Values &values) const
Marginals marginals(graph, result)
void print(const std::string &s="BayesNet", const KeyFormatter &formatter=DefaultKeyFormatter) const override