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


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