testDecisionTree.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  * @author Can Erdogan
17  * @date Jan 30, 2012
18  */
19 
20 // #define DT_DEBUG_MEMORY
21 #define DISABLE_DOT
23 #include <gtsam/base/Testable.h>
27 #include <gtsam/inference/Symbol.h>
28 
29 #include <iomanip>
30 
31 using std::vector;
32 using std::string;
33 using std::map;
34 using namespace gtsam;
35 
36 template <typename T>
37 void dot(const T& f, const string& filename) {
38 #ifndef DISABLE_DOT
39  f.dot(filename);
40 #endif
41 }
42 
43 #define DOT(x) (dot(x, #x))
44 
45 struct Crazy {
46  int a;
47  double b;
48 };
49 
50 struct CrazyDecisionTree : public DecisionTree<string, Crazy> {
52  void print(const std::string& s = "") const {
53  auto keyFormatter = [](const std::string& s) { return s; };
54  auto valueFormatter = [](const Crazy& v) {
55  std::stringstream ss;
56  ss << "{" << v.a << "," << std::setw(4) << std::setprecision(2) << v.b << "}";
57  return ss.str();
58  };
60  }
62  bool equals(const CrazyDecisionTree& other, double tol = 1e-9) const {
63  auto compare = [tol](const Crazy& v, const Crazy& w) {
64  return v.a == w.a && std::abs(v.b - w.b) < tol;
65  };
67  }
68 };
69 
70 // traits
71 namespace gtsam {
72 template <>
73 struct traits<CrazyDecisionTree> : public Testable<CrazyDecisionTree> {};
74 } // namespace gtsam
75 
77 
78 /* ************************************************************************** */
79 // Test char labels and int range
80 /* ************************************************************************** */
81 
82 // Create a decision stump one one variable 'a' with values 10 and 20.
83 TEST(DecisionTree, Constructor) {
84  DecisionTree<char, int> tree('a', 10, 20);
85 
86  // Evaluate the tree on an assignment to the variable.
87  EXPECT_LONGS_EQUAL(10, tree({{'a', 0}}));
88  EXPECT_LONGS_EQUAL(20, tree({{'a', 1}}));
89 }
90 
91 /* ************************************************************************** */
92 // Test string labels and int range
93 /* ************************************************************************** */
94 
95 struct DT : public DecisionTree<string, int> {
98  DT() = default;
99 
100  DT(const Base& dt) : Base(dt) {}
101 
103  void print(const std::string& s = "") const {
104  auto keyFormatter = [](const std::string& s) { return s; };
105  auto valueFormatter = [](const int& v) {
106  return std::to_string(v);
107  };
108  std::cout << s;
109  Base::print("", keyFormatter, valueFormatter);
110  }
112  bool equals(const Base& other, double tol = 1e-9) const {
113  auto compare = [](const int& v, const int& w) { return v == w; };
114  return Base::equals(other, compare);
115  }
116 };
117 
118 // traits
119 namespace gtsam {
120 template <>
121 struct traits<DT> : public Testable<DT> {};
122 } // namespace gtsam
123 
125 
126 struct Ring {
127  static inline int zero() { return 0; }
128  static inline int one() { return 1; }
129  static inline int id(const int& a) { return a; }
130  static inline int add(const int& a, const int& b) { return a + b; }
131  static inline int mul(const int& a, const int& b) { return a * b; }
132 };
133 
134 /* ************************************************************************** */
135 // Check that creating decision trees respects key order.
136 TEST(DecisionTree, ConstructorOrder) {
137  // Create labels
138  string A("A"), B("B");
139 
140  const std::vector<int> ys1 = {1, 2, 3, 4};
141  DT tree1({{B, 2}, {A, 2}}, ys1); // faster version, as B is "higher" than A!
142 
143  const std::vector<int> ys2 = {1, 3, 2, 4};
144  DT tree2({{A, 2}, {B, 2}}, ys2); // slower version !
145 
146  // Both trees will be the same, tree is order from high to low labels.
147  // Choice(B)
148  // 0 Choice(A)
149  // 0 0 Leaf 1
150  // 0 1 Leaf 2
151  // 1 Choice(A)
152  // 1 0 Leaf 3
153  // 1 1 Leaf 4
154 
155  EXPECT(tree2.equals(tree1));
156 
157  // Check the values are as expected by calling the () operator:
158  EXPECT_LONGS_EQUAL(1, tree1({{A, 0}, {B, 0}}));
159  EXPECT_LONGS_EQUAL(3, tree1({{A, 0}, {B, 1}}));
160  EXPECT_LONGS_EQUAL(2, tree1({{A, 1}, {B, 0}}));
161  EXPECT_LONGS_EQUAL(4, tree1({{A, 1}, {B, 1}}));
162 }
163 
164 /* ************************************************************************** */
165 // test DT
166 TEST(DecisionTree, Example) {
167  // Create labels
168  string A("A"), B("B"), C("C");
169 
170  // Create assignments using brace initialization:
171  Assignment<string> x00{{A, 0}, {B, 0}};
172  Assignment<string> x01{{A, 0}, {B, 1}};
173  Assignment<string> x10{{A, 1}, {B, 0}};
174  Assignment<string> x11{{A, 1}, {B, 1}};
175 
176  // empty
177  DT empty;
178 
179  // A
180  DT a(A, 0, 5);
181  LONGS_EQUAL(0, a(x00))
182  LONGS_EQUAL(5, a(x10))
183  DOT(a);
184 
185  // pruned
186  DT p(A, 2, 2);
187  LONGS_EQUAL(2, p(x00))
188  LONGS_EQUAL(2, p(x10))
189  DOT(p);
190 
191  // \neg B
192  DT notb(B, 5, 0);
193  LONGS_EQUAL(5, notb(x00))
194  LONGS_EQUAL(5, notb(x10))
195  DOT(notb);
196 
197  // Check supplying empty trees yields an exception
198  CHECK_EXCEPTION(gtsam::apply(empty, &Ring::id), std::runtime_error);
199  CHECK_EXCEPTION(gtsam::apply(empty, a, &Ring::mul), std::runtime_error);
200  CHECK_EXCEPTION(gtsam::apply(a, empty, &Ring::mul), std::runtime_error);
201 
202  // apply, two nodes, in natural order
203  DT anotb = apply(a, notb, &Ring::mul);
204  LONGS_EQUAL(0, anotb(x00))
205  LONGS_EQUAL(0, anotb(x01))
206  LONGS_EQUAL(25, anotb(x10))
207  LONGS_EQUAL(0, anotb(x11))
208  DOT(anotb);
209 
210  // check pruning
211  DT pnotb = apply(p, notb, &Ring::mul);
212  LONGS_EQUAL(10, pnotb(x00))
213  LONGS_EQUAL(0, pnotb(x01))
214  LONGS_EQUAL(10, pnotb(x10))
215  LONGS_EQUAL(0, pnotb(x11))
216  DOT(pnotb);
217 
218  // check pruning
219  DT zeros = apply(DT(A, 0, 0), notb, &Ring::mul);
220  LONGS_EQUAL(0, zeros(x00))
221  LONGS_EQUAL(0, zeros(x01))
222  LONGS_EQUAL(0, zeros(x10))
223  LONGS_EQUAL(0, zeros(x11))
224  DOT(zeros);
225 
226  // apply, two nodes, in switched order
227  DT notba = apply(a, notb, &Ring::mul);
228  LONGS_EQUAL(0, notba(x00))
229  LONGS_EQUAL(0, notba(x01))
230  LONGS_EQUAL(25, notba(x10))
231  LONGS_EQUAL(0, notba(x11))
232  DOT(notba);
233 
234  // Test choose 0
235  DT actual0 = notba.choose(A, 0);
236 #ifdef GTSAM_DT_MERGING
237  EXPECT(assert_equal(DT(0.0), actual0));
238 #else
239  EXPECT(assert_equal(DT({0.0, 0.0}), actual0));
240 #endif
241  DOT(actual0);
242 
243  // Test choose 1
244  DT actual1 = notba.choose(A, 1);
245  EXPECT(assert_equal(DT(B, 25, 0), actual1));
246  DOT(actual1);
247 
248  // apply, two nodes at same level
249  DT a_and_a = apply(a, a, &Ring::mul);
250  LONGS_EQUAL(0, a_and_a(x00))
251  LONGS_EQUAL(0, a_and_a(x01))
252  LONGS_EQUAL(25, a_and_a(x10))
253  LONGS_EQUAL(25, a_and_a(x11))
254  DOT(a_and_a);
255 
256  // create a function on C
257  DT c(C, 0, 5);
258 
259  // and a model assigning stuff to C
260  Assignment<string> x101;
261  x101[A] = 1, x101[B] = 0, x101[C] = 1;
262 
263  // mul notba with C
264  DT notbac = apply(notba, c, &Ring::mul);
265  LONGS_EQUAL(125, notbac(x101))
266  DOT(notbac);
267 
268  // mul now in different order
269  DT acnotb = apply(apply(a, c, &Ring::mul), notb, &Ring::mul);
270  LONGS_EQUAL(125, acnotb(x101))
271  DOT(acnotb);
272 }
273 
274 /* ************************************************************************** */
275 // test Conversion of values
276 bool bool_of_int(const int& y) { return y != 0; };
278 
279 TEST(DecisionTree, ConvertValuesOnly) {
280  // Create labels
281  string A("A"), B("B");
282 
283  // apply, two nodes, in natural order
284  DT f1 = apply(DT(A, 0, 5), DT(B, 5, 0), &Ring::mul);
285 
286  // convert
288 
289  // Check a value
290  Assignment<string> x00 {{A, 0}, {B, 0}};
291  EXPECT(!f2(x00));
292 }
293 
294 /* ************************************************************************** */
295 // test Conversion of both values and labels.
296 enum Label { U, V, X, Y, Z };
298 
299 TEST(DecisionTree, ConvertBoth) {
300  // Create labels
301  string A("A"), B("B");
302 
303  // apply, two nodes, in natural order
304  DT f1 = apply(DT(A, 0, 5), DT(B, 5, 0), &Ring::mul);
305 
306  // convert
307  map<string, Label> ordering;
308  ordering[A] = X;
309  ordering[B] = Y;
311 
312  // Check some values
313  Assignment<Label> x00, x01, x10, x11;
314  x00 = {{X, 0}, {Y, 0}};
315  x01 = {{X, 0}, {Y, 1}};
316  x10 = {{X, 1}, {Y, 0}};
317  x11 = {{X, 1}, {Y, 1}};
318 
319  EXPECT(!f2(x00));
320  EXPECT(!f2(x01));
321  EXPECT(f2(x10));
322  EXPECT(!f2(x11));
323 }
324 
325 /* ************************************************************************** */
326 // test Compose expansion
327 TEST(DecisionTree, Compose) {
328  // Create labels
329  string A("A"), B("B"), C("C");
330 
331  // Put two stumps on A together
332  DT f1(B, DT(A, 0, 1), DT(A, 2, 3));
333 
334  // Create from string
335  vector<DT::LabelC> keys{DT::LabelC(A, 2), DT::LabelC(B, 2)};
336  DT f2(keys, "0 2 1 3");
337  EXPECT(assert_equal(f2, f1, 1e-9));
338 
339  // Put this AB tree together with another one
340  DT f3(keys, "4 6 5 7");
341  DT f4(C, f1, f3);
342  DOT(f4);
343 
344  // a bigger tree
345  keys.push_back(DT::LabelC(C, 2));
346  DT f5(keys, "0 4 2 6 1 5 3 7");
347  EXPECT(assert_equal(f5, f4, 1e-9));
348  DOT(f5);
349 }
350 
351 /* ************************************************************************** */
352 // Check we can create a decision tree of containers.
353 TEST(DecisionTree, Containers) {
354  using Container = std::vector<double>;
355  using StringContainerTree = DecisionTree<string, Container>;
356 
357  // Check default constructor
358  StringContainerTree tree;
359 
360  // Create small two-level tree
361  string A("A"), B("B");
362  DT stringIntTree(B, DT(A, 0, 1), DT(A, 2, 3));
363 
364  // Check conversion
365  auto container_of_int = [](const int& i) {
366  Container c;
367  c.emplace_back(i);
368  return c;
369  };
370  StringContainerTree converted(stringIntTree, container_of_int);
371 }
372 
373 /* ************************************************************************** */
374 // Test visit.
376  // Create small two-level tree
377  string A("A"), B("B");
378  DT tree(B, DT(A, 0, 1), DT(A, 2, 3));
379  double sum = 0.0;
380  auto visitor = [&](int y) { sum += y; };
381  tree.visit(visitor);
382  EXPECT_DOUBLES_EQUAL(6.0, sum, 1e-9);
383 }
384 
385 /* ************************************************************************** */
386 // Test visit, with Choices argument.
387 TEST(DecisionTree, visitWith) {
388  // Create small two-level tree
389  string A("A"), B("B");
390  DT tree(B, DT(A, 0, 1), DT(A, 2, 3));
391  double sum = 0.0;
392  auto visitor = [&](const Assignment<string>& choices, int y) { sum += y; };
393  tree.visitWith(visitor);
394  EXPECT_DOUBLES_EQUAL(6.0, sum, 1e-9);
395 }
396 
397 /* ************************************************************************** */
398 // Test visit, with Choices argument.
399 TEST(DecisionTree, VisitWithPruned) {
400  // Create pruned tree
401  std::pair<string, size_t> A("A", 2), B("B", 2), C("C", 2);
402  std::vector<std::pair<string, size_t>> labels = {C, B, A};
403  std::vector<int> nodes = {0, 0, 2, 3, 4, 4, 6, 7};
404  DT tree(labels, nodes);
405 
406  std::vector<Assignment<string>> choices;
407  auto func = [&](const Assignment<string>& choice, const int& d) {
408  choices.push_back(choice);
409  };
410  tree.visitWith(func);
411 
412 #ifdef GTSAM_DT_MERGING
413  EXPECT_LONGS_EQUAL(6, choices.size());
414 #else
415  EXPECT_LONGS_EQUAL(8, choices.size());
416 #endif
417 
418  Assignment<string> expectedAssignment;
419 
420 #ifdef GTSAM_DT_MERGING
421  expectedAssignment = {{"B", 0}, {"C", 0}};
422  EXPECT(expectedAssignment == choices.at(0));
423 
424  expectedAssignment = {{"A", 0}, {"B", 1}, {"C", 0}};
425  EXPECT(expectedAssignment == choices.at(1));
426 
427  expectedAssignment = {{"A", 1}, {"B", 1}, {"C", 0}};
428  EXPECT(expectedAssignment == choices.at(2));
429 
430  expectedAssignment = {{"B", 0}, {"C", 1}};
431  EXPECT(expectedAssignment == choices.at(3));
432 
433  expectedAssignment = {{"A", 0}, {"B", 1}, {"C", 1}};
434  EXPECT(expectedAssignment == choices.at(4));
435 
436  expectedAssignment = {{"A", 1}, {"B", 1}, {"C", 1}};
437  EXPECT(expectedAssignment == choices.at(5));
438 #else
439  expectedAssignment = {{"A", 0}, {"B", 0}, {"C", 0}};
440  EXPECT(expectedAssignment == choices.at(0));
441 
442  expectedAssignment = {{"A", 1}, {"B", 0}, {"C", 0}};
443  EXPECT(expectedAssignment == choices.at(1));
444 
445  expectedAssignment = {{"A", 0}, {"B", 1}, {"C", 0}};
446  EXPECT(expectedAssignment == choices.at(2));
447 
448  expectedAssignment = {{"A", 1}, {"B", 1}, {"C", 0}};
449  EXPECT(expectedAssignment == choices.at(3));
450 
451  expectedAssignment = {{"A", 0}, {"B", 0}, {"C", 1}};
452  EXPECT(expectedAssignment == choices.at(4));
453 
454  expectedAssignment = {{"A", 1}, {"B", 0}, {"C", 1}};
455  EXPECT(expectedAssignment == choices.at(5));
456 #endif
457 }
458 
459 /* ************************************************************************** */
460 // Test fold.
462  // Create small two-level tree
463  string A("A"), B("B");
464  DT tree(B, DT(A, 1, 1), DT(A, 2, 3));
465  auto add = [](const int& y, double x) { return y + x; };
466  double sum = tree.fold(add, 0.0);
467 #ifdef GTSAM_DT_MERGING
468  EXPECT_DOUBLES_EQUAL(6.0, sum, 1e-9); // Note, not 7, due to merging!
469 #else
470  EXPECT_DOUBLES_EQUAL(7.0, sum, 1e-9);
471 #endif
472 }
473 
474 /* ************************************************************************** */
475 // Test retrieving all labels.
477  // Create small two-level tree
478  string A("A"), B("B");
479  DT tree(B, DT(A, 0, 1), DT(A, 2, 3));
480  auto labels = tree.labels();
481  EXPECT_LONGS_EQUAL(2, labels.size());
482 }
483 
484 /* ************************************************************************** */
485 // Test unzip method.
488  using DT1 = DecisionTree<string, int>;
489  using DT2 = DecisionTree<string, string>;
490 
491  // Create small two-level tree
492  string A("A"), B("B"), C("C");
493  DTP tree(B, DTP(A, {0, "zero"}, {1, "one"}),
494  DTP(A, {2, "two"}, {1337, "l33t"}));
495 
496  const auto [dt1, dt2] = unzip(tree);
497 
498  DT1 tree1(B, DT1(A, 0, 1), DT1(A, 2, 1337));
499  DT2 tree2(B, DT2(A, "zero", "one"), DT2(A, "two", "l33t"));
500 
501  EXPECT(tree1.equals(dt1));
502  EXPECT(tree2.equals(dt2));
503 }
504 
505 /* ************************************************************************** */
506 // Test thresholding.
507 TEST(DecisionTree, threshold) {
508  // Create three level tree
509  const vector<DT::LabelC> keys{DT::LabelC("C", 2), DT::LabelC("B", 2),
510  DT::LabelC("A", 2)};
511  DT tree(keys, "0 1 2 3 4 5 6 7");
512 
513  // Check number of leaves equal to zero
514  auto count = [](const int& value, int count) {
515  return value == 0 ? count + 1 : count;
516  };
517  EXPECT_LONGS_EQUAL(1, tree.fold(count, 0));
518 
519  // Now threshold
520  auto threshold = [](int value) { return value < 5 ? 0 : value; };
521  DT thresholded(tree, threshold);
522 
523 #ifdef GTSAM_DT_MERGING
524  // Check number of leaves equal to zero now = 2
525  // Note: it is 2, because the pruned branches are counted as 1!
526  EXPECT_LONGS_EQUAL(2, thresholded.fold(count, 0));
527 #else
528  // if GTSAM_DT_MERGING is disabled, the count will be larger
529  EXPECT_LONGS_EQUAL(5, thresholded.fold(count, 0));
530 #endif
531 }
532 
533 /* ************************************************************************** */
534 // Test apply with assignment.
535 TEST(DecisionTree, ApplyWithAssignment) {
536  // Create three level tree
537  const vector<DT::LabelC> keys{DT::LabelC("C", 2), DT::LabelC("B", 2),
538  DT::LabelC("A", 2)};
539  DT tree(keys, "1 2 3 4 5 6 7 8");
540 
542  keys, "0.01 0.02 0.03 0.04 0.05 0.06 0.07 0.08");
543  double threshold = 0.045;
544 
545  // We test pruning one tree by indexing into another.
546  auto pruner = [&](const Assignment<string>& choices, const int& x) {
547  // Prune out all the leaves with even numbers
548  if (probTree(choices) < threshold) {
549  return 0;
550  } else {
551  return x;
552  }
553  };
554  DT prunedTree = tree.apply(pruner);
555 
556  DT expectedTree(keys, "0 0 0 0 5 6 7 8");
557  EXPECT(assert_equal(expectedTree, prunedTree));
558 
559  size_t count = 0;
560  auto counter = [&](const Assignment<string>& choices, const int& x) {
561  count += 1;
562  return x;
563  };
564  DT prunedTree2 = prunedTree.apply(counter);
565 
566 #ifdef GTSAM_DT_MERGING
567  // Check if apply doesn't enumerate all leaves.
568  EXPECT_LONGS_EQUAL(5, count);
569 #else
570  // if GTSAM_DT_MERGING is disabled, the count will be full
571  EXPECT_LONGS_EQUAL(8, count);
572 #endif
573 }
574 
575 /* ************************************************************************* */
576 int main() {
577  TestResult tr;
578  return TestRegistry::runAllTests(tr);
579 }
580 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
Ring::id
static int id(const int &a)
Definition: testDecisionTree.cpp:129
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
compare
bool compare
Definition: SolverComparer.cpp:98
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
CHECK_EXCEPTION
#define CHECK_EXCEPTION(condition, exception_name)
Definition: Test.h:118
Ring::one
static int one()
Definition: testDecisionTree.cpp:128
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
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
GTSAM_CONCEPT_TESTABLE_INST
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:176
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
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
DT::equals
bool equals(const Base &other, double tol=1e-9) const
Equality method customized to int node type.
Definition: testDecisionTree.cpp:112
tree
Definition: testExpression.cpp:212
gtsam::DecisionTree::equals
bool equals(const DecisionTree &other, const CompareFunc &compare=&DefaultCompare) const
Definition: DecisionTree-inl.h:898
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
dt
const double dt
Definition: testVelocityConstraint.cpp:15
f2
double f2(const Vector2 &x)
Definition: testNumericalDerivative.cpp:56
gtsam::DecisionTree::DecisionTree
DecisionTree()
Definition: DecisionTree-inl.h:482
gtsam::DecisionTree::print
void print(const std::string &s, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter) const
GTSAM-style print.
Definition: DecisionTree-inl.h:904
gtsam::DecisionTree::choose
DecisionTree choose(const L &label, size_t index) const
Definition: DecisionTree.h:370
bool_of_int
bool bool_of_int(const int &y)
Definition: testDecisionTree.cpp:276
Ring
Definition: testDecisionTree.cpp:126
Ring::zero
static int zero()
Definition: testDecisionTree.cpp:127
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
ss
static std::stringstream ss
Definition: testBTree.cpp:31
DOT
#define DOT(x)
Definition: testDecisionTree.cpp:43
labels
std::vector< std::string > labels
Definition: dense_solvers.cpp:11
DT::print
void print(const std::string &s="") const
print to stdout
Definition: testDecisionTree.cpp:103
DT
Definition: testDecisionTree.cpp:95
relicense.filename
filename
Definition: relicense.py:57
V
@ V
Definition: testDecisionTree.cpp:296
Signature.h
signatures for conditional densities
add
graph add(PriorFactor< Pose2 >(1, priorMean, priorNoise))
Crazy::a
int a
Definition: testDecisionTree.cpp:46
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:195
main
int main()
Definition: testDecisionTree.cpp:576
CrazyDecisionTree::equals
bool equals(const CrazyDecisionTree &other, double tol=1e-9) const
Equality method customized to Crazy node type.
Definition: testDecisionTree.cpp:62
Symbol.h
gtsam::Assignment
Definition: Assignment.h:37
Ring::add
static int add(const int &a, const int &b)
Definition: testDecisionTree.cpp:130
Eigen::Triplet< double >
gtsam::DecisionTree::apply
DecisionTree apply(const Unary &op) const
Definition: DecisionTree-inl.h:921
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
ordering
static enum @1096 ordering
serializationTestHelpers.h
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::DecisionTree
a decision tree is a function from assignments to values.
Definition: DecisionTree.h:63
gtsam::b
const G & b
Definition: Group.h:79
nodes
KeyVector nodes
Definition: testMFAS.cpp:28
DT::DT
DT(const Base &dt)
Definition: testDecisionTree.cpp:100
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
Label
Label
Definition: testDecisionTree.cpp:296
empty
Definition: test_copy_move.cpp:19
C
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
gtsam
traits
Definition: chartTesting.h:28
gtsam::Testable
Definition: Testable.h:152
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
DecisionTree-inl.h
gtsam::traits
Definition: Group.h:36
LabelBoolTree
DecisionTree< Label, bool > LabelBoolTree
Definition: testDecisionTree.cpp:297
f3
double f3(double x1, double x2)
Definition: testNumericalDerivative.cpp:76
CrazyDecisionTree
Definition: testDecisionTree.cpp:50
gtsam::DecisionTree< string, int >::LabelC
std::pair< string, size_t > LabelC
Definition: DecisionTree.h:81
X
@ X
Definition: testDecisionTree.cpp:296
p
float * p
Definition: Tutorial_Map_using.cpp:9
StringBoolTree
DecisionTree< string, bool > StringBoolTree
Definition: testDecisionTree.cpp:276
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
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
f4
double f4(double x, double y, double z)
Definition: testNumericalDerivative.cpp:105
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
CrazyDecisionTree::print
void print(const std::string &s="") const
print to stdout
Definition: testDecisionTree.cpp:52
gtsam::tol
const G double tol
Definition: Group.h:79
U
@ U
Definition: testDecisionTree.cpp:296
Y
@ Y
Definition: testDecisionTree.cpp:296
abs
#define abs(x)
Definition: datatypes.h:17
unary::f1
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
Definition: testExpression.cpp:79
func
Definition: benchGeometry.cpp:23
gtsam::unzip
std::pair< DecisionTree< L, T1 >, DecisionTree< L, T2 > > unzip(const DecisionTree< L, std::pair< T1, T2 > > &input)
unzip a DecisionTree with std::pair values.
Definition: DecisionTree.h:454
gtsam::valueFormatter
static std::string valueFormatter(const double &v)
Definition: DecisionTreeFactor.cpp:266
gtsam::DecisionTree::fold
X fold(Func f, X x0) const
Fold a binary function over the tree, returning accumulator.
Definition: DecisionTree-inl.h:865
test_callbacks.value
value
Definition: test_callbacks.py:158
LONGS_EQUAL
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:134
Z
@ Z
Definition: testDecisionTree.cpp:296
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
Crazy
Definition: testDecisionTree.cpp:45
Ring::mul
static int mul(const int &a, const int &b)
Definition: testDecisionTree.cpp:131
Crazy::b
double b
Definition: testDecisionTree.cpp:47


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:09:08