testSymbolicBayesNet.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 
18 #include <boost/make_shared.hpp>
19 
21 
22 #include <gtsam/base/Testable.h>
25 
26 using namespace std;
27 using namespace gtsam;
28 
29 static const Key _L_ = 0;
30 static const Key _A_ = 1;
31 static const Key _B_ = 2;
32 static const Key _C_ = 3;
33 static const Key _D_ = 4;
34 
38 
39 /* ************************************************************************* */
41 {
43  f1.push_back(B);
44  f1.push_back(L);
46  f2.push_back(L);
47  f2.push_back(B);
48  CHECK(f1.equals(f1));
49  CHECK(!f1.equals(f2));
50 }
51 
52 /* ************************************************************************* */
54 {
59 
60  // p(A|BC)
61  SymbolicBayesNet p_ABC;
62  p_ABC.push_back(A);
63 
64  // P(BC)=P(B|C)P(C)
65  SymbolicBayesNet p_BC;
66  p_BC.push_back(B);
67  p_BC.push_back(C);
68 
69  // P(ABC) = P(A|BC) P(BC)
70  p_ABC.push_back(p_BC);
71 
73  expected.push_back(A);
74  expected.push_back(B);
75  expected.push_back(C);
76 
77  CHECK(assert_equal(expected,p_ABC));
78 }
79 
80 /* ************************************************************************* */
81 TEST(SymbolicBayesNet, saveGraph) {
83  bn += SymbolicConditional(_A_, _B_);
84  KeyVector keys {_B_, _C_, _D_};
85  bn += SymbolicConditional::FromKeys(keys,2);
86  bn += SymbolicConditional(_D_);
87 
88  bn.saveGraph("SymbolicBayesNet.dot");
89 }
90 
91 /* ************************************************************************* */
92 int main() {
93  TestResult tr;
94  return TestRegistry::runAllTests(tr);
95 }
96 /* ************************************************************************* */
#define CHECK(condition)
Definition: Test.h:109
GTSAM_EXPORT void saveGraph(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
static const Key _C_
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Matrix expected
Definition: testMatrix.cpp:974
Definition: Half.h:150
static const Key _L_
double f2(const Vector2 &x)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
boost::shared_ptr< This > shared_ptr
Typedef to the conditional base class.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
GTSAM_EXPORT bool equals(const This &bn, double tol=1e-9) const
static const Key _D_
TEST(SymbolicBayesNet, equals)
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
static const Key _B_
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
static SymbolicConditional::shared_ptr L(new SymbolicConditional(_L_, _B_))
const KeyVector keys
static const Key _A_
int main()
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:49:57