Go to the documentation of this file.
26 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
27 #include <boost/serialization/nvp.hpp>
61 template<
typename L,
typename Y>
77 using Binary = std::function<
Y(
const Y&,
const Y&)>;
88 using Ptr = std::shared_ptr<Node>;
90 #ifdef DT_DEBUG_MEMORY
96 #ifdef DT_DEBUG_MEMORY
97 std::cout << ++nrNodes <<
" constructed " <<
id() << std::endl;
104 #ifdef DT_DEBUG_MEMORY
105 std::cout << --nrNodes <<
" destructed " <<
id() << std::endl;
111 const void*
id()
const {
return this; }
114 virtual void print(
const std::string&
s,
119 bool showZero)
const = 0;
131 virtual Ptr choose(
const L& label,
size_t index)
const = 0;
132 virtual bool isLeaf()
const = 0;
135 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
137 friend class boost::serialization::access;
138 template <
class ARCHIVE>
139 void serialize(ARCHIVE& ar,
const unsigned int ) {}
156 template <
typename It,
typename ValueIt>
164 template <
typename It,
typename ValueIt>
176 template <
typename X>
178 std::function<
Y(
const X&)> Y_of_X);
190 template <
typename M,
typename X>
192 std::function<
L(
const M&)> L_of_M,
193 std::function<
Y(
const X&)> Y_of_X);
218 DecisionTree(
const std::vector<LabelC>& labelCs,
const std::vector<Y>& ys);
224 template<
typename Iterator>
247 template <
typename X,
typename Func>
260 template <
typename M,
typename X,
typename Func>
312 template <
typename Func>
329 template <
typename Func>
346 template <
typename Func>
367 template <
typename Func,
typename X>
371 std::set<L>
labels()
const;
402 return combine(labelC.first, labelC.second, op);
416 bool showZero =
true)
const;
426 template <
typename A,
typename B>
428 std::function<std::pair<A, B>(
const Y&)> AB_of_Y)
const;
437 template<
typename Iterator>
NodePtr
443 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
445 friend class boost::serialization::access;
446 template <
class ARCHIVE>
447 void serialize(ARCHIVE& ar,
const unsigned int ) {
448 ar& BOOST_SERIALIZATION_NVP(
root_);
453 template <
class L,
class Y>
458 template<
typename L,
typename Y>
466 template<
typename L,
typename Y>
473 template<
typename L,
typename Y>
477 return f.apply(
g, op);
486 template <
typename L,
typename T1,
typename T2>
std::function< std::string(Key)> LabelFormatter
Annotation for function names.
std::function< bool(const GaussianFactorGraphValuePair &, const GaussianFactorGraphValuePair &)> CompareFunc
static sharedNode Leaf(Key key, const SymbolicFactorGraph &factors)
std::pair< DecisionTree< L, A >, DecisionTree< L, B > > split(std::function< std::pair< A, B >(const Y &)> AB_of_Y) const
Convert into two trees with value types A and B.
Typedefs for easier changing of types.
Concept check for values that can be used in unit tests.
bool empty() const
Check if tree is empty.
GaussianFactorGraphValuePair Y
bool equals(const DecisionTree &other, const CompareFunc &compare=&DefaultCompare) const
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::function< std::string(GaussianFactorGraphValuePair)> ValueFormatter
std::set< L > labels() const
virtual const Y & operator()(const Assignment< L > &x) const =0
void print(const std::string &s, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter) const
GTSAM-style print.
static NodePtr build(It begin, It end, ValueIt beginY, ValueIt endY)
DecisionTree choose(const L &label, size_t index) const
ofstream os("timeSchurFactors.csv")
virtual bool equals(const Node &other, const CompareFunc &compare=&DefaultCompare) const =0
static bool DefaultCompare(const Y &a, const Y &b)
Default method for comparison of two objects of type Y.
virtual bool isLeaf() const =0
virtual Ptr apply_f_op_g(const Node &, const Binary &) const =0
DecisionTree combine(const LabelC &labelC, const Binary &op) const
std::function< GaussianFactorGraphValuePair(const GaussianFactorGraphValuePair &)> Unary
NodePtr root_
A DecisionTree just contains the root. TODO(dellaert): make protected.
virtual Ptr apply_g_op_fL(const Leaf &, const Binary &) const =0
static NodePtr compose(Iterator begin, Iterator end, const L &label)
EIGEN_DEVICE_FUNC const Scalar & q
virtual Ptr choose(const L &label, size_t index) const =0
std::function< GaussianFactorGraphValuePair(const GaussianFactorGraphValuePair &, const GaussianFactorGraphValuePair &)> Binary
An assignment from labels to a discrete value index (size_t)
void visit(Func f) const
Visit all leaves in depth-first fashion.
void dot(std::ostream &os, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter, bool showZero=true) const
void visitWith(Func f) const
Visit all leaves in depth-first fashion.
DecisionTree apply(const Unary &op) const
virtual void dot(std::ostream &os, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter, bool showZero) const =0
void g(const string &key, int i)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
a decision tree is a function from assignments to values.
static NodePtr create(It begin, It end, ValueIt beginY, ValueIt endY)
virtual bool sameLeaf(const Leaf &q) const =0
virtual ~DecisionTree()=default
Make virtual.
virtual Ptr apply(const Unary &op) const =0
bool operator==(const DecisionTree &q) const
std::function< GaussianFactorGraphValuePair(const Assignment< Key > &, const GaussianFactorGraphValuePair &)> UnaryAssignment
std::pair< Key, size_t > LabelC
DecisionTree< L, Y > apply(const DecisionTree< L, Y > &f, const typename DecisionTree< L, Y >::Unary &op)
Apply unary operator op to DecisionTree f.
size_t nrLeaves() const
Return the number of leaves in the tree.
typename Node::Ptr NodePtr
DecisionTree combine(const L &label, size_t cardinality, const Binary &op) const
static const EIGEN_DEPRECATED end_t end
std::pair< DecisionTree< L, T1 >, DecisionTree< L, T2 > > unzip(const DecisionTree< L, std::pair< T1, T2 > > &input)
unzip a DecisionTree with std::pair values.
static std::string valueFormatter(const double &v)
X fold(Func f, X x0) const
Fold a binary function over the tree, returning accumulator.
const Y & operator()(const Assignment< L > &x) const
static NodePtr convertFrom(const typename DecisionTree< L, X >::NodePtr &f, std::function< Y(const X &)> Y_of_X)
Convert from a DecisionTree<L, X> to DecisionTree<L, Y>.
virtual void print(const std::string &s, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter) const =0
void visitLeaf(Func f) const
Visit all leaves in depth-first fashion.
virtual Ptr apply_g_op_fC(const Choice &, const Binary &) const =0
Matrix< RealScalar, Dynamic, Dynamic > M
std::shared_ptr< Node > Ptr
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:10