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


gtsam
Author(s):
autogenerated on Sun Feb 16 2025 04:06:00