26 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 27 #include <boost/serialization/nvp.hpp> 48 template<
typename L,
typename Y>
62 using Unary = std::function<Y(const Y&)>;
64 using Binary = std::function<Y(const Y&, const Y&)>;
75 using Ptr = std::shared_ptr<const Node>;
77 #ifdef DT_DEBUG_MEMORY 83 #ifdef DT_DEBUG_MEMORY 84 std::cout << ++nrNodes <<
" constructed " <<
id() << std::endl;
91 #ifdef DT_DEBUG_MEMORY 92 std::cout << --nrNodes <<
" destructed " <<
id() << std::endl;
98 const void*
id()
const {
return this; }
101 virtual void print(
const std::string&
s,
106 bool showZero)
const = 0;
118 virtual Ptr choose(
const L& label,
size_t index)
const = 0;
119 virtual bool isLeaf()
const = 0;
122 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 124 friend class boost::serialization::access;
125 template <
class ARCHIVE>
126 void serialize(ARCHIVE& ar,
const unsigned int ) {}
142 template<
typename It,
typename ValueIt>
155 template <
typename M,
typename X>
157 std::function<
L(
const M&)> L_of_M,
158 std::function<
Y(
const X&)> Y_of_X)
const;
177 DecisionTree(
const std::vector<LabelC>& labelCs,
const std::vector<Y>& ys);
183 template<
typename Iterator>
197 template <
typename X,
typename Func>
210 template <
typename M,
typename X,
typename Func>
262 template <
typename Func>
263 void visit(Func f)
const;
279 template <
typename Func>
296 template <
typename Func>
317 template <
typename Func,
typename X>
321 std::set<L>
labels()
const;
352 return combine(labelC.first, labelC.second, op);
361 const ValueFormatter& valueFormatter,
bool showZero =
true)
const;
366 bool showZero =
true)
const;
375 template<
typename Iterator>
NodePtr 376 compose(Iterator begin, Iterator
end,
const L& label)
const;
381 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 383 friend class boost::serialization::access;
384 template <
class ARCHIVE>
385 void serialize(ARCHIVE& ar,
const unsigned int ) {
386 ar& BOOST_SERIALIZATION_NVP(root_);
391 template <
class L,
class Y>
396 template<
typename L,
typename Y>
404 template<
typename L,
typename Y>
411 template<
typename L,
typename Y>
415 return f.
apply(g, op);
424 template <
typename L,
typename T1,
typename T2>
virtual ~DecisionTree()=default
Make virtual.
NodePtr convertFrom(const typename DecisionTree< M, X >::NodePtr &f, std::function< L(const M &)> L_of_M, std::function< Y(const X &)> Y_of_X) const
Convert from a DecisionTree<M, X> to DecisionTree<L, Y>.
Matrix< RealScalar, Dynamic, Dynamic > M
Typedefs for easier changing of types.
std::function< double(const Assignment< Key > &, const double &)> UnaryAssignment
Concept check for values that can be used in unit tests.
void visit(Func f) const
Visit all leaves in depth-first fashion.
std::string serialize(const T &input)
serializes to a string
std::function< double(const double &, const double &)> Binary
An assignment from labels to a discrete value index (size_t)
virtual Ptr choose(const L &label, size_t index) const =0
virtual Ptr apply_g_op_fL(const Leaf &, const Binary &) const =0
std::function< double(const double &)> Unary
static std::string valueFormatter(const double &v)
std::set< L > labels() const
virtual bool isLeaf() const =0
void g(const string &key, int i)
NodePtr root_
A DecisionTree just contains the root. TODO(dellaert): make protected.
DecisionTree combine(const L &label, size_t cardinality, const Binary &op) const
virtual void dot(std::ostream &os, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter, bool showZero) const =0
virtual const Y & operator()(const Assignment< L > &x) const =0
void visitWith(Func f) const
Visit all leaves in depth-first fashion.
virtual bool sameLeaf(const Leaf &q) const =0
size_t nrLeaves() const
Return the number of leaves in the tree.
std::pair< DecisionTree< L, T1 >, DecisionTree< L, T2 > > unzip(const DecisionTree< L, std::pair< T1, T2 > > &input)
unzip a DecisionTree with std::pair values.
void visitLeaf(Func f) const
Visit all leaves in depth-first fashion.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
virtual void print(const std::string &s, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter) const =0
EIGEN_DEVICE_FUNC const Scalar & q
X fold(Func f, X x0) const
Fold a binary function over the tree, returning accumulator.
DecisionTree apply(const Unary &op) const
static sharedNode Leaf(Key key, const SymbolicFactorGraph &factors)
NodePtr create(It begin, It end, ValueIt beginY, ValueIt endY) const
typename Node::Ptr NodePtr
DecisionTree combine(const LabelC &labelC, const Binary &op) const
std::function< bool(const double &, const double &)> CompareFunc
std::shared_ptr< const Node > Ptr
std::function< std::string(Key)> LabelFormatter
bool empty() const
Check if tree is empty.
ofstream os("timeSchurFactors.csv")
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
virtual Ptr apply_g_op_fC(const Choice &, const Binary &) const =0
bool operator==(const DecisionTree &q) const
std::function< std::string(double)> ValueFormatter
static EIGEN_DEPRECATED const end_t end
Annotation for function names.
virtual bool equals(const Node &other, const CompareFunc &compare=&DefaultCompare) const =0
std::pair< Key, size_t > LabelC
virtual Ptr apply_f_op_g(const Node &, 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
NodePtr compose(Iterator begin, Iterator end, const L &label) const
virtual Ptr apply(const Unary &op) const =0
DecisionTree choose(const L &label, size_t index) const
static bool DefaultCompare(const Y &a, const Y &b)
Default method for comparison of two objects of type Y.