DecisionTree.h
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 
20 #pragma once
21 
23 #include <boost/function.hpp>
24 #include <iostream>
25 #include <vector>
26 #include <map>
27 
28 namespace gtsam {
29 
35  template<typename L, typename Y>
36  class DecisionTree {
37 
38  public:
39 
41  typedef boost::function<Y(const Y&)> Unary;
42  typedef boost::function<Y(const Y&, const Y&)> Binary;
43 
45  typedef std::pair<L,size_t> LabelC;
46 
48  class Leaf;
49  class Choice;
50 
52  class Node {
53  public:
54  typedef boost::shared_ptr<const Node> Ptr;
55 
56 #ifdef DT_DEBUG_MEMORY
57  static int nrNodes;
58 #endif
59 
60  // Constructor
61  Node() {
62 #ifdef DT_DEBUG_MEMORY
63  std::cout << ++nrNodes << " constructed " << id() << std::endl; std::cout.flush();
64 #endif
65  }
66 
67  // Destructor
68  virtual ~Node() {
69 #ifdef DT_DEBUG_MEMORY
70  std::cout << --nrNodes << " destructed " << id() << std::endl; std::cout.flush();
71 #endif
72  }
73 
74  // Unique ID for dot files
75  const void* id() const { return this; }
76 
77  // everything else is virtual, no documentation here as internal
78  virtual void print(const std::string& s = "") const = 0;
79  virtual void dot(std::ostream& os, bool showZero) const = 0;
80  virtual bool sameLeaf(const Leaf& q) const = 0;
81  virtual bool sameLeaf(const Node& q) const = 0;
82  virtual bool equals(const Node& other, double tol = 1e-9) const = 0;
83  virtual const Y& operator()(const Assignment<L>& x) const = 0;
84  virtual Ptr apply(const Unary& op) const = 0;
85  virtual Ptr apply_f_op_g(const Node&, const Binary&) const = 0;
86  virtual Ptr apply_g_op_fL(const Leaf&, const Binary&) const = 0;
87  virtual Ptr apply_g_op_fC(const Choice&, const Binary&) const = 0;
88  virtual Ptr choose(const L& label, size_t index) const = 0;
89  virtual bool isLeaf() const = 0;
90  };
93  public:
94 
96  typedef typename Node::Ptr NodePtr;
97 
98  /* a DecisionTree just contains the root */
99  NodePtr root_;
100 
101  protected:
102 
104  template<typename It, typename ValueIt>
105  NodePtr create(It begin, It end, ValueIt beginY, ValueIt endY) const;
106 
108  template<typename M, typename X> NodePtr
109  convert(const typename DecisionTree<M, X>::NodePtr& f, const std::map<M,
110  L>& map, boost::function<Y(const X&)> op);
111 
113  DecisionTree();
114 
115  public:
116 
119 
121  DecisionTree(const Y& y);
122 
124  DecisionTree(const L& label, const Y& y1, const Y& y2);
125 
127  DecisionTree(const LabelC& label, const Y& y1, const Y& y2);
128 
130  DecisionTree(const std::vector<LabelC>& labelCs, const std::vector<Y>& ys);
131 
133  DecisionTree(const std::vector<LabelC>& labelCs, const std::string& table);
134 
136  template<typename Iterator>
137  DecisionTree(Iterator begin, Iterator end, const L& label);
138 
140  DecisionTree(const L& label, //
141  const DecisionTree& f0, const DecisionTree& f1);
142 
144  template<typename M, typename X>
145  DecisionTree(const DecisionTree<M, X>& other,
146  const std::map<M, L>& map, boost::function<Y(const X&)> op);
147 
151 
153  void print(const std::string& s = "DecisionTree") const;
154 
155  // Testable
156  bool equals(const DecisionTree& other, double tol = 1e-9) const;
157 
161 
163  virtual ~DecisionTree() {
164  }
165 
167  bool operator==(const DecisionTree& q) const;
168 
170  const Y& operator()(const Assignment<L>& x) const;
171 
173  DecisionTree apply(const Unary& op) const;
174 
176  DecisionTree apply(const DecisionTree& g, const Binary& op) const;
177 
180  DecisionTree choose(const L& label, size_t index) const {
181  NodePtr newRoot = root_->choose(label, index);
182  return DecisionTree(newRoot);
183  }
184 
186  DecisionTree combine(const L& label, size_t cardinality, const Binary& op) const;
187 
189  DecisionTree combine(const LabelC& labelC, const Binary& op) const {
190  return combine(labelC.first, labelC.second, op);
191  }
192 
194  void dot(std::ostream& os, bool showZero = true) const;
195 
197  void dot(const std::string& name, bool showZero = true) const;
198 
201 
202  // internal use only
203  DecisionTree(const NodePtr& root);
204 
205  // internal use only
206  template<typename Iterator> NodePtr
207  compose(Iterator begin, Iterator end, const L& label) const;
208 
210 
211  }; // DecisionTree
212 
215  template<typename Y, typename L>
217  const typename DecisionTree<L, Y>::Unary& op) {
218  return f.apply(op);
219  }
220 
221  template<typename Y, typename L>
223  const DecisionTree<L, Y>& g,
224  const typename DecisionTree<L, Y>::Binary& op) {
225  return f.apply(g, op);
226  }
227 
228 } // namespace gtsam
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:38
Scalar * y
virtual void print(const std::string &s="") const =0
virtual bool isLeaf() const =0
virtual bool equals(const Node &other, double tol=1e-9) const =0
An assignment from labels to a discrete value index (size_t)
DecisionTree apply(const Unary &op) const
virtual Ptr choose(const L &label, size_t index) const =0
boost::function< Y(const Y &, const Y &)> Binary
Definition: DecisionTree.h:42
MatrixXd L
Definition: LLT_example.cpp:6
virtual Ptr apply_g_op_fL(const Leaf &, const Binary &) const =0
DecisionTree choose(const L &label, size_t index) const
Definition: DecisionTree.h:180
virtual ~DecisionTree()
Definition: DecisionTree.h:163
const mpreal root(const mpreal &x, unsigned long int k, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2194
virtual void dot(std::ostream &os, bool showZero) const =0
void g(const string &key, int i)
Definition: testBTree.cpp:43
virtual Ptr apply(const Unary &op) const =0
virtual const Y & operator()(const Assignment< L > &x) const =0
DecisionTree combine(const L &label, size_t cardinality, const Binary &op) const
boost::shared_ptr< const Node > Ptr
Definition: DecisionTree.h:54
boost::function< Y(const Y &)> Unary
Definition: DecisionTree.h:41
NodePtr compose(Iterator begin, Iterator end, const L &label) const
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
EIGEN_DEVICE_FUNC const Scalar & q
string::const_iterator It
Definition: Signature.cpp:35
traits
Definition: chartTesting.h:28
NodePtr create(It begin, It end, ValueIt beginY, ValueIt endY) const
ofstream os("timeSchurFactors.csv")
ArrayXXf table(10, 4)
virtual Ptr apply_f_op_g(const Node &, const Binary &) const =0
bool operator==(const DecisionTree &q) const
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
NodePtr convert(const typename DecisionTree< M, X >::NodePtr &f, const std::map< M, L > &map, boost::function< Y(const X &)> op)
virtual bool sameLeaf(const Leaf &q) const =0
Annotation for function names.
Definition: attr.h:36
const G double tol
Definition: Group.h:83
#define X
Definition: icosphere.cpp:20
virtual Ptr apply_g_op_fC(const Choice &, const Binary &) const =0
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
std::pair< L, size_t > LabelC
Definition: DecisionTree.h:45
DecisionTree combine(const LabelC &labelC, const Binary &op) const
Definition: DecisionTree.h:189
const void * id() const
Definition: DecisionTree.h:75


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:57