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