testDiscreteConditional.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 testDecisionTreeFactor.cpp
14  * @brief unit tests for DiscreteConditional
15  * @author Duy-Nguyen Ta
16  * @date Feb 14, 2011
17  */
18 
19 #include <boost/assign/std/map.hpp>
20 #include <boost/assign/std/vector.hpp>
21 #include <boost/make_shared.hpp>
22 using namespace boost::assign;
23 
27 
28 using namespace std;
29 using namespace gtsam;
30 
31 /* ************************************************************************* */
32 TEST( DiscreteConditional, constructors)
33 {
34  DiscreteKey X(0, 2), Y(2, 3), Z(1, 2); // watch ordering !
35 
36  DiscreteConditional::shared_ptr expected1 = //
37  boost::make_shared<DiscreteConditional>(X | Y = "1/1 2/3 1/4");
38  EXPECT(expected1);
39  EXPECT_LONGS_EQUAL(0, *(expected1->beginFrontals()));
40  EXPECT_LONGS_EQUAL(2, *(expected1->beginParents()));
41  EXPECT(expected1->endParents() == expected1->end());
42  EXPECT(expected1->endFrontals() == expected1->beginParents());
43 
44  DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8");
45  DiscreteConditional actual1(1, f1);
46  EXPECT(assert_equal(*expected1, actual1, 1e-9));
47 
48  DecisionTreeFactor f2(X & Y & Z,
49  "0.2 0.5 0.3 0.6 0.4 0.7 0.25 0.55 0.35 0.65 0.45 0.75");
50  DiscreteConditional actual2(1, f2);
51  EXPECT(assert_equal(f2 / *f2.sum(1), *actual2.toFactor(), 1e-9));
52 }
53 
54 /* ************************************************************************* */
55 TEST(DiscreteConditional, constructors_alt_interface) {
56  DiscreteKey X(0, 2), Y(2, 3), Z(1, 2); // watch ordering !
57 
60  r1 += 1.0, 1.0;
61  r2 += 2.0, 3.0;
62  r3 += 1.0, 4.0;
63  table += r1, r2, r3;
64  auto actual1 = boost::make_shared<DiscreteConditional>(X | Y = table);
65  EXPECT(actual1);
66  DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8");
67  DiscreteConditional expected1(1, f1);
68  EXPECT(assert_equal(expected1, *actual1, 1e-9));
69 
71  X & Y & Z, "0.2 0.5 0.3 0.6 0.4 0.7 0.25 0.55 0.35 0.65 0.45 0.75");
72  DiscreteConditional actual2(1, f2);
73  EXPECT(assert_equal(f2 / *f2.sum(1), *actual2.toFactor(), 1e-9));
74 }
75 
76 /* ************************************************************************* */
77 TEST(DiscreteConditional, constructors2) {
78  // Declare keys and ordering
79  DiscreteKey C(0, 2), B(1, 2);
80  DecisionTreeFactor actual(C & B, "0.8 0.75 0.2 0.25");
81  Signature signature((C | B) = "4/1 3/1");
82  DiscreteConditional expected(signature);
83  DecisionTreeFactor::shared_ptr expectedFactor = expected.toFactor();
84  EXPECT(assert_equal(*expectedFactor, actual));
85 }
86 
87 /* ************************************************************************* */
88 TEST(DiscreteConditional, constructors3) {
89  // Declare keys and ordering
90  DiscreteKey C(0, 2), B(1, 2), A(2, 2);
91  DecisionTreeFactor actual(C & B & A, "0.8 0.5 0.5 0.2 0.2 0.5 0.5 0.8");
92  Signature signature((C | B, A) = "4/1 1/1 1/1 1/4");
93  DiscreteConditional expected(signature);
94  DecisionTreeFactor::shared_ptr expectedFactor = expected.toFactor();
95  EXPECT(assert_equal(*expectedFactor, actual));
96 }
97 
98 /* ************************************************************************* */
100  DiscreteKey A(0, 2), B(1, 2);
101  vector<DiscreteConditional::shared_ptr> c;
102  c.push_back(boost::make_shared<DiscreteConditional>(A | B = "1/2 2/1"));
103  c.push_back(boost::make_shared<DiscreteConditional>(B % "1/2"));
104  DecisionTreeFactor factor(A & B, "0.111111 0.444444 0.222222 0.222222");
105  DiscreteConditional actual(2, factor);
106  auto expected = DiscreteConditional::Combine(c.begin(), c.end());
107  EXPECT(assert_equal(*expected, actual, 1e-5));
108 }
109 
110 /* ************************************************************************* */
111 int main() {
112  TestResult tr;
113  return TestRegistry::runAllTests(tr);
114 }
115 /* ************************************************************************* */
DecisionTreeFactor::shared_ptr toFactor() const
static int runAllTests(TestResult &result)
Matrix expected
Definition: testMatrix.cpp:974
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Definition: Half.h:150
double f2(const Vector2 &x)
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
#define Z
Definition: icosphere.cpp:21
std::vector< Row > Table
Definition: Signature.h:58
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:34
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double r2
shared_ptr sum(size_t nrFrontals) const
Create new factor by summing all values with the same separator values.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static const double r3
std::vector< double > Row
Definition: Signature.h:57
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
TEST(DiscreteConditional, constructors)
static const double r1
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
ArrayXXf table(10, 4)
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
boost::shared_ptr< DecisionTreeFactor > shared_ptr
#define X
Definition: icosphere.cpp:20


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:25