testAlgebraicDecisionTree.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 testDecisionTree.cpp
14  * @brief Develop DecisionTree
15  * @author Frank Dellaert
16  * @date Mar 6, 2011
17  */
18 
19 #include <gtsam/base/Testable.h>
20 #include <gtsam/discrete/DiscreteKey.h> // make sure we have traits
22 // headers first to make sure no missing headers
25 #include <gtsam/discrete/DecisionTree-inl.h> // for convert only
27 
28 using namespace std;
29 using namespace gtsam;
30 
31 /* ************************************************************************** */
33 
34 // traits
35 namespace gtsam {
36 template <>
37 struct traits<ADT> : public Testable<ADT> {};
38 } // namespace gtsam
39 
40 #define DISABLE_DOT
41 
42 template <typename T>
43 void dot(const T& f, const string& filename) {
44 #ifndef DISABLE_DOT
45  f.dot(filename);
46 #endif
47 }
48 
67 /* ************************************************************************** */
68 // instrumented operators
69 /* ************************************************************************** */
70 size_t muls = 0, adds = 0;
71 void resetCounts() {
72  muls = 0;
73  adds = 0;
74 }
75 void printCounts(const string& s) {
76 #ifndef DISABLE_TIMING
77  cout << s << ": " << std::setw(3) << muls << " muls, " << std::setw(3) << adds
78  << " adds" << endl;
79 #endif
80  resetCounts();
81 }
82 double mul(const double& a, const double& b) {
83  muls++;
84  return a * b;
85 }
86 double add_(const double& a, const double& b) {
87  adds++;
88  return a + b;
89 }
90 
91 /* ************************************************************************** */
92 // test ADT
93 TEST(ADT, example3) {
94  // Create labels
95  DiscreteKey A(0, 2), B(1, 2), C(2, 2), D(3, 2), E(4, 2);
96 
97  // Literals
98  ADT a(A, 0.5, 0.5);
99  ADT notb(B, 1, 0);
100  ADT c(C, 0.1, 0.9);
101  ADT d(D, 0.1, 0.9);
102  ADT note(E, 0.9, 0.1);
103 
104  ADT cnotb = c * notb;
105  dot(cnotb, "ADT-cnotb");
106 
107  // a.print("a: ");
108  // cnotb.print("cnotb: ");
109  ADT acnotb = a * cnotb;
110  // acnotb.print("acnotb: ");
111  // acnotb.printCache("acnotb Cache:");
112 
113  dot(acnotb, "ADT-acnotb");
114 
115  ADT big = apply(apply(d, note, &mul), acnotb, &add_);
116  dot(big, "ADT-big");
117 }
118 
119 /* ************************************************************************** */
120 // Asia Bayes Network
121 /* ************************************************************************** */
122 
124 ADT create(const Signature& signature) {
125  ADT p(signature.discreteKeys(), signature.cpt());
126  static size_t count = 0;
127  const DiscreteKey& key = signature.key();
128  std::stringstream ss;
129  ss << "CPT-" << std::setw(3) << std::setfill('0') << ++count << "-"
130  << key.first;
131  string DOTfile = ss.str();
132  dot(p, DOTfile);
133  return p;
134 }
135 
136 /* ************************************************************************* */
137 namespace asiaCPTs {
138 DiscreteKey A(0, 2), S(1, 2), T(2, 2), L(3, 2), B(4, 2), E(5, 2), X(6, 2),
139  D(7, 2);
140 
141 ADT pA = create(A % "99/1");
142 ADT pS = create(S % "50/50");
143 ADT pT = create(T | A = "99/1 95/5");
144 ADT pL = create(L | S = "99/1 90/10");
145 ADT pB = create(B | S = "70/30 40/60");
146 ADT pE = create((E | T, L) = "F T T T");
147 ADT pX = create(X | E = "95/5 2/98");
148 ADT pD = create((D | E, B) = "9/1 2/8 3/7 1/9");
149 } // namespace asiaCPTs
150 
151 /* ************************************************************************* */
152 // test Asia Joint
153 TEST(ADT, joint) {
154  using namespace asiaCPTs;
155 
156  // Create joint
157  resetCounts();
158  ADT joint = pA;
159  dot(joint, "Asia-A");
160  joint = apply(joint, pS, &mul);
161  dot(joint, "Asia-AS");
162  joint = apply(joint, pT, &mul);
163  dot(joint, "Asia-AST");
164  joint = apply(joint, pL, &mul);
165  dot(joint, "Asia-ASTL");
166  joint = apply(joint, pB, &mul);
167  dot(joint, "Asia-ASTLB");
168  joint = apply(joint, pE, &mul);
169  dot(joint, "Asia-ASTLBE");
170  joint = apply(joint, pX, &mul);
171  dot(joint, "Asia-ASTLBEX");
172  joint = apply(joint, pD, &mul);
173  dot(joint, "Asia-ASTLBEXD");
174 #ifdef GTSAM_DT_MERGING
175  EXPECT_LONGS_EQUAL(346, muls);
176 #else
177  EXPECT_LONGS_EQUAL(508, muls);
178 #endif
179  printCounts("Asia joint");
180 }
181 
182 /* ************************************************************************* */
183 TEST(ADT, combine) {
184  using namespace asiaCPTs;
185 
186  // Form P(A,S,T,L) = P(A) P(S) P(T|A) P(L|S)
187  ADT pASTL = pA;
188  pASTL = apply(pASTL, pS, &mul);
189  pASTL = apply(pASTL, pT, &mul);
190  pASTL = apply(pASTL, pL, &mul);
191 
192  // test combine to check that P(A) = \sum_{S,T,L} P(A,S,T,L)
193  ADT fAa = pASTL.combine(L, &add_).combine(T, &add_).combine(S, &add_);
194  EXPECT(assert_equal(pA, fAa));
195  ADT fAb = pASTL.combine(S, &add_).combine(T, &add_).combine(L, &add_);
196  EXPECT(assert_equal(pA, fAb));
197 }
198 
199 /* ************************************************************************* */
200 // test Inference with joint, created using different ordering
201 TEST(ADT, inference) {
202  DiscreteKey A(0, 2), D(1, 2), //
203  B(2, 2), L(3, 2), E(4, 2), S(5, 2), T(6, 2), X(7, 2);
204 
205  ADT pA = create(A % "99/1");
206  ADT pS = create(S % "50/50");
207  ADT pT = create(T | A = "99/1 95/5");
208  ADT pL = create(L | S = "99/1 90/10");
209  ADT pB = create(B | S = "70/30 40/60");
210  ADT pE = create((E | T, L) = "F T T T");
211  ADT pX = create(X | E = "95/5 2/98");
212  ADT pD = create((D | E, B) = "9/1 2/8 3/7 1/9");
213 
214  // Create joint, note different ordering than above: different tree!
215  resetCounts();
216  ADT joint = pA;
217  dot(joint, "Joint-Product-A");
218  joint = apply(joint, pS, &mul);
219  dot(joint, "Joint-Product-AS");
220  joint = apply(joint, pT, &mul);
221  dot(joint, "Joint-Product-AST");
222  joint = apply(joint, pL, &mul);
223  dot(joint, "Joint-Product-ASTL");
224  joint = apply(joint, pB, &mul);
225  dot(joint, "Joint-Product-ASTLB");
226  joint = apply(joint, pE, &mul);
227  dot(joint, "Joint-Product-ASTLBE");
228  joint = apply(joint, pX, &mul);
229  dot(joint, "Joint-Product-ASTLBEX");
230  joint = apply(joint, pD, &mul);
231  dot(joint, "Joint-Product-ASTLBEXD");
232 #ifdef GTSAM_DT_MERGING
233  EXPECT_LONGS_EQUAL(370, (long)muls); // different ordering
234 #else
235  EXPECT_LONGS_EQUAL(508, (long)muls); // different ordering
236 #endif
237  printCounts("Asia product");
238 
239  resetCounts();
240  ADT marginal = joint;
241  marginal = marginal.combine(X, &add_);
242  dot(marginal, "Joint-Sum-ADBLEST");
243  marginal = marginal.combine(T, &add_);
244  dot(marginal, "Joint-Sum-ADBLES");
245  marginal = marginal.combine(S, &add_);
246  dot(marginal, "Joint-Sum-ADBLE");
247  marginal = marginal.combine(E, &add_);
248  dot(marginal, "Joint-Sum-ADBL");
249 #ifdef GTSAM_DT_MERGING
250  EXPECT_LONGS_EQUAL(161, (long)adds);
251 #else
252  EXPECT_LONGS_EQUAL(240, (long)adds);
253 #endif
254  printCounts("Asia sum");
255 }
256 
257 /* ************************************************************************* */
258 TEST(ADT, factor_graph) {
259  DiscreteKey B(0, 2), L(1, 2), E(2, 2), S(3, 2), T(4, 2), X(5, 2);
260 
261  ADT pS = create(S % "50/50");
262  ADT pT = create(T % "95/5");
263  ADT pL = create(L | S = "99/1 90/10");
264  ADT pE = create((E | T, L) = "F T T T");
265  ADT pX = create(X | E = "95/5 2/98");
266  ADT pD = create(B | E = "1/8 7/9");
267  ADT pB = create(B | S = "70/30 40/60");
268 
269  // Create joint
270  resetCounts();
271  ADT fg = pS;
272  fg = apply(fg, pT, &mul);
273  fg = apply(fg, pL, &mul);
274  fg = apply(fg, pB, &mul);
275  fg = apply(fg, pE, &mul);
276  fg = apply(fg, pX, &mul);
277  fg = apply(fg, pD, &mul);
278  dot(fg, "FactorGraph");
279 #ifdef GTSAM_DT_MERGING
280  EXPECT_LONGS_EQUAL(158, (long)muls);
281 #else
282  EXPECT_LONGS_EQUAL(188, (long)muls);
283 #endif
284  printCounts("Asia FG");
285 
286  resetCounts();
287  fg = fg.combine(X, &add_);
288  dot(fg, "Marginalized-6X");
289  fg = fg.combine(T, &add_);
290  dot(fg, "Marginalized-5T");
291  fg = fg.combine(S, &add_);
292  dot(fg, "Marginalized-4S");
293  fg = fg.combine(E, &add_);
294  dot(fg, "Marginalized-3E");
295  fg = fg.combine(L, &add_);
296  dot(fg, "Marginalized-2L");
297 #ifdef GTSAM_DT_MERGING
298  LONGS_EQUAL(49, adds);
299 #else
300  LONGS_EQUAL(62, adds);
301 #endif
302  printCounts("marginalize");
303 
304  // BLESTX
305 
306  // Eliminate X
307  resetCounts();
308  ADT fE = pX;
309  dot(fE, "Eliminate-01-fEX");
310  fE = fE.combine(X, &add_);
311  dot(fE, "Eliminate-02-fE");
312  printCounts("Eliminate X");
313 
314  // Eliminate T
315  resetCounts();
316  ADT fLE = pT;
317  fLE = apply(fLE, pE, &mul);
318  dot(fLE, "Eliminate-03-fLET");
319  fLE = fLE.combine(T, &add_);
320  dot(fLE, "Eliminate-04-fLE");
321  printCounts("Eliminate T");
322 
323  // Eliminate S
324  resetCounts();
325  ADT fBL = pS;
326  fBL = apply(fBL, pL, &mul);
327  fBL = apply(fBL, pB, &mul);
328  dot(fBL, "Eliminate-05-fBLS");
329  fBL = fBL.combine(S, &add_);
330  dot(fBL, "Eliminate-06-fBL");
331  printCounts("Eliminate S");
332 
333  // Eliminate E
334  resetCounts();
335  ADT fBL2 = fE;
336  fBL2 = apply(fBL2, fLE, &mul);
337  fBL2 = apply(fBL2, pD, &mul);
338  dot(fBL2, "Eliminate-07-fBLE");
339  fBL2 = fBL2.combine(E, &add_);
340  dot(fBL2, "Eliminate-08-fBL2");
341  printCounts("Eliminate E");
342 
343  // Eliminate L
344  resetCounts();
345  ADT fB = fBL;
346  fB = apply(fB, fBL2, &mul);
347  dot(fB, "Eliminate-09-fBL");
348  fB = fB.combine(L, &add_);
349  dot(fB, "Eliminate-10-fB");
350  printCounts("Eliminate L");
351 }
352 
353 /* ************************************************************************* */
354 // test equality
355 TEST(ADT, equality_noparser) {
356  const DiscreteKey A(0, 2), B(1, 2);
357  const Signature::Row rA{80, 20}, rB{60, 40};
358  const Signature::Table tableA{rA}, tableB{rB};
359 
360  // Check straight equality
361  ADT pA1 = create(A % tableA);
362  ADT pA2 = create(A % tableA);
363  EXPECT(pA1.equals(pA2)); // should be equal
364 
365  // Check equality after apply
366  ADT pB = create(B % tableB);
367  ADT pAB1 = apply(pA1, pB, &mul);
368  ADT pAB2 = apply(pB, pA1, &mul);
369  EXPECT(pAB2.equals(pAB1));
370 }
371 
372 /* ************************************************************************* */
373 // test equality
374 TEST(ADT, equality_parser) {
375  DiscreteKey A(0, 2), B(1, 2);
376  // Check straight equality
377  ADT pA1 = create(A % "80/20");
378  ADT pA2 = create(A % "80/20");
379  EXPECT(pA1.equals(pA2)); // should be equal
380 
381  // Check equality after apply
382  ADT pB = create(B % "60/40");
383  ADT pAB1 = apply(pA1, pB, &mul);
384  ADT pAB2 = apply(pB, pA1, &mul);
385  EXPECT(pAB2.equals(pAB1));
386 }
387 
388 /* ************************************************************************** */
389 // Factor graph construction
390 // test constructor from strings
392  DiscreteKey v0(0, 2), v1(1, 3);
393  DiscreteValues x00, x01, x02, x10, x11, x12;
394  x00[0] = 0, x00[1] = 0;
395  x01[0] = 0, x01[1] = 1;
396  x02[0] = 0, x02[1] = 2;
397  x10[0] = 1, x10[1] = 0;
398  x11[0] = 1, x11[1] = 1;
399  x12[0] = 1, x12[1] = 2;
400 
401  ADT f1(v0 & v1, "0 1 2 3 4 5");
402  EXPECT_DOUBLES_EQUAL(0, f1(x00), 1e-9);
403  EXPECT_DOUBLES_EQUAL(1, f1(x01), 1e-9);
404  EXPECT_DOUBLES_EQUAL(2, f1(x02), 1e-9);
405  EXPECT_DOUBLES_EQUAL(3, f1(x10), 1e-9);
406  EXPECT_DOUBLES_EQUAL(4, f1(x11), 1e-9);
407  EXPECT_DOUBLES_EQUAL(5, f1(x12), 1e-9);
408 
409  ADT f2(v1 & v0, "0 1 2 3 4 5");
410  EXPECT_DOUBLES_EQUAL(0, f2(x00), 1e-9);
411  EXPECT_DOUBLES_EQUAL(2, f2(x01), 1e-9);
412  EXPECT_DOUBLES_EQUAL(4, f2(x02), 1e-9);
413  EXPECT_DOUBLES_EQUAL(1, f2(x10), 1e-9);
414  EXPECT_DOUBLES_EQUAL(3, f2(x11), 1e-9);
415  EXPECT_DOUBLES_EQUAL(5, f2(x12), 1e-9);
416 
417  DiscreteKey z0(0, 5), z1(1, 4), z2(2, 3), z3(3, 2);
418  vector<double> table(5 * 4 * 3 * 2);
419  double x = 0;
420  for (double& t : table) t = x++;
421  ADT f3(z0 & z1 & z2 & z3, table);
422  DiscreteValues assignment;
423  assignment[0] = 0;
424  assignment[1] = 0;
425  assignment[2] = 0;
426  assignment[3] = 1;
427  EXPECT_DOUBLES_EQUAL(1, f3(assignment), 1e-9);
428 }
429 
430 /* ************************************************************************* */
431 // test conversion to integer indices
432 // Only works if DiscreteKeys are binary, as size_t has binary cardinality!
433 TEST(ADT, conversion) {
434  DiscreteKey X(0, 2), Y(1, 2);
435  ADT fDiscreteKey(X & Y, "0.2 0.5 0.3 0.6");
436  dot(fDiscreteKey, "conversion-f1");
437 
438  std::map<Key, Key> keyMap;
439  keyMap[0] = 5;
440  keyMap[1] = 2;
441 
442  AlgebraicDecisionTree<Key> fIndexKey(fDiscreteKey, keyMap);
443  // f1.print("f1");
444  // f2.print("f2");
445  dot(fIndexKey, "conversion-f2");
446 
447  DiscreteValues x00, x01, x02, x10, x11, x12;
448  x00[5] = 0, x00[2] = 0;
449  x01[5] = 0, x01[2] = 1;
450  x10[5] = 1, x10[2] = 0;
451  x11[5] = 1, x11[2] = 1;
452  EXPECT_DOUBLES_EQUAL(0.2, fIndexKey(x00), 1e-9);
453  EXPECT_DOUBLES_EQUAL(0.5, fIndexKey(x01), 1e-9);
454  EXPECT_DOUBLES_EQUAL(0.3, fIndexKey(x10), 1e-9);
455  EXPECT_DOUBLES_EQUAL(0.6, fIndexKey(x11), 1e-9);
456 }
457 
458 /* ************************************************************************** */
459 // test operations in elimination
460 TEST(ADT, elimination) {
461  DiscreteKey A(0, 2), B(1, 3), C(2, 2);
462  ADT f1(A & B & C, "1 2 3 4 5 6 1 8 3 3 5 5");
463  dot(f1, "elimination-f1");
464 
465  {
466  // sum out lower key
467  ADT actualSum = f1.sum(C);
468  ADT expectedSum(A & B, "3 7 11 9 6 10");
469  CHECK(assert_equal(expectedSum, actualSum));
470 
471  // normalize
472  ADT actual = f1 / actualSum;
473  const vector<double> cpt{
474  1.0 / 3, 2.0 / 3, 3.0 / 7, 4.0 / 7, 5.0 / 11, 6.0 / 11, //
475  1.0 / 9, 8.0 / 9, 3.0 / 6, 3.0 / 6, 5.0 / 10, 5.0 / 10};
476  ADT expected(A & B & C, cpt);
477  CHECK(assert_equal(expected, actual));
478  }
479 
480  {
481  // sum out lower 2 keys
482  ADT actualSum = f1.sum(C).sum(B);
483  ADT expectedSum(A, 21, 25);
484  CHECK(assert_equal(expectedSum, actualSum));
485 
486  // normalize
487  ADT actual = f1 / actualSum;
488  const vector<double> cpt{
489  1.0 / 21, 2.0 / 21, 3.0 / 21, 4.0 / 21, 5.0 / 21, 6.0 / 21, //
490  1.0 / 25, 8.0 / 25, 3.0 / 25, 3.0 / 25, 5.0 / 25, 5.0 / 25};
491  ADT expected(A & B & C, cpt);
492  CHECK(assert_equal(expected, actual));
493  }
494 }
495 
496 /* ************************************************************************** */
497 // Test non-commutative op
498 TEST(ADT, div) {
499  DiscreteKey A(0, 2), B(1, 2);
500 
501  // Literals
502  ADT a(A, 8, 16);
503  ADT b(B, 2, 4);
504  ADT expected_a_div_b(A & B, "4 2 8 4"); // 8/2 8/4 16/2 16/4
505  ADT expected_b_div_a(A & B, "0.25 0.5 0.125 0.25"); // 2/8 4/8 2/16 4/16
506  EXPECT(assert_equal(expected_a_div_b, a / b));
507  EXPECT(assert_equal(expected_b_div_a, b / a));
508 }
509 
510 /* ************************************************************************** */
511 // test zero shortcut
513  DiscreteKey A(0, 2), B(1, 2);
514 
515  // Literals
516  ADT a(A, 0, 1);
517  ADT notb(B, 1, 0);
518  ADT anotb = a * notb;
519  // GTSAM_PRINT(anotb);
520  DiscreteValues x00, x01, x10, x11;
521  x00[0] = 0, x00[1] = 0;
522  x01[0] = 0, x01[1] = 1;
523  x10[0] = 1, x10[1] = 0;
524  x11[0] = 1, x11[1] = 1;
525  EXPECT_DOUBLES_EQUAL(0, anotb(x00), 1e-9);
526  EXPECT_DOUBLES_EQUAL(0, anotb(x01), 1e-9);
527  EXPECT_DOUBLES_EQUAL(1, anotb(x10), 1e-9);
528  EXPECT_DOUBLES_EQUAL(0, anotb(x11), 1e-9);
529 }
530 
533  DiscreteKey A(0, 2), B(1, 3), C(2, 2);
534  ADT f(A & B & C, "0 6 2 8 4 10 1 7 3 9 5 11");
535  return f;
536 }
537 /* ************************************************************************** */
538 // Test sum
539 TEST(ADT, Sum) {
540  ADT a = exampleADT();
541  double expected_sum = 0;
542  for (double i = 0; i < 12; i++) {
543  expected_sum += i;
544  }
545  EXPECT_DOUBLES_EQUAL(expected_sum, a.sum(), 1e-9);
546 }
547 
548 /* ************************************************************************** */
549 // Test normalize
550 TEST(ADT, Normalize) {
551  ADT a = exampleADT();
552  double sum = a.sum();
553  auto actual = a.normalize(sum);
554 
555  DiscreteKey A(0, 2), B(1, 3), C(2, 2);
557  std::vector<double> cpt{0 / sum, 6 / sum, 2 / sum, 8 / sum,
558  4 / sum, 10 / sum, 1 / sum, 7 / sum,
559  3 / sum, 9 / sum, 5 / sum, 11 / sum};
560  ADT expected(keys, cpt);
561  EXPECT(assert_equal(expected, actual));
562 }
563 
564 /* ************************************************************************** */
565 // Test min
566 TEST(ADT, Min) {
567  ADT a = exampleADT();
568  double min = a.min();
569  EXPECT_DOUBLES_EQUAL(0.0, min, 1e-9);
570 }
571 
572 /* ************************************************************************** */
573 // Test max
574 TEST(ADT, Max) {
575  ADT a = exampleADT();
576  double max = a.max();
577  EXPECT_DOUBLES_EQUAL(11.0, max, 1e-9);
578 }
579 
580 /* ************************************************************************* */
581 int main() {
582  TestResult tr;
583  return TestRegistry::runAllTests(tr);
584 }
585 /* ************************************************************************* */
gtsam::Signature::cpt
std::vector< double > cpt() const
Definition: Signature.cpp:69
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
asiaCPTs::L
DiscreteKey L(3, 2)
create
ADT create(const Signature &signature)
Definition: testAlgebraicDecisionTree.cpp:124
gtsam::Signature::Table
std::vector< Row > Table
Definition: Signature.h:60
asiaCPTs::X
DiscreteKey X(6, 2)
gtsam::Signature::key
const DiscreteKey & key() const
Definition: Signature.h:115
add_
double add_(const double &a, const double &b)
Definition: testAlgebraicDecisionTree.cpp:86
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
Y
const char Y
Definition: test/EulerAngles.cpp:31
test_constructor::f1
auto f1
Definition: testHybridNonlinearFactor.cpp:56
muls
size_t muls
Definition: testAlgebraicDecisionTree.cpp:70
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
v0
static const double v0
Definition: testCal3DFisheye.cpp:31
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
main
int main()
Definition: testAlgebraicDecisionTree.cpp:581
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
b
Scalar * b
Definition: benchVecAdd.cpp:17
z1
Point2 z1
Definition: testTriangulationFactor.cpp:45
asiaCPTs::pX
ADT pX
Definition: testAlgebraicDecisionTree.cpp:147
x
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
Definition: gnuplot_common_settings.hh:12
asiaCPTs::pA
ADT pA
Definition: testAlgebraicDecisionTree.cpp:141
asiaCPTs
Definition: testAlgebraicDecisionTree.cpp:137
f2
double f2(const Vector2 &x)
Definition: testNumericalDerivative.cpp:56
mul
double mul(const double &a, const double &b)
Definition: testAlgebraicDecisionTree.cpp:82
gtsam::Signature::Row
std::vector< double > Row
Definition: Signature.h:59
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
gtsam::AlgebraicDecisionTree::equals
bool equals(const AlgebraicDecisionTree &other, double tol=1e-9) const
Equality method customized to value type double.
Definition: AlgebraicDecisionTree.h:258
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
gtsam::AlgebraicDecisionTree< Key >
printCounts
void printCounts(const string &s)
Definition: testAlgebraicDecisionTree.cpp:75
ss
static std::stringstream ss
Definition: testBTree.cpp:31
asiaCPTs::pE
ADT pE
Definition: testAlgebraicDecisionTree.cpp:146
AlgebraicDecisionTree.h
Algebraic Decision Trees.
z3
static const Unit3 z3
Definition: testRotateFactor.cpp:44
asiaCPTs::T
DiscreteKey T(2, 2)
ADT
AlgebraicDecisionTree< Key > ADT
Definition: testAlgebraicDecisionTree.cpp:32
table
ArrayXXf table(10, 4)
TEST
TEST(ADT, example3)
Definition: testAlgebraicDecisionTree.cpp:93
relicense.filename
filename
Definition: relicense.py:57
resetCounts
void resetCounts()
Definition: testAlgebraicDecisionTree.cpp:71
Signature.h
signatures for conditional densities
zero
EIGEN_DONT_INLINE Scalar zero()
Definition: svd_common.h:296
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
exampleADT
ADT exampleADT()
Example ADT from 0 to 11.
Definition: testAlgebraicDecisionTree.cpp:532
asiaCPTs::pT
ADT pT
Definition: testAlgebraicDecisionTree.cpp:143
asiaCPTs::pS
ADT pS
Definition: testAlgebraicDecisionTree.cpp:142
Eigen::Triplet< double >
dot
void dot(const T &f, const string &filename)
Definition: testAlgebraicDecisionTree.cpp:43
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
asiaCPTs::pD
ADT pD
Definition: testAlgebraicDecisionTree.cpp:148
TestResult
Definition: TestResult.h:26
DiscreteKey.h
specialized key for discrete variables
key
const gtsam::Symbol key('X', 0)
E
DiscreteKey E(5, 2)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
C
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
gtsam
traits
Definition: chartTesting.h:28
gtsam::Testable
Definition: Testable.h:152
DiscreteValues.h
DecisionTree-inl.h
gtsam::traits
Definition: Group.h:36
constructor
Definition: init.h:200
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
f3
double f3(double x1, double x2)
Definition: testNumericalDerivative.cpp:76
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std
Definition: BFloat16.h:88
big
static double big
Definition: igam.c:119
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::apply
DecisionTree< L, Y > apply(const DecisionTree< L, Y > &f, const typename DecisionTree< L, Y >::Unary &op)
Apply unary operator op to DecisionTree f.
Definition: DecisionTree.h:427
asiaCPTs::D
DiscreteKey D(7, 2)
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
min
#define min(a, b)
Definition: datatypes.h:19
gtsam::Signature::discreteKeys
DiscreteKeys discreteKeys() const
Definition: Signature.cpp:55
asiaCPTs::pB
ADT pB
Definition: testAlgebraicDecisionTree.cpp:145
gtsam::DecisionTree::combine
DecisionTree combine(const L &label, size_t cardinality, const Binary &op) const
Definition: DecisionTree-inl.h:970
align_3::t
Point2 t(10, 10)
max
#define max(a, b)
Definition: datatypes.h:20
asiaCPTs::pL
ADT pL
Definition: testAlgebraicDecisionTree.cpp:144
gtsam::Signature
Definition: Signature.h:54
LONGS_EQUAL
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:134
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
adds
size_t adds
Definition: testAlgebraicDecisionTree.cpp:70
S
DiscreteKey S(1, 2)
v1
Vector v1
Definition: testSerializationBase.cpp:38
z2
static const Unit3 z2
Definition: testRotateFactor.cpp:43


gtsam
Author(s):
autogenerated on Sat Sep 28 2024 03:05:08