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