DecisionTree-inl.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 
24 #include <algorithm>
25 #include <cassert>
26 #include <fstream>
27 #include <iterator>
28 #include <map>
29 #include <optional>
30 #include <set>
31 #include <sstream>
32 #include <stdexcept>
33 #include <string>
34 #include <vector>
35 
36 namespace gtsam {
37 
38  /****************************************************************************/
39  // Node
40  /****************************************************************************/
41 #ifdef DT_DEBUG_MEMORY
42  template<typename L, typename Y>
43  int DecisionTree<L, Y>::Node::nrNodes = 0;
44 #endif
45 
46  /****************************************************************************/
47  // Leaf
48  /****************************************************************************/
49  template <typename L, typename Y>
50  struct DecisionTree<L, Y>::Leaf : public DecisionTree<L, Y>::Node {
53 
55  Leaf() {}
56 
58  Leaf(const Y& constant) : constant_(constant) {}
59 
61  const Y& constant() const {
62  return constant_;
63  }
64 
66  bool sameLeaf(const Leaf& q) const override {
67  return constant_ == q.constant_;
68  }
69 
71  bool sameLeaf(const Node& q) const override {
72  return (q.isLeaf() && q.sameLeaf(*this));
73  }
74 
76  bool equals(const Node& q, const CompareFunc& compare) const override {
77  const Leaf* other = dynamic_cast<const Leaf*>(&q);
78  if (!other) return false;
79  return compare(this->constant_, other->constant_);
80  }
81 
83  void print(const std::string& s, const LabelFormatter& labelFormatter,
84  const ValueFormatter& valueFormatter) const override {
85  std::cout << s << " Leaf " << valueFormatter(constant_) << std::endl;
86  }
87 
89  void dot(std::ostream& os, const LabelFormatter& labelFormatter,
91  bool showZero) const override {
92  const std::string value = valueFormatter(constant_);
93  if (showZero || value.compare("0"))
94  os << "\"" << this->id() << "\" [label=\"" << value
95  << "\", shape=box, rank=sink, height=0.35, fixedsize=true]\n";
96  }
97 
99  const Y& operator()(const Assignment<L>& x) const override {
100  return constant_;
101  }
102 
104  NodePtr apply(const Unary& op) const override {
105  NodePtr f(new Leaf(op(constant_)));
106  return f;
107  }
108 
111  const Assignment<L>& assignment) const override {
112  NodePtr f(new Leaf(op(assignment, constant_)));
113  return f;
114  }
115 
116  // Apply binary operator "h = f op g" on Leaf node
117  // Note op is not assumed commutative so we need to keep track of order
118  // Simply calls apply on argument to call correct virtual method:
119  // fL.apply_f_op_g(gL) -> gL.apply_g_op_fL(fL) (below)
120  // fL.apply_f_op_g(gC) -> gC.apply_g_op_fL(fL) (Choice)
121  NodePtr apply_f_op_g(const Node& g, const Binary& op) const override {
122  return g.apply_g_op_fL(*this, op);
123  }
124 
125  // Applying binary operator to two leaves results in a leaf
126  NodePtr apply_g_op_fL(const Leaf& fL, const Binary& op) const override {
127  // fL op gL
128  NodePtr h(new Leaf(op(fL.constant_, constant_)));
129  return h;
130  }
131 
132  // If second argument is a Choice node, call it's apply with leaf as second
133  NodePtr apply_g_op_fC(const Choice& fC, const Binary& op) const override {
134  return fC.apply_fC_op_gL(*this, op); // operand order back to normal
135  }
136 
138  NodePtr choose(const L& label, size_t index) const override {
139  return NodePtr(new Leaf(constant()));
140  }
141 
142  bool isLeaf() const override { return true; }
143 
144  private:
146 
147 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
148 
149  friend class boost::serialization::access;
150  template <class ARCHIVE>
151  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
152  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
153  ar& BOOST_SERIALIZATION_NVP(constant_);
154  }
155 #endif
156  }; // Leaf
157 
158  /****************************************************************************/
159  // Choice
160  /****************************************************************************/
161  template<typename L, typename Y>
162  struct DecisionTree<L, Y>::Choice: public DecisionTree<L, Y>::Node {
165 
167  std::vector<NodePtr> branches_;
168 
169  private:
174  size_t allSame_;
175 
176  using ChoicePtr = std::shared_ptr<const Choice>;
177 
178  public:
180  Choice() {}
181 
182  ~Choice() override {
183 #ifdef DT_DEBUG_MEMORY
184  std::cout << Node::nrNodes << " destructing (Choice) " << this->id()
185  << std::endl;
186 #endif
187  }
188 
205  static NodePtr Unique(const NodePtr& node) {
206  if (auto choice = std::dynamic_pointer_cast<const Choice>(node)) {
207  // Choice node, we recurse!
208  // Make non-const copy so we can update
209  auto f = std::make_shared<Choice>(choice->label(), choice->nrChoices());
210 
211  // Iterate over all the branches
212  for (size_t i = 0; i < choice->nrChoices(); i++) {
213  auto branch = choice->branches_[i];
214  f->push_back(Unique(branch));
215  }
216 
217 #ifdef GTSAM_DT_MERGING
218  // If all the branches are the same, we can merge them into one
219  if (f->allSame_) {
220  assert(f->branches().size() > 0);
221  NodePtr f0 = f->branches_[0];
222 
223  NodePtr newLeaf(
224  new Leaf(std::dynamic_pointer_cast<const Leaf>(f0)->constant()));
225  return newLeaf;
226  }
227 #endif
228  return f;
229  } else {
230  // Leaf node, return as is
231  return node;
232  }
233  }
234 
235  bool isLeaf() const override { return false; }
236 
238  Choice(const L& label, size_t count) :
239  label_(label), allSame_(true) {
240  branches_.reserve(count);
241  }
242 
244  Choice(const Choice& f, const Choice& g, const Binary& op) :
245  allSame_(true) {
246  // Choose what to do based on label
247  if (f.label() > g.label()) {
248  // f higher than g
249  label_ = f.label();
250  size_t count = f.nrChoices();
251  branches_.reserve(count);
252  for (size_t i = 0; i < count; i++) {
253  NodePtr newBranch = f.branches_[i]->apply_f_op_g(g, op);
254  push_back(std::move(newBranch));
255  }
256  } else if (g.label() > f.label()) {
257  // f lower than g
258  label_ = g.label();
259  size_t count = g.nrChoices();
260  branches_.reserve(count);
261  for (size_t i = 0; i < count; i++) {
262  NodePtr newBranch = g.branches_[i]->apply_g_op_fC(f, op);
263  push_back(std::move(newBranch));
264  }
265  } else {
266  // f same level as g
267  label_ = f.label();
268  size_t count = f.nrChoices();
269  branches_.reserve(count);
270  for (size_t i = 0; i < count; i++) {
271  NodePtr newBranch = f.branches_[i]->apply_f_op_g(*g.branches_[i], op);
272  push_back(std::move(newBranch));
273  }
274  }
275  }
276 
278  const L& label() const {
279  return label_;
280  }
281 
282  size_t nrChoices() const {
283  return branches_.size();
284  }
285 
286  const std::vector<NodePtr>& branches() const {
287  return branches_;
288  }
289 
290  std::vector<NodePtr>& branches() {
291  return branches_;
292  }
293 
295  void push_back(NodePtr&& node) {
296  // allSame_ is restricted to leaf nodes in a decision tree
297  if (allSame_ && !branches_.empty()) {
298  allSame_ = node->sameLeaf(*branches_.back());
299  }
300  branches_.push_back(std::move(node));
301  }
302 
304  void print(const std::string& s, const LabelFormatter& labelFormatter,
305  const ValueFormatter& valueFormatter) const override {
306  std::cout << s << " Choice(";
307  std::cout << labelFormatter(label_) << ") " << std::endl;
308  for (size_t i = 0; i < branches_.size(); i++) {
309  branches_[i]->print(s + " " + std::to_string(i), labelFormatter, valueFormatter);
310  }
311  }
312 
314  void dot(std::ostream& os, const LabelFormatter& labelFormatter,
316  bool showZero) const override {
317  const std::string label = labelFormatter(label_);
318  os << "\"" << this->id() << "\" [shape=circle, label=\"" << label
319  << "\"]\n";
320  size_t B = branches_.size();
321  for (size_t i = 0; i < B; i++) {
322  const NodePtr& branch = branches_[i];
323 
324  // Check if zero
325  if (!showZero) {
326  const Leaf* leaf = dynamic_cast<const Leaf*>(branch.get());
327  if (leaf && valueFormatter(leaf->constant()).compare("0")) continue;
328  }
329 
330  os << "\"" << this->id() << "\" -> \"" << branch->id() << "\"";
331  if (B == 2 && i == 0) os << " [style=dashed]";
332  os << std::endl;
333  branch->dot(os, labelFormatter, valueFormatter, showZero);
334  }
335  }
336 
338  bool sameLeaf(const Leaf& q) const override {
339  return false;
340  }
341 
343  bool sameLeaf(const Node& q) const override {
344  return (q.isLeaf() && q.sameLeaf(*this));
345  }
346 
348  bool equals(const Node& q, const CompareFunc& compare) const override {
349  const Choice* other = dynamic_cast<const Choice*>(&q);
350  if (!other) return false;
351  if (this->label_ != other->label_) return false;
352  if (branches_.size() != other->branches_.size()) return false;
353  // we don't care about shared pointers being equal here
354  for (size_t i = 0; i < branches_.size(); i++)
355  if (!(branches_[i]->equals(*(other->branches_[i]), compare)))
356  return false;
357  return true;
358  }
359 
361  const Y& operator()(const Assignment<L>& x) const override {
362 #ifndef NDEBUG
363  typename Assignment<L>::const_iterator it = x.find(label_);
364  if (it == x.end()) {
365  std::cout << "Trying to find value for " << label_ << std::endl;
366  throw std::invalid_argument(
367  "DecisionTree::operator(): value undefined for a label");
368  }
369 #endif
370  size_t index = x.at(label_);
371  NodePtr child = branches_[index];
372  return (*child)(x);
373  }
374 
376  Choice(const L& label, const Choice& f, const Unary& op) :
377  label_(label), allSame_(true) {
378  branches_.reserve(f.branches_.size()); // reserve space
379  for (const NodePtr& branch : f.branches_) {
380  push_back(branch->apply(op));
381  }
382  }
383 
394  Choice(const L& label, const Choice& f, const UnaryAssignment& op,
395  const Assignment<L>& assignment)
396  : label_(label), allSame_(true) {
397  branches_.reserve(f.branches_.size()); // reserve space
398 
399  Assignment<L> assignment_ = assignment;
400 
401  for (size_t i = 0; i < f.branches_.size(); i++) {
402  assignment_[label_] = i; // Set assignment for label to i
403 
404  const NodePtr branch = f.branches_[i];
405  push_back(branch->apply(op, assignment_));
406 
407  // Remove the assignment so we are backtracking
408  auto assignment_it = assignment_.find(label_);
409  assignment_.erase(assignment_it);
410  }
411  }
412 
414  NodePtr apply(const Unary& op) const override {
415  auto r = std::make_shared<Choice>(label_, *this, op);
416  return Unique(r);
417  }
418 
421  const Assignment<L>& assignment) const override {
422  auto r = std::make_shared<Choice>(label_, *this, op, assignment);
423  return Unique(r);
424  }
425 
426  // Apply binary operator "h = f op g" on Choice node
427  // Note op is not assumed commutative so we need to keep track of order
428  // Simply calls apply on argument to call correct virtual method:
429  // fC.apply_f_op_g(gL) -> gL.apply_g_op_fC(fC) -> (Leaf)
430  // fC.apply_f_op_g(gC) -> gC.apply_g_op_fC(fC) -> (below)
431  NodePtr apply_f_op_g(const Node& g, const Binary& op) const override {
432  return g.apply_g_op_fC(*this, op);
433  }
434 
435  // If second argument of binary op is Leaf node, recurse on branches
436  NodePtr apply_g_op_fL(const Leaf& fL, const Binary& op) const override {
437  auto h = std::make_shared<Choice>(label(), nrChoices());
438  for (auto&& branch : branches_)
439  h->push_back(fL.apply_f_op_g(*branch, op));
440  return Unique(h);
441  }
442 
443  // If second argument of binary op is Choice, call constructor
444  NodePtr apply_g_op_fC(const Choice& fC, const Binary& op) const override {
445  auto h = std::make_shared<Choice>(fC, *this, op);
446  return Unique(h);
447  }
448 
449  // If second argument of binary op is Leaf
450  template<typename OP>
451  NodePtr apply_fC_op_gL(const Leaf& gL, OP op) const {
452  auto h = std::make_shared<Choice>(label(), nrChoices());
453  for (auto&& branch : branches_)
454  h->push_back(branch->apply_f_op_g(gL, op));
455  return Unique(h);
456  }
457 
459  NodePtr choose(const L& label, size_t index) const override {
460  if (label_ == label) return branches_[index]; // choose branch
461 
462  // second case, not label of interest, just recurse
463  auto r = std::make_shared<Choice>(label_, branches_.size());
464  for (auto&& branch : branches_) {
465  r->push_back(branch->choose(label, index));
466  }
467 
468  return Unique(r);
469  }
470 
471  private:
473 
474 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
475 
476  friend class boost::serialization::access;
477  template <class ARCHIVE>
478  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
479  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
480  ar& BOOST_SERIALIZATION_NVP(label_);
481  ar& BOOST_SERIALIZATION_NVP(branches_);
482  ar& BOOST_SERIALIZATION_NVP(allSame_);
483  }
484 #endif
485  }; // Choice
486 
487  /****************************************************************************/
488  // DecisionTree
489  /****************************************************************************/
490  template <typename L, typename Y>
491  DecisionTree<L, Y>::DecisionTree() : root_(nullptr) {}
492 
493  template<typename L, typename Y>
495  root_(root) {}
496 
497  /****************************************************************************/
498  template<typename L, typename Y>
500  root_ = NodePtr(new Leaf(y));
501  }
502 
503  /****************************************************************************/
504  template <typename L, typename Y>
505  DecisionTree<L, Y>::DecisionTree(const L& label, const Y& y1, const Y& y2) {
506  auto a = std::make_shared<Choice>(label, 2);
507  NodePtr l1(new Leaf(y1)), l2(new Leaf(y2));
508  a->push_back(std::move(l1));
509  a->push_back(std::move(l2));
510  root_ = Choice::Unique(std::move(a));
511  }
512 
513  /****************************************************************************/
514  template <typename L, typename Y>
516  const Y& y2) {
517  if (labelC.second != 2) throw std::invalid_argument(
518  "DecisionTree: binary constructor called with non-binary label");
519  auto a = std::make_shared<Choice>(labelC.first, 2);
520  NodePtr l1(new Leaf(y1)), l2(new Leaf(y2));
521  a->push_back(std::move(l1));
522  a->push_back(std::move(l2));
523  root_ = Choice::Unique(std::move(a));
524  }
525  /****************************************************************************/
526  template<typename L, typename Y>
527  DecisionTree<L, Y>::DecisionTree(const std::vector<LabelC>& labelCs,
528  const std::vector<Y>& ys) {
529  // call recursive Create
530  root_ = create(labelCs.begin(), labelCs.end(), ys.begin(), ys.end());
531  }
532 
533  /****************************************************************************/
534  template<typename L, typename Y>
535  DecisionTree<L, Y>::DecisionTree(const std::vector<LabelC>& labelCs,
536  const std::string& table) {
537  // Convert std::string to values of type Y
538  std::vector<Y> ys;
539  std::istringstream iss(table);
540  copy(std::istream_iterator<Y>(iss), std::istream_iterator<Y>(),
541  back_inserter(ys));
542 
543  // now call recursive Create
544  root_ = create(labelCs.begin(), labelCs.end(), ys.begin(), ys.end());
545  }
546 
547  /****************************************************************************/
548  template<typename L, typename Y>
549  template<typename Iterator> DecisionTree<L, Y>::DecisionTree(
550  Iterator begin, Iterator end, const L& label) {
551  root_ = compose(begin, end, label);
552  }
553 
554  /****************************************************************************/
555  template<typename L, typename Y>
557  const DecisionTree& f0, const DecisionTree& f1) {
558  const std::vector<DecisionTree> functions{f0, f1};
559  root_ = compose(functions.begin(), functions.end(), label);
560  }
561 
562  /****************************************************************************/
563  template <typename L, typename Y>
565  DecisionTree&& other) noexcept
566  : root_(std::move(other.root_)) {
567  // Apply the unary operation directly to each leaf in the tree
568  if (root_) {
569  // Define a helper function to traverse and apply the operation
570  struct ApplyUnary {
571  const Unary& op;
572  void operator()(typename DecisionTree<L, Y>::NodePtr& node) const {
573  if (auto leaf = std::dynamic_pointer_cast<Leaf>(node)) {
574  // Apply the unary operation to the leaf's constant value
575  leaf->constant_ = op(leaf->constant_);
576  } else if (auto choice = std::dynamic_pointer_cast<Choice>(node)) {
577  // Recurse into the choice branches
578  for (NodePtr& branch : choice->branches()) {
579  (*this)(branch);
580  }
581  }
582  }
583  };
584 
585  ApplyUnary applyUnary{op};
586  applyUnary(root_);
587  }
588  // Reset the other tree's root to nullptr to avoid dangling references
589  other.root_ = nullptr;
590  }
591 
592  /****************************************************************************/
593  template <typename L, typename Y>
594  template <typename X, typename Func>
596  Func Y_of_X) {
597  root_ = convertFrom<X>(other.root_, Y_of_X);
598  }
599 
600  /****************************************************************************/
601  template <typename L, typename Y>
602  template <typename M, typename X, typename Func>
604  const std::map<M, L>& map, Func Y_of_X) {
605  auto L_of_M = [&map](const M& label) -> L { return map.at(label); };
606  root_ = convertFrom<M, X>(other.root_, L_of_M, Y_of_X);
607  }
608 
609  /****************************************************************************/
610  // Called by two constructors above.
611  // Takes a label and a corresponding range of decision trees, and creates a
612  // new decision tree. However, the order of the labels needs to be respected,
613  // so we cannot just create a root Choice node on the label: if the label is
614  // not the highest label, we need a complicated/ expensive recursive call.
615  template <typename L, typename Y>
616  template <typename Iterator>
618  Iterator begin, Iterator end, const L& label) {
619  // find highest label among branches
620  std::optional<L> highestLabel;
621  size_t nrChoices = 0;
622  for (Iterator it = begin; it != end; it++) {
623  if (it->root_->isLeaf())
624  continue;
625  std::shared_ptr<const Choice> c =
626  std::dynamic_pointer_cast<const Choice>(it->root_);
627  if (!highestLabel || c->label() > *highestLabel) {
628  highestLabel = c->label();
629  nrChoices = c->nrChoices();
630  }
631  }
632 
633  // if label is already in correct order, just put together a choice on label
634  if (!nrChoices || !highestLabel || label > *highestLabel) {
635  auto choiceOnLabel = std::make_shared<Choice>(label, end - begin);
636  for (Iterator it = begin; it != end; it++) {
637  NodePtr root = it->root_;
638  choiceOnLabel->push_back(std::move(root));
639  }
640  // If no reordering, no need to call Choice::Unique
641  return choiceOnLabel;
642  } else {
643  // Set up a new choice on the highest label
644  auto choiceOnHighestLabel =
645  std::make_shared<Choice>(*highestLabel, nrChoices);
646  // now, for all possible values of highestLabel
647  for (size_t index = 0; index < nrChoices; index++) {
648  // make a new set of functions for composing by iterating over the given
649  // functions, and selecting the appropriate branch.
650  std::vector<DecisionTree> functions;
651  for (Iterator it = begin; it != end; it++) {
652  // by restricting the input functions to value i for labelBelow
653  DecisionTree chosen = it->choose(*highestLabel, index);
654  functions.push_back(chosen);
655  }
656  // We then recurse, for all values of the highest label
657  NodePtr fi = compose(functions.begin(), functions.end(), label);
658  choiceOnHighestLabel->push_back(std::move(fi));
659  }
660  return choiceOnHighestLabel;
661  }
662  }
663 
664  /****************************************************************************/
665  // "build" is a bit of a complicated thing, but very useful.
666  // It takes a range of labels and a corresponding range of values,
667  // and builds a decision tree, as follows:
668  // - if there is only one label, creates a choice node with values in leaves
669  // - otherwise, it evenly splits up the range of values and creates a tree for
670  // each sub-range, and assigns that tree to first label's choices
671  // Example:
672  // build([B A],[1 2 3 4]) would call
673  // build([A],[1 2])
674  // build([A],[3 4])
675  // and produce
676  // B=0
677  // A=0: 1
678  // A=1: 2
679  // B=1
680  // A=0: 3
681  // A=1: 4
682  // Note, through the magic of "compose", create([A B],[1 3 2 4]) will produce
683  // exactly the same tree as above: the highest label is always the root.
684  // However, it will be *way* faster if labels are given highest to lowest.
685  template<typename L, typename Y>
686  template<typename It, typename ValueIt>
688  It begin, It end, ValueIt beginY, ValueIt endY) {
689  // get crucial counts
690  size_t nrChoices = begin->second;
691  size_t size = endY - beginY;
692 
693  // Find the next key to work on
694  It labelC = begin + 1;
695  if (labelC == end) {
696  // Base case: only one key left
697  // Create a simple choice node with values as leaves.
698  if (size != nrChoices) {
699  std::cout << "Trying to create DD on " << begin->first << std::endl;
700  std::cout << "DecisionTree::create: expected " << nrChoices
701  << " values but got " << size << " instead" << std::endl;
702  throw std::invalid_argument("DecisionTree::create invalid argument");
703  }
704  auto choice = std::make_shared<Choice>(begin->first, endY - beginY);
705  for (ValueIt y = beginY; y != endY; y++) {
706  choice->push_back(NodePtr(new Leaf(*y)));
707  }
708  return choice;
709  }
710 
711  // Recursive case: perform "Shannon expansion"
712  // Creates one tree (i.e.,function) for each choice of current key
713  // by calling create recursively, and then puts them all together.
714  std::vector<DecisionTree> functions;
715  functions.reserve(nrChoices);
716  size_t split = size / nrChoices;
717  for (size_t i = 0; i < nrChoices; i++, beginY += split) {
718  NodePtr f = build<It, ValueIt>(labelC, end, beginY, beginY + split);
719  functions.emplace_back(f);
720  }
721  return compose(functions.begin(), functions.end(), begin->first);
722  }
723 
724  /****************************************************************************/
725  // Top-level factory method, which takes a range of labels and a corresponding
726  // range of values, and creates a decision tree.
727  template<typename L, typename Y>
728  template<typename It, typename ValueIt>
730  It begin, It end, ValueIt beginY, ValueIt endY) {
731  auto node = build(begin, end, beginY, endY);
732  if (auto choice = std::dynamic_pointer_cast<Choice>(node)) {
733  return Choice::Unique(choice);
734  } else {
735  return node;
736  }
737  }
738 
739  /****************************************************************************/
740  template <typename L, typename Y>
741  template <typename X>
743  const typename DecisionTree<L, X>::NodePtr& f,
744  std::function<Y(const X&)> Y_of_X) {
745 
746  // If leaf, apply unary conversion "op" and create a unique leaf.
747  using LXLeaf = typename DecisionTree<L, X>::Leaf;
748  if (auto leaf = std::dynamic_pointer_cast<LXLeaf>(f)) {
749  return NodePtr(new Leaf(Y_of_X(leaf->constant())));
750  }
751 
752  // Check if Choice
753  using LXChoice = typename DecisionTree<L, X>::Choice;
754  auto choice = std::dynamic_pointer_cast<const LXChoice>(f);
755  if (!choice) throw std::invalid_argument(
756  "DecisionTree::convertFrom: Invalid NodePtr");
757 
758  // Create a new Choice node with the same label
759  auto newChoice = std::make_shared<Choice>(choice->label(), choice->nrChoices());
760 
761  // Convert each branch recursively
762  for (auto&& branch : choice->branches()) {
763  newChoice->push_back(convertFrom<X>(branch, Y_of_X));
764  }
765 
766  return Choice::Unique(newChoice);
767  }
768 
769  /****************************************************************************/
770  template <typename L, typename Y>
771  template <typename M, typename X>
773  const typename DecisionTree<M, X>::NodePtr& f,
774  std::function<L(const M&)> L_of_M, std::function<Y(const X&)> Y_of_X) {
775  using LY = DecisionTree<L, Y>;
776 
777  // If leaf, apply unary conversion "op" and create a unique leaf.
778  using MXLeaf = typename DecisionTree<M, X>::Leaf;
779  if (auto leaf = std::dynamic_pointer_cast<const MXLeaf>(f)) {
780  return NodePtr(new Leaf(Y_of_X(leaf->constant())));
781  }
782 
783  // Check if Choice
784  using MXChoice = typename DecisionTree<M, X>::Choice;
785  auto choice = std::dynamic_pointer_cast<const MXChoice>(f);
786  if (!choice)
787  throw std::invalid_argument("DecisionTree::convertFrom: Invalid NodePtr");
788 
789  // get new label
790  const M oldLabel = choice->label();
791  const L newLabel = L_of_M(oldLabel);
792 
793  // Shannon expansion in this context involves:
794  // 1. Creating separate subtrees (functions) for each possible value of the new label.
795  // 2. Combining these subtrees using the 'compose' method, which implements the expansion.
796  // This approach guarantees that the resulting tree maintains the correct variable ordering
797  // based on the new labels (L) after translation from the old labels (M).
798  // Simply creating a Choice node here would not work because it wouldn't account for the
799  // potentially new ordering of variables resulting from the label translation,
800  // which is crucial for maintaining consistency and efficiency in the converted tree.
801  std::vector<LY> functions;
802  for (auto&& branch : choice->branches()) {
803  functions.emplace_back(convertFrom<M, X>(branch, L_of_M, Y_of_X));
804  }
805  return Choice::Unique(
806  LY::compose(functions.begin(), functions.end(), newLabel));
807  }
808 
809  /****************************************************************************/
820  template <typename L, typename Y>
821  struct Visit {
822  using F = std::function<void(const Y&)>;
823  explicit Visit(F f) : f(f) {}
824  F f;
825 
827  void operator()(const typename DecisionTree<L, Y>::NodePtr& node) const {
828  using Leaf = typename DecisionTree<L, Y>::Leaf;
829  if (auto leaf = std::dynamic_pointer_cast<const Leaf>(node))
830  return f(leaf->constant());
831 
832  using Choice = typename DecisionTree<L, Y>::Choice;
833  auto choice = std::dynamic_pointer_cast<const Choice>(node);
834  if (!choice)
835  throw std::invalid_argument("DecisionTree::Visit: Invalid NodePtr");
836  for (auto&& branch : choice->branches()) (*this)(branch); // recurse!
837  }
838  };
839 
840  template <typename L, typename Y>
841  template <typename Func>
842  void DecisionTree<L, Y>::visit(Func f) const {
843  Visit<L, Y> visit(f);
844  visit(root_);
845  }
846 
847  /****************************************************************************/
857  template <typename L, typename Y>
858  struct VisitLeaf {
859  using F = std::function<void(const typename DecisionTree<L, Y>::Leaf&)>;
860  explicit VisitLeaf(F f) : f(f) {}
861  F f;
862 
864  void operator()(const typename DecisionTree<L, Y>::NodePtr& node) const {
865  using Leaf = typename DecisionTree<L, Y>::Leaf;
866  if (auto leaf = std::dynamic_pointer_cast<const Leaf>(node))
867  return f(*leaf);
868 
869  using Choice = typename DecisionTree<L, Y>::Choice;
870  auto choice = std::dynamic_pointer_cast<const Choice>(node);
871  if (!choice)
872  throw std::invalid_argument("DecisionTree::VisitLeaf: Invalid NodePtr");
873  for (auto&& branch : choice->branches()) (*this)(branch); // recurse!
874  }
875  };
876 
877  template <typename L, typename Y>
878  template <typename Func>
879  void DecisionTree<L, Y>::visitLeaf(Func f) const {
880  VisitLeaf<L, Y> visit(f);
881  visit(root_);
882  }
883 
884  /****************************************************************************/
891  template <typename L, typename Y>
892  struct VisitWith {
893  using F = std::function<void(const Assignment<L>&, const Y&)>;
894  explicit VisitWith(F f) : f(f) {}
896  F f;
897 
899  void operator()(const typename DecisionTree<L, Y>::NodePtr& node) {
900  using Leaf = typename DecisionTree<L, Y>::Leaf;
901  if (auto leaf = std::dynamic_pointer_cast<const Leaf>(node))
902  return f(assignment, leaf->constant());
903 
904  using Choice = typename DecisionTree<L, Y>::Choice;
905  auto choice = std::dynamic_pointer_cast<const Choice>(node);
906  if (!choice)
907  throw std::invalid_argument("DecisionTree::VisitWith: Invalid NodePtr");
908  for (size_t i = 0; i < choice->nrChoices(); i++) {
909  assignment[choice->label()] = i; // Set assignment for label to i
910 
911  (*this)(choice->branches()[i]); // recurse!
912 
913  // Remove the choice so we are backtracking
914  auto choice_it = assignment.find(choice->label());
915  assignment.erase(choice_it);
916  }
917  }
918  };
919 
920  template <typename L, typename Y>
921  template <typename Func>
922  void DecisionTree<L, Y>::visitWith(Func f) const {
923  VisitWith<L, Y> visit(f);
924  visit(root_);
925  }
926 
927  /****************************************************************************/
928  template <typename L, typename Y>
930  size_t total = 0;
931  visit([&total](const Y& node) { total += 1; });
932  return total;
933  }
934 
935  /****************************************************************************/
936  // fold is just done with a visit
937  template <typename L, typename Y>
938  template <typename Func, typename X>
939  X DecisionTree<L, Y>::fold(Func f, X x0) const {
940  visit([&](const Y& y) { x0 = f(y, x0); });
941  return x0;
942  }
943 
944  /****************************************************************************/
958  template <typename L, typename Y>
959  std::set<L> DecisionTree<L, Y>::labels() const {
960  std::set<L> unique;
961  auto f = [&](const Assignment<L>& assignment, const Y&) {
962  for (auto&& kv : assignment) {
963  unique.insert(kv.first);
964  }
965  };
966  visitWith(f);
967  return unique;
968  }
969 
970 /****************************************************************************/
971  template <typename L, typename Y>
973  const CompareFunc& compare) const {
974  return root_->equals(*other.root_, compare);
975  }
976 
977  template <typename L, typename Y>
978  void DecisionTree<L, Y>::print(const std::string& s,
979  const LabelFormatter& labelFormatter,
980  const ValueFormatter& valueFormatter) const {
981  root_->print(s, labelFormatter, valueFormatter);
982  }
983 
984  template<typename L, typename Y>
986  return root_->equals(*other.root_);
987  }
988 
989  /****************************************************************************/
990  template<typename L, typename Y>
992  if (root_ == nullptr)
993  throw std::invalid_argument(
994  "DecisionTree::operator() called on empty tree");
995  return root_->operator ()(x);
996  }
997 
998  /****************************************************************************/
999  template<typename L, typename Y>
1001  // It is unclear what should happen if tree is empty:
1002  if (empty()) {
1003  throw std::runtime_error(
1004  "DecisionTree::apply(unary op) undefined for empty tree.");
1005  }
1006  return DecisionTree(root_->apply(op));
1007  }
1008 
1009  /****************************************************************************/
1011  template <typename L, typename Y>
1013  const UnaryAssignment& op) const {
1014  // It is unclear what should happen if tree is empty:
1015  if (empty()) {
1016  throw std::runtime_error(
1017  "DecisionTree::apply(unary op) undefined for empty tree.");
1018  }
1019  Assignment<L> assignment;
1020  return DecisionTree(root_->apply(op, assignment));
1021  }
1022 
1023  /****************************************************************************/
1024  template<typename L, typename Y>
1026  const Binary& op) const {
1027  // It is unclear what should happen if either tree is empty:
1028  if (empty() || g.empty()) {
1029  throw std::runtime_error(
1030  "DecisionTree::apply(binary op) undefined for empty trees.");
1031  }
1032  // apply the operaton on the root of both diagrams
1033  NodePtr h = root_->apply_f_op_g(*g.root_, op);
1034  // create a new class with the resulting root "h"
1036  return result;
1037  }
1038 
1039  /****************************************************************************/
1040  // The way this works:
1041  // We have an ADT, picture it as a tree.
1042  // At a certain depth, we have a branch on "label".
1043  // The function "choose(label,index)" will return a tree of one less depth,
1044  // where there is no more branch on "label": only the subtree under that
1045  // branch point corresponding to the value "index" is left instead.
1046  // The function below get all these smaller trees and "ops" them together.
1047  // This implements marginalization in Darwiche09book, pg 330
1048  template<typename L, typename Y>
1050  size_t cardinality, const Binary& op) const {
1051  DecisionTree result = choose(label, 0);
1052  for (size_t index = 1; index < cardinality; index++) {
1053  DecisionTree chosen = choose(label, index);
1054  result = result.apply(chosen, op);
1055  }
1056  return result;
1057  }
1058 
1059  /****************************************************************************/
1060  template <typename L, typename Y>
1061  void DecisionTree<L, Y>::dot(std::ostream& os,
1062  const LabelFormatter& labelFormatter,
1064  bool showZero) const {
1065  os << "digraph G {\n";
1066  root_->dot(os, labelFormatter, valueFormatter, showZero);
1067  os << " [ordering=out]}" << std::endl;
1068  }
1069 
1070  template <typename L, typename Y>
1071  void DecisionTree<L, Y>::dot(const std::string& name,
1072  const LabelFormatter& labelFormatter,
1074  bool showZero) const {
1075  std::ofstream os((name + ".dot").c_str());
1076  dot(os, labelFormatter, valueFormatter, showZero);
1077  int result =
1078  system(("dot -Tpdf " + name + ".dot -o " + name + ".pdf >& /dev/null")
1079  .c_str());
1080  if (result == -1)
1081  throw std::runtime_error("DecisionTree::dot system call failed");
1082  }
1083 
1084  template <typename L, typename Y>
1085  std::string DecisionTree<L, Y>::dot(const LabelFormatter& labelFormatter,
1087  bool showZero) const {
1088  std::stringstream ss;
1089  dot(ss, labelFormatter, valueFormatter, showZero);
1090  return ss.str();
1091  }
1092 
1093  /******************************************************************************/
1094  template <typename L, typename Y>
1095  template <typename A, typename B>
1096  std::pair<DecisionTree<L, A>, DecisionTree<L, B>> DecisionTree<L, Y>::split(
1097  std::function<std::pair<A, B>(const Y&)> AB_of_Y) const {
1098  using AB = std::pair<A, B>;
1099  const DecisionTree<L, AB> ab(*this, AB_of_Y);
1100  const DecisionTree<L, A> a(ab, [](const AB& p) { return p.first; });
1101  const DecisionTree<L, B> b(ab, [](const AB& p) { return p.second; });
1102  return {a, b};
1103  }
1104 
1105  /******************************************************************************/
1106 
1107  } // namespace gtsam
gtsam::DecisionTree::Choice::branches
std::vector< NodePtr > & branches()
Definition: DecisionTree-inl.h:290
gtsam::DecisionTree::Choice::branches_
std::vector< NodePtr > branches_
Definition: DecisionTree-inl.h:167
gtsam::DecisionTree::Leaf::apply_f_op_g
NodePtr apply_f_op_g(const Node &g, const Binary &op) const override
Definition: DecisionTree-inl.h:121
create
ADT create(const Signature &signature)
Definition: testAlgebraicDecisionTree.cpp:136
compare
bool compare
Definition: SolverComparer.cpp:98
gtsam::DecisionTree::Choice::sameLeaf
bool sameLeaf(const Node &q) const override
polymorphic equality: if q is a leaf, could be...
Definition: DecisionTree-inl.h:343
gtsam::VisitWith::F
std::function< void(const Assignment< L > &, const Y &)> F
Definition: DecisionTree-inl.h:893
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
gtsam::DecisionTree::Choice::choose
NodePtr choose(const L &label, size_t index) const override
Definition: DecisionTree-inl.h:459
gtsam::DecisionTree::LabelFormatter
std::function< std::string(L)> LabelFormatter
Definition: DecisionTree.h:70
name
Annotation for function names.
Definition: attr.h:51
gtsam::DecisionTree::Choice::print
void print(const std::string &s, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter) const override
print (as a tree).
Definition: DecisionTree-inl.h:304
gtsam::DecisionTree::Leaf::apply
NodePtr apply(const UnaryAssignment &op, const Assignment< L > &assignment) const override
Apply unary operator with assignment.
Definition: DecisionTree-inl.h:110
test_constructor::f1
auto f1
Definition: testHybridNonlinearFactor.cpp:56
gtsam::DecisionTree::CompareFunc
std::function< bool(const Y &, const Y &)> CompareFunc
Definition: DecisionTree.h:72
Leaf
static sharedNode Leaf(Key key, const SymbolicFactorGraph &factors)
Definition: testSymbolicEliminationTree.cpp:78
gtsam::Visit::F
std::function< void(const Y &)> F
Definition: DecisionTree-inl.h:822
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::VisitWith
Definition: DecisionTree-inl.h:892
l2
gtsam::Key l2
Definition: testLinearContainerFactor.cpp:24
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
b
Scalar * b
Definition: benchVecAdd.cpp:17
gtsam::Y
GaussianFactorGraphValuePair Y
Definition: HybridGaussianProductFactor.cpp:29
gtsam::DecisionTree::equals
bool equals(const DecisionTree &other, const CompareFunc &compare=&DefaultCompare) const
Definition: DecisionTree-inl.h:972
gtsam::DecisionTree::Choice::apply_g_op_fC
NodePtr apply_g_op_fC(const Choice &fC, const Binary &op) const override
Definition: DecisionTree-inl.h:444
gtsam::DecisionTree::Leaf::apply_g_op_fC
NodePtr apply_g_op_fC(const Choice &fC, const Binary &op) const override
Definition: DecisionTree-inl.h:133
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
gtsam::DecisionTree::Choice::dot
void dot(std::ostream &os, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter, bool showZero) const override
Definition: DecisionTree-inl.h:314
gtsam::DecisionTree::ValueFormatter
std::function< std::string(Y)> ValueFormatter
Definition: DecisionTree.h:71
gtsam::Visit
Definition: DecisionTree-inl.h:821
B
Definition: test_numpy_dtypes.cpp:299
noxfile.build
None build(nox.Session session)
Definition: noxfile.py:96
gtsam::DecisionTree::Choice::Choice
Choice(const L &label, const Choice &f, const Unary &op)
Construct from applying unary op to a Choice node.
Definition: DecisionTree-inl.h:376
gtsam::DecisionTree::Choice
Definition: DecisionTree-inl.h:162
gtsam::DecisionTree::DecisionTree
DecisionTree()
Definition: DecisionTree-inl.h:491
copy
int EIGEN_BLAS_FUNC() copy(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Definition: level1_impl.h:29
Iterator
Definition: typing.h:54
X
#define X
Definition: icosphere.cpp:20
gtsam::DecisionTree::Choice::~Choice
~Choice() override
Definition: DecisionTree-inl.h:182
gtsam::DecisionTree::Leaf::print
void print(const std::string &s, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter) const override
print
Definition: DecisionTree-inl.h:83
h
const double h
Definition: testSimpleHelicopter.cpp:19
gtsam::DecisionTree::choose
DecisionTree choose(const L &label, size_t index) const
Definition: DecisionTree.h:391
os
ofstream os("timeSchurFactors.csv")
gtsam::VisitLeaf
Definition: DecisionTree-inl.h:858
gtsam::DecisionTree::Leaf::Leaf
Leaf(const Y &constant)
Constructor from constant.
Definition: DecisionTree-inl.h:58
gtsam::DecisionTree::Leaf::apply
NodePtr apply(const Unary &op) const override
Definition: DecisionTree-inl.h:104
result
Values result
Definition: OdometryOptimize.cpp:8
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
dot
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Definition: level1_real_impl.h:49
ss
static std::stringstream ss
Definition: testBTree.cpp:31
gtsam::VisitLeaf::f
F f
folding function object.
Definition: DecisionTree-inl.h:861
gtsam::DecisionTree::Choice::Choice
Choice(const L &label, size_t count)
Constructor, given choice label and mandatory expected branch count.
Definition: DecisionTree-inl.h:238
labels
std::vector< std::string > labels
Definition: dense_solvers.cpp:11
gtsam::DecisionTree::Leaf::Leaf
Leaf()
Default constructor for serialization.
Definition: DecisionTree-inl.h:55
gtsam::DecisionTree::Choice::isLeaf
bool isLeaf() const override
Definition: DecisionTree-inl.h:235
gtsam::DecisionTree::Unary
std::function< Y(const Y &)> Unary
Definition: DecisionTree.h:75
gtsam::DecisionTree::Choice::Unique
static NodePtr Unique(const NodePtr &node)
Merge branches with equal leaf values for every choice node in a decision tree. If all branches are t...
Definition: DecisionTree-inl.h:205
id
static const Similarity3 id
Definition: testSimilarity3.cpp:44
y1
double y1(double x)
Definition: j1.c:199
gtsam::VisitWith::assignment
Assignment< L > assignment
Assignment, mutating through recursion.
Definition: DecisionTree-inl.h:895
table
ArrayXXf table(10, 4)
test_constructor::f0
auto f0
Definition: testHybridNonlinearFactor.cpp:55
gtsam::DecisionTree::Leaf::sameLeaf
bool sameLeaf(const Leaf &q) const override
Leaf-Leaf equality.
Definition: DecisionTree-inl.h:66
gtsam::DecisionTree::Leaf::constant
const Y & constant() const
Return the constant.
Definition: DecisionTree-inl.h:61
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
gtsam::DecisionTree::Choice::allSame_
size_t allSame_
Definition: DecisionTree-inl.h:174
gtsam::VisitWith::f
F f
folding function object.
Definition: DecisionTree-inl.h:896
operator()
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
Definition: IndexedViewMethods.h:73
gtsam::DecisionTree::Binary
std::function< Y(const Y &, const Y &)> Binary
Definition: DecisionTree.h:77
gtsam::VisitWith::operator()
void operator()(const typename DecisionTree< L, Y >::NodePtr &node)
Do a depth-first visit on the tree rooted at node.
Definition: DecisionTree-inl.h:899
DecisionTree.h
Decision Tree for use in DiscreteFactors.
gtsam::DecisionTree::Choice::apply_f_op_g
NodePtr apply_f_op_g(const Node &g, const Binary &op) const override
Definition: DecisionTree-inl.h:431
x0
static Symbol x0('x', 0)
gtsam::DecisionTree::Leaf::apply_g_op_fL
NodePtr apply_g_op_fL(const Leaf &fL, const Binary &op) const override
Definition: DecisionTree-inl.h:126
gtsam::DecisionTree::Choice::Choice
Choice()
Default constructor for serialization.
Definition: DecisionTree-inl.h:180
L
MatrixXd L
Definition: LLT_example.cpp:6
gtsam::DecisionTree::Choice::operator()
const Y & operator()(const Assignment< L > &x) const override
evaluate
Definition: DecisionTree-inl.h:361
gtsam::DecisionTree::Choice::apply
NodePtr apply(const Unary &op) const override
apply unary operator.
Definition: DecisionTree-inl.h:414
gtsam::Assignment
Definition: Assignment.h:37
gtsam::DecisionTree::Choice::label_
L label_
Definition: DecisionTree-inl.h:164
gtsam::VisitLeaf::operator()
void operator()(const typename DecisionTree< L, Y >::NodePtr &node) const
Do a depth-first visit on the tree rooted at node.
Definition: DecisionTree-inl.h:864
gtsam::DecisionTree::Leaf::isLeaf
bool isLeaf() const override
Definition: DecisionTree-inl.h:142
gtsam::DecisionTree::Choice::sameLeaf
bool sameLeaf(const Leaf &q) const override
Choice-Leaf equality: always false.
Definition: DecisionTree-inl.h:338
gtsam::DecisionTree::Choice::branches
const std::vector< NodePtr > & branches() const
Definition: DecisionTree-inl.h:286
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
y
Scalar * y
Definition: level1_cplx_impl.h:124
gtsam::DecisionTree::Choice::Choice
Choice(const L &label, const Choice &f, const UnaryAssignment &op, const Assignment< L > &assignment)
Constructor which accepts a UnaryAssignment op and the corresponding assignment.
Definition: DecisionTree-inl.h:394
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::DecisionTree::Choice::ChoicePtr
std::shared_ptr< const Choice > ChoicePtr
Definition: DecisionTree-inl.h:176
gtsam::DecisionTree
a decision tree is a function from assignments to values.
Definition: DecisionTree.h:62
gtsam::DecisionTree::Leaf::equals
bool equals(const Node &q, const CompareFunc &compare) const override
equality up to tolerance
Definition: DecisionTree-inl.h:76
gtsam::DecisionTree::Choice::apply_fC_op_gL
NodePtr apply_fC_op_gL(const Leaf &gL, OP op) const
Definition: DecisionTree-inl.h:451
gtsam::DecisionTree::Choice::equals
bool equals(const Node &q, const CompareFunc &compare) const override
equality
Definition: DecisionTree-inl.h:348
gtsam::DecisionTree::Leaf
Definition: DecisionTree-inl.h:50
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
Eigen::bfloat16_impl::operator==
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool operator==(const bfloat16 &a, const bfloat16 &b)
Definition: BFloat16.h:218
empty
Definition: test_copy_move.cpp:19
gtsam::Visit::operator()
void operator()(const typename DecisionTree< L, Y >::NodePtr &node) const
Do a depth-first visit on the tree rooted at node.
Definition: DecisionTree-inl.h:827
gtsam
traits
Definition: SFMdata.h:40
gtsam::VisitLeaf::F
std::function< void(const typename DecisionTree< L, Y >::Leaf &)> F
Definition: DecisionTree-inl.h:859
gtsam::DecisionTree::Leaf::choose
NodePtr choose(const L &label, size_t index) const override
Definition: DecisionTree-inl.h:138
OP
#define OP(X)
Definition: gtsam/3rdparty/Eigen/blas/common.h:47
gtsam::testing::compose
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
l1
gtsam::Key l1
Definition: testLinearContainerFactor.cpp:24
gtsam::DecisionTree::UnaryAssignment
std::function< Y(const Assignment< L > &, const Y &)> UnaryAssignment
Definition: DecisionTree.h:76
gtsam::DecisionTree< Key, GaussianFactorGraphValuePair >::LabelC
std::pair< Key, size_t > LabelC
Definition: DecisionTree.h:80
gtsam::DecisionTree::Choice::apply
NodePtr apply(const UnaryAssignment &op, const Assignment< L > &assignment) const override
Apply unary operator with assignment.
Definition: DecisionTree-inl.h:420
gtsam::DecisionTree::Leaf::constant_
Y constant_
Definition: DecisionTree-inl.h:52
gtsam::DecisionTree::Choice::label
const L & label() const
Return the label of this choice node.
Definition: DecisionTree-inl.h:278
p
float * p
Definition: Tutorial_Map_using.cpp:9
c_str
const char * c_str(Args &&...args)
Definition: internals.h:684
leaf
Definition: testExpressionFactor.cpp:42
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:460
gtsam::DecisionTree::Node
Definition: DecisionTree.h:87
gtsam::DecisionTree::Choice::apply_g_op_fL
NodePtr apply_g_op_fL(const Leaf &fL, const Binary &op) const override
Definition: DecisionTree-inl.h:436
gtsam::split
void split(const G &g, const PredecessorMap< KEY > &tree, G &Ab1, G &Ab2)
Definition: graph-inl.h:245
gtsam::DecisionTree::Leaf::operator()
const Y & operator()(const Assignment< L > &x) const override
Definition: DecisionTree-inl.h:99
gtsam::DecisionTree::NodePtr
typename Node::Ptr NodePtr
Definition: DecisionTree.h:146
gtsam::DecisionTree::Choice::nrChoices
size_t nrChoices() const
Definition: DecisionTree-inl.h:282
gtsam::DecisionTree::Choice::Choice
Choice(const Choice &f, const Choice &g, const Binary &op)
Construct from applying binary op to two Choice nodes.
Definition: DecisionTree-inl.h:244
gtsam::DecisionTree::Choice::push_back
void push_back(NodePtr &&node)
Definition: DecisionTree-inl.h:295
Eigen::placeholders::end
static const EIGEN_DEPRECATED end_t end
Definition: IndexedViewHelper.h:181
gtsam::DecisionTree::Leaf::dot
void dot(std::ostream &os, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter, bool showZero) const override
Definition: DecisionTree-inl.h:89
gtsam::valueFormatter
static std::string valueFormatter(const double &v)
Definition: DecisionTreeFactor.cpp:248
gtsam::DecisionTree::Leaf::sameLeaf
bool sameLeaf(const Node &q) const override
polymorphic equality: is q a leaf and is it the same as this leaf?
Definition: DecisionTree-inl.h:71
choose
static const T & choose(int layout, const T &col, const T &row)
Definition: cxx11_tensor_block_access.cpp:27
test_callbacks.value
value
Definition: test_callbacks.py:160
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::Visit::f
F f
folding function object.
Definition: DecisionTree-inl.h:824
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:32:23