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  if (!q.isLeaf()) return false;
78  const Leaf* other = static_cast<const Leaf*>(&q);
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 #if 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  #ifdef GTSAM_DT_MERGING
206 
207  static NodePtr Unique(const NodePtr& node) {
208  if (node->isLeaf()) return node; // Leaf node, return as is
209 
210  auto choice = std::static_pointer_cast<const Choice>(node);
211  // Choice node, we recurse!
212  // Make non-const copy so we can update
213  auto f = std::make_shared<Choice>(choice->label(), choice->nrChoices());
214 
215  // Iterate over all the branches
216  for (const auto& branch : choice->branches_) {
217  f->push_back(Unique(branch));
218  }
219 
220  // If all the branches are the same, we can merge them into one
221  if (f->allSame_) {
222  assert(f->branches().size() > 0);
223  auto f0 = std::static_pointer_cast<const Leaf>(f->branches_[0]);
224  return std::make_shared<Leaf>(f0->constant());
225  }
226 
227  return f;
228  }
229 
230  #else
231 
232  static NodePtr Unique(const NodePtr& node) {
233  // No-op when GTSAM_DT_MERGING is not defined
234  return node;
235  }
236 
237  #endif
238  bool isLeaf() const override { return false; }
239 
241  Choice(const L& label, size_t count) :
242  label_(label), allSame_(true) {
243  branches_.reserve(count);
244  }
245 
247  Choice(const Choice& f, const Choice& g, const Binary& op) :
248  allSame_(true) {
249  // Choose what to do based on label
250  if (f.label() > g.label()) {
251  // f higher than g
252  label_ = f.label();
253  size_t count = f.nrChoices();
254  branches_.reserve(count);
255  for (size_t i = 0; i < count; i++) {
256  NodePtr newBranch = f.branches_[i]->apply_f_op_g(g, op);
257  push_back(std::move(newBranch));
258  }
259  } else if (g.label() > f.label()) {
260  // f lower than g
261  label_ = g.label();
262  size_t count = g.nrChoices();
263  branches_.reserve(count);
264  for (size_t i = 0; i < count; i++) {
265  NodePtr newBranch = g.branches_[i]->apply_g_op_fC(f, op);
266  push_back(std::move(newBranch));
267  }
268  } else {
269  // f same level as g
270  label_ = f.label();
271  size_t count = f.nrChoices();
272  branches_.reserve(count);
273  for (size_t i = 0; i < count; i++) {
274  NodePtr newBranch = f.branches_[i]->apply_f_op_g(*g.branches_[i], op);
275  push_back(std::move(newBranch));
276  }
277  }
278  }
279 
281  const L& label() const {
282  return label_;
283  }
284 
285  size_t nrChoices() const {
286  return branches_.size();
287  }
288 
289  const std::vector<NodePtr>& branches() const {
290  return branches_;
291  }
292 
293  std::vector<NodePtr>& branches() {
294  return branches_;
295  }
296 
298  void push_back(NodePtr&& node) {
299  // allSame_ is restricted to leaf nodes in a decision tree
300  if (allSame_ && !branches_.empty()) {
301  allSame_ = node->sameLeaf(*branches_.back());
302  }
303  branches_.push_back(std::move(node));
304  }
305 
307  void print(const std::string& s, const LabelFormatter& labelFormatter,
308  const ValueFormatter& valueFormatter) const override {
309  std::cout << s << " Choice(";
310  std::cout << labelFormatter(label_) << ") " << std::endl;
311  for (size_t i = 0; i < branches_.size(); i++) {
312  branches_[i]->print(s + " " + std::to_string(i), labelFormatter, valueFormatter);
313  }
314  }
315 
317  void dot(std::ostream& os, const LabelFormatter& labelFormatter,
319  bool showZero) const override {
320  const std::string label = labelFormatter(label_);
321  os << "\"" << this->id() << "\" [shape=circle, label=\"" << label
322  << "\"]\n";
323  size_t B = branches_.size();
324  for (size_t i = 0; i < B; i++) {
325  const NodePtr& branch = branches_[i];
326 
327  // Check if zero
328  if (!showZero && branch->isLeaf()) {
329  auto leaf = std::static_pointer_cast<const Leaf>(branch);
330  if (valueFormatter(leaf->constant()).compare("0")) continue;
331  }
332 
333  os << "\"" << this->id() << "\" -> \"" << branch->id() << "\"";
334  if (B == 2 && i == 0) os << " [style=dashed]";
335  os << std::endl;
336  branch->dot(os, labelFormatter, valueFormatter, showZero);
337  }
338  }
339 
341  bool sameLeaf(const Leaf& q) const override {
342  return false;
343  }
344 
346  bool sameLeaf(const Node& q) const override {
347  return (q.isLeaf() && q.sameLeaf(*this));
348  }
349 
351  bool equals(const Node& q, const CompareFunc& compare) const override {
352  if (q.isLeaf()) return false;
353  const Choice* other = static_cast<const Choice*>(&q);
354  if (this->label_ != other->label_) return false;
355  if (branches_.size() != other->branches_.size()) return false;
356  // we don't care about shared pointers being equal here
357  for (size_t i = 0; i < branches_.size(); i++)
358  if (!(branches_[i]->equals(*(other->branches_[i]), compare)))
359  return false;
360  return true;
361  }
362 
364  const Y& operator()(const Assignment<L>& x) const override {
365 #ifndef NDEBUG
366  typename Assignment<L>::const_iterator it = x.find(label_);
367  if (it == x.end()) {
368  std::cout << "Trying to find value for " << label_ << std::endl;
369  throw std::invalid_argument(
370  "DecisionTree::operator(): value undefined for a label");
371  }
372 #endif
373  size_t index = x.at(label_);
374  NodePtr child = branches_[index];
375  return (*child)(x);
376  }
377 
379  Choice(const L& label, const Choice& f, const Unary& op) :
380  label_(label), allSame_(true) {
381  branches_.reserve(f.branches_.size()); // reserve space
382  for (const NodePtr& branch : f.branches_) {
383  push_back(branch->apply(op));
384  }
385  }
386 
397  Choice(const L& label, const Choice& f, const UnaryAssignment& op,
398  const Assignment<L>& assignment)
399  : label_(label), allSame_(true) {
400  branches_.reserve(f.branches_.size()); // reserve space
401 
402  Assignment<L> assignment_ = assignment;
403 
404  for (size_t i = 0; i < f.branches_.size(); i++) {
405  assignment_[label_] = i; // Set assignment for label to i
406 
407  const NodePtr branch = f.branches_[i];
408  push_back(branch->apply(op, assignment_));
409 
410  // Remove the assignment so we are backtracking
411  auto assignment_it = assignment_.find(label_);
412  assignment_.erase(assignment_it);
413  }
414  }
415 
417  NodePtr apply(const Unary& op) const override {
418  auto r = std::make_shared<Choice>(label_, *this, op);
419  return Unique(r);
420  }
421 
424  const Assignment<L>& assignment) const override {
425  auto r = std::make_shared<Choice>(label_, *this, op, assignment);
426  return Unique(r);
427  }
428 
429  // Apply binary operator "h = f op g" on Choice node
430  // Note op is not assumed commutative so we need to keep track of order
431  // Simply calls apply on argument to call correct virtual method:
432  // fC.apply_f_op_g(gL) -> gL.apply_g_op_fC(fC) -> (Leaf)
433  // fC.apply_f_op_g(gC) -> gC.apply_g_op_fC(fC) -> (below)
434  NodePtr apply_f_op_g(const Node& g, const Binary& op) const override {
435  return g.apply_g_op_fC(*this, op);
436  }
437 
438  // If second argument of binary op is Leaf node, recurse on branches
439  NodePtr apply_g_op_fL(const Leaf& fL, const Binary& op) const override {
440  auto h = std::make_shared<Choice>(label(), nrChoices());
441  for (auto&& branch : branches_)
442  h->push_back(fL.apply_f_op_g(*branch, op));
443  return Unique(h);
444  }
445 
446  // If second argument of binary op is Choice, call constructor
447  NodePtr apply_g_op_fC(const Choice& fC, const Binary& op) const override {
448  auto h = std::make_shared<Choice>(fC, *this, op);
449  return Unique(h);
450  }
451 
452  // If second argument of binary op is Leaf
453  template<typename OP>
454  NodePtr apply_fC_op_gL(const Leaf& gL, OP op) const {
455  auto h = std::make_shared<Choice>(label(), nrChoices());
456  for (auto&& branch : branches_)
457  h->push_back(branch->apply_f_op_g(gL, op));
458  return Unique(h);
459  }
460 
462  NodePtr choose(const L& label, size_t index) const override {
463  if (label_ == label) return branches_[index]; // choose branch
464 
465  // second case, not label of interest, just recurse
466  auto r = std::make_shared<Choice>(label_, branches_.size());
467  for (auto&& branch : branches_) {
468  r->push_back(branch->choose(label, index));
469  }
470 
471  return Unique(r);
472  }
473 
474  private:
476 
477 #if GTSAM_ENABLE_BOOST_SERIALIZATION
478 
479  friend class boost::serialization::access;
480  template <class ARCHIVE>
481  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
482  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
483  ar& BOOST_SERIALIZATION_NVP(label_);
484  ar& BOOST_SERIALIZATION_NVP(branches_);
485  ar& BOOST_SERIALIZATION_NVP(allSame_);
486  }
487 #endif
488  }; // Choice
489 
490  /****************************************************************************/
491  // DecisionTree
492  /****************************************************************************/
493  template <typename L, typename Y>
494  DecisionTree<L, Y>::DecisionTree() : root_(nullptr) {}
495 
496  template<typename L, typename Y>
498  root_(root) {}
499 
500  /****************************************************************************/
501  template<typename L, typename Y>
503  root_ = NodePtr(new Leaf(y));
504  }
505 
506  /****************************************************************************/
507  template <typename L, typename Y>
508  DecisionTree<L, Y>::DecisionTree(const L& label, const Y& y1, const Y& y2) {
509  auto a = std::make_shared<Choice>(label, 2);
510  NodePtr l1(new Leaf(y1)), l2(new Leaf(y2));
511  a->push_back(std::move(l1));
512  a->push_back(std::move(l2));
513  root_ = Choice::Unique(std::move(a));
514  }
515 
516  /****************************************************************************/
517  template <typename L, typename Y>
519  const Y& y2) {
520  if (labelC.second != 2) throw std::invalid_argument(
521  "DecisionTree: binary constructor called with non-binary label");
522  auto a = std::make_shared<Choice>(labelC.first, 2);
523  NodePtr l1(new Leaf(y1)), l2(new Leaf(y2));
524  a->push_back(std::move(l1));
525  a->push_back(std::move(l2));
526  root_ = Choice::Unique(std::move(a));
527  }
528  /****************************************************************************/
529  template<typename L, typename Y>
530  DecisionTree<L, Y>::DecisionTree(const std::vector<LabelC>& labelCs,
531  const std::vector<Y>& ys) {
532  // call recursive Create
533  root_ = create(labelCs.begin(), labelCs.end(), ys.begin(), ys.end());
534  }
535 
536  /****************************************************************************/
537  template<typename L, typename Y>
538  DecisionTree<L, Y>::DecisionTree(const std::vector<LabelC>& labelCs,
539  const std::string& table) {
540  // Convert std::string to values of type Y
541  std::vector<Y> ys;
542  std::istringstream iss(table);
543  copy(std::istream_iterator<Y>(iss), std::istream_iterator<Y>(),
544  back_inserter(ys));
545 
546  // now call recursive Create
547  root_ = create(labelCs.begin(), labelCs.end(), ys.begin(), ys.end());
548  }
549 
550  /****************************************************************************/
551  template<typename L, typename Y>
552  template<typename Iterator> DecisionTree<L, Y>::DecisionTree(
553  Iterator begin, Iterator end, const L& label) {
554  root_ = compose(begin, end, label);
555  }
556 
557  /****************************************************************************/
558  template<typename L, typename Y>
560  const DecisionTree& f0, const DecisionTree& f1) {
561  const std::vector<DecisionTree> functions{f0, f1};
562  root_ = compose(functions.begin(), functions.end(), label);
563  }
564 
565  /****************************************************************************/
566  template <typename L, typename Y>
568  DecisionTree&& other) noexcept
569  : root_(std::move(other.root_)) {
570  // Apply the unary operation directly to each leaf in the tree
571  if (root_) {
572  // Define a helper function to traverse and apply the operation
573  struct ApplyUnary {
574  const Unary& op;
575  void operator()(typename DecisionTree<L, Y>::NodePtr& node) const {
576  if (node->isLeaf()) {
577  // Apply the unary operation to the leaf's constant value
578  auto leaf = std::static_pointer_cast<Leaf>(node);
579  leaf->constant_ = op(leaf->constant_);
580  } else {
581  // Recurse into the choice branches
582  auto choice = std::static_pointer_cast<Choice>(node);
583  for (NodePtr& branch : choice->branches()) {
584  (*this)(branch);
585  }
586  }
587  }
588  };
589 
590  ApplyUnary applyUnary{op};
591  applyUnary(root_);
592  }
593  // Reset the other tree's root to nullptr to avoid dangling references
594  other.root_ = nullptr;
595  }
596 
597  /****************************************************************************/
598  template <typename L, typename Y>
599  template <typename X, typename Func>
601  Func Y_of_X) {
602  root_ = convertFrom<X>(other.root_, Y_of_X);
603  }
604 
605  /****************************************************************************/
606  template <typename L, typename Y>
607  template <typename M, typename X, typename Func>
609  const std::map<M, L>& map, Func Y_of_X) {
610  auto L_of_M = [&map](const M& label) -> L { return map.at(label); };
611  root_ = convertFrom<M, X>(other.root_, L_of_M, Y_of_X);
612  }
613 
614  /****************************************************************************/
615  // Called by two constructors above.
616  // Takes a label and a corresponding range of decision trees, and creates a
617  // new decision tree. However, the order of the labels needs to be respected,
618  // so we cannot just create a root Choice node on the label: if the label is
619  // not the highest label, we need a complicated/ expensive recursive call.
620  template <typename L, typename Y>
621  template <typename Iterator>
623  Iterator begin, Iterator end, const L& label) {
624  // find highest label among branches
625  std::optional<L> highestLabel;
626  size_t nrChoices = 0;
627  for (Iterator it = begin; it != end; it++) {
628  if (it->root_->isLeaf())
629  continue;
630  auto c = std::static_pointer_cast<const Choice>(it->root_);
631  if (!highestLabel || c->label() > *highestLabel) {
632  highestLabel = c->label();
633  nrChoices = c->nrChoices();
634  }
635  }
636 
637  // if label is already in correct order, just put together a choice on label
638  if (!nrChoices || !highestLabel || label > *highestLabel) {
639  auto choiceOnLabel = std::make_shared<Choice>(label, end - begin);
640  for (Iterator it = begin; it != end; it++) {
641  NodePtr root = it->root_;
642  choiceOnLabel->push_back(std::move(root));
643  }
644  // If no reordering, no need to call Choice::Unique
645  return choiceOnLabel;
646  } else {
647  // Set up a new choice on the highest label
648  auto choiceOnHighestLabel =
649  std::make_shared<Choice>(*highestLabel, nrChoices);
650  // now, for all possible values of highestLabel
651  for (size_t index = 0; index < nrChoices; index++) {
652  // make a new set of functions for composing by iterating over the given
653  // functions, and selecting the appropriate branch.
654  std::vector<DecisionTree> functions;
655  for (Iterator it = begin; it != end; it++) {
656  // by restricting the input functions to value i for labelBelow
657  DecisionTree chosen = it->choose(*highestLabel, index);
658  functions.push_back(chosen);
659  }
660  // We then recurse, for all values of the highest label
661  NodePtr fi = compose(functions.begin(), functions.end(), label);
662  choiceOnHighestLabel->push_back(std::move(fi));
663  }
664  return choiceOnHighestLabel;
665  }
666  }
667 
668  /****************************************************************************/
669  // "build" is a bit of a complicated thing, but very useful.
670  // It takes a range of labels and a corresponding range of values,
671  // and builds a decision tree, as follows:
672  // - if there is only one label, creates a choice node with values in leaves
673  // - otherwise, it evenly splits up the range of values and creates a tree for
674  // each sub-range, and assigns that tree to first label's choices
675  // Example:
676  // build([B A],[1 2 3 4]) would call
677  // build([A],[1 2])
678  // build([A],[3 4])
679  // and produce
680  // B=0
681  // A=0: 1
682  // A=1: 2
683  // B=1
684  // A=0: 3
685  // A=1: 4
686  // Note, through the magic of "compose", create([A B],[1 3 2 4]) will produce
687  // exactly the same tree as above: the highest label is always the root.
688  // However, it will be *way* faster if labels are given highest to lowest.
689  template<typename L, typename Y>
690  template<typename It, typename ValueIt>
692  It begin, It end, ValueIt beginY, ValueIt endY) {
693  // get crucial counts
694  size_t nrChoices = begin->second;
695  size_t size = endY - beginY;
696 
697  // Find the next key to work on
698  It labelC = begin + 1;
699  if (labelC == end) {
700  // Base case: only one key left
701  // Create a simple choice node with values as leaves.
702  if (size != nrChoices) {
703  std::cout << "Trying to create DD on " << begin->first << std::endl;
704  std::cout << "DecisionTree::create: expected " << nrChoices
705  << " values but got " << size << " instead" << std::endl;
706  throw std::invalid_argument("DecisionTree::create invalid argument");
707  }
708  auto choice = std::make_shared<Choice>(begin->first, endY - beginY);
709  for (ValueIt y = beginY; y != endY; y++) {
710  choice->push_back(NodePtr(new Leaf(*y)));
711  }
712  return choice;
713  }
714 
715  // Recursive case: perform "Shannon expansion"
716  // Creates one tree (i.e.,function) for each choice of current key
717  // by calling create recursively, and then puts them all together.
718  std::vector<DecisionTree> functions;
719  functions.reserve(nrChoices);
720  size_t split = size / nrChoices;
721  for (size_t i = 0; i < nrChoices; i++, beginY += split) {
722  NodePtr f = build<It, ValueIt>(labelC, end, beginY, beginY + split);
723  functions.emplace_back(f);
724  }
725  return compose(functions.begin(), functions.end(), begin->first);
726  }
727 
728  /****************************************************************************/
729  // Top-level factory method, which takes a range of labels and a corresponding
730  // range of values, and creates a decision tree.
731  template<typename L, typename Y>
732  template<typename It, typename ValueIt>
734  It begin, It end, ValueIt beginY, ValueIt endY) {
735  auto node = build(begin, end, beginY, endY);
736  return Choice::Unique(node);
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  using LXLeaf = typename DecisionTree<L, X>::Leaf;
746  using LXChoice = typename DecisionTree<L, X>::Choice;
747 
748  // If leaf, apply unary conversion "op" and create a unique leaf.
749  if (f->isLeaf()) {
750  auto leaf = std::static_pointer_cast<LXLeaf>(f);
751  return NodePtr(new Leaf(Y_of_X(leaf->constant())));
752  }
753 
754  // Now a Choice!
755  auto choice = std::static_pointer_cast<const LXChoice>(f);
756 
757  // Create a new Choice node with the same label
758  auto newChoice = std::make_shared<Choice>(choice->label(), choice->nrChoices());
759 
760  // Convert each branch recursively
761  for (auto&& branch : choice->branches()) {
762  newChoice->push_back(convertFrom<X>(branch, Y_of_X));
763  }
764 
765  return Choice::Unique(newChoice);
766  }
767 
768  /****************************************************************************/
769  template <typename L, typename Y>
770  template <typename M, typename X>
772  const typename DecisionTree<M, X>::NodePtr& f,
773  std::function<L(const M&)> L_of_M, std::function<Y(const X&)> Y_of_X) {
774  using LY = DecisionTree<L, Y>;
775  using MXLeaf = typename DecisionTree<M, X>::Leaf;
776  using MXChoice = typename DecisionTree<M, X>::Choice;
777 
778  // If leaf, apply unary conversion "op" and create a unique leaf.
779  if (f->isLeaf()) {
780  auto leaf = std::static_pointer_cast<const MXLeaf>(f);
781  return NodePtr(new Leaf(Y_of_X(leaf->constant())));
782  }
783 
784  // Now is Choice!
785  auto choice = std::static_pointer_cast<const MXChoice>(f);
786 
787  // get new label
788  const M oldLabel = choice->label();
789  const L newLabel = L_of_M(oldLabel);
790 
791  // Shannon expansion in this context involves:
792  // 1. Creating separate subtrees (functions) for each possible value of the new label.
793  // 2. Combining these subtrees using the 'compose' method, which implements the expansion.
794  // This approach guarantees that the resulting tree maintains the correct variable ordering
795  // based on the new labels (L) after translation from the old labels (M).
796  // Simply creating a Choice node here would not work because it wouldn't account for the
797  // potentially new ordering of variables resulting from the label translation,
798  // which is crucial for maintaining consistency and efficiency in the converted tree.
799  std::vector<LY> functions;
800  for (auto&& branch : choice->branches()) {
801  functions.emplace_back(convertFrom<M, X>(branch, L_of_M, Y_of_X));
802  }
803  return Choice::Unique(
804  LY::compose(functions.begin(), functions.end(), newLabel));
805  }
806 
807  /****************************************************************************/
818  template <typename L, typename Y>
819  struct Visit {
820  using F = std::function<void(const Y&)>;
821  explicit Visit(F f) : f(f) {}
822  F f;
823 
825  void operator()(const typename DecisionTree<L, Y>::NodePtr& node) const {
826  using Leaf = typename DecisionTree<L, Y>::Leaf;
827  using Choice = typename DecisionTree<L, Y>::Choice;
828 
829  if (node->isLeaf()) {
830  auto leaf = std::static_pointer_cast<const Leaf>(node);
831  return f(leaf->constant());
832  }
833 
834  auto choice = std::static_pointer_cast<const Choice>(node);
835  for (auto&& branch : choice->branches()) (*this)(branch); // recurse!
836  }
837  };
838 
839  template <typename L, typename Y>
840  template <typename Func>
841  void DecisionTree<L, Y>::visit(Func f) const {
842  Visit<L, Y> visit(f);
843  visit(root_);
844  }
845 
846  /****************************************************************************/
856  template <typename L, typename Y>
857  struct VisitLeaf {
858  using F = std::function<void(const typename DecisionTree<L, Y>::Leaf&)>;
859  explicit VisitLeaf(F f) : f(f) {}
860  F f;
861 
863  void operator()(const typename DecisionTree<L, Y>::NodePtr& node) const {
864  using Leaf = typename DecisionTree<L, Y>::Leaf;
865  using Choice = typename DecisionTree<L, Y>::Choice;
866 
867  if (node->isLeaf()) {
868  auto leaf = std::static_pointer_cast<const Leaf>(node);
869  return f(*leaf);
870  }
871 
872  auto choice = std::static_pointer_cast<const Choice>(node);
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  using Choice = typename DecisionTree<L, Y>::Choice;
902 
903  if (node->isLeaf()) {
904  auto leaf = std::static_pointer_cast<const Leaf>(node);
905  return f(assignment, leaf->constant());
906  }
907 
908 
909 
910  auto choice = std::static_pointer_cast<const Choice>(node);
911  for (size_t i = 0; i < choice->nrChoices(); i++) {
912  assignment[choice->label()] = i; // Set assignment for label to i
913 
914  (*this)(choice->branches()[i]); // recurse!
915 
916  // Remove the choice so we are backtracking
917  auto choice_it = assignment.find(choice->label());
918  assignment.erase(choice_it);
919  }
920  }
921  };
922 
923  template <typename L, typename Y>
924  template <typename Func>
925  void DecisionTree<L, Y>::visitWith(Func f) const {
926  VisitWith<L, Y> visit(f);
927  visit(root_);
928  }
929 
930  /****************************************************************************/
931  template <typename L, typename Y>
933  size_t total = 0;
934  visit([&total](const Y& node) { total += 1; });
935  return total;
936  }
937 
938  /****************************************************************************/
939  // fold is just done with a visit
940  template <typename L, typename Y>
941  template <typename Func, typename X>
942  X DecisionTree<L, Y>::fold(Func f, X x0) const {
943  visit([&](const Y& y) { x0 = f(y, x0); });
944  return x0;
945  }
946 
947  /****************************************************************************/
961  template <typename L, typename Y>
962  std::set<L> DecisionTree<L, Y>::labels() const {
963  std::set<L> unique;
964  auto f = [&](const Assignment<L>& assignment, const Y&) {
965  for (auto&& kv : assignment) {
966  unique.insert(kv.first);
967  }
968  };
969  visitWith(f);
970  return unique;
971  }
972 
973 /****************************************************************************/
974  template <typename L, typename Y>
976  const CompareFunc& compare) const {
977  return root_->equals(*other.root_, compare);
978  }
979 
980  template <typename L, typename Y>
981  void DecisionTree<L, Y>::print(const std::string& s,
982  const LabelFormatter& labelFormatter,
983  const ValueFormatter& valueFormatter) const {
984  root_->print(s, labelFormatter, valueFormatter);
985  }
986 
987  template<typename L, typename Y>
989  return root_->equals(*other.root_);
990  }
991 
992  /****************************************************************************/
993  template<typename L, typename Y>
995  if (root_ == nullptr)
996  throw std::invalid_argument(
997  "DecisionTree::operator() called on empty tree");
998  return root_->operator ()(x);
999  }
1000 
1001  /****************************************************************************/
1002  template<typename L, typename Y>
1004  // It is unclear what should happen if tree is empty:
1005  if (empty()) {
1006  throw std::runtime_error(
1007  "DecisionTree::apply(unary op) undefined for empty tree.");
1008  }
1009  return DecisionTree(root_->apply(op));
1010  }
1011 
1012  /****************************************************************************/
1014  template <typename L, typename Y>
1016  const UnaryAssignment& op) const {
1017  // It is unclear what should happen if tree is empty:
1018  if (empty()) {
1019  throw std::runtime_error(
1020  "DecisionTree::apply(unary op) undefined for empty tree.");
1021  }
1022  Assignment<L> assignment;
1023  return DecisionTree(root_->apply(op, assignment));
1024  }
1025 
1026  /****************************************************************************/
1027  template<typename L, typename Y>
1029  const Binary& op) const {
1030  // It is unclear what should happen if either tree is empty:
1031  if (empty() || g.empty()) {
1032  throw std::runtime_error(
1033  "DecisionTree::apply(binary op) undefined for empty trees.");
1034  }
1035  // apply the operaton on the root of both diagrams
1036  NodePtr h = root_->apply_f_op_g(*g.root_, op);
1037  // create a new class with the resulting root "h"
1039  return result;
1040  }
1041 
1042  /****************************************************************************/
1043  // The way this works:
1044  // We have an ADT, picture it as a tree.
1045  // At a certain depth, we have a branch on "label".
1046  // The function "choose(label,index)" will return a tree of one less depth,
1047  // where there is no more branch on "label": only the subtree under that
1048  // branch point corresponding to the value "index" is left instead.
1049  // The function below get all these smaller trees and "ops" them together.
1050  // This implements marginalization in Darwiche09book, pg 330
1051  template<typename L, typename Y>
1053  size_t cardinality, const Binary& op) const {
1054  DecisionTree result = choose(label, 0);
1055  for (size_t index = 1; index < cardinality; index++) {
1056  DecisionTree chosen = choose(label, index);
1057  result = result.apply(chosen, op);
1058  }
1059  return result;
1060  }
1061 
1062  /****************************************************************************/
1063  template <typename L, typename Y>
1064  void DecisionTree<L, Y>::dot(std::ostream& os,
1065  const LabelFormatter& labelFormatter,
1067  bool showZero) const {
1068  os << "digraph G {\n";
1069  root_->dot(os, labelFormatter, valueFormatter, showZero);
1070  os << " [ordering=out]}" << std::endl;
1071  }
1072 
1073  template <typename L, typename Y>
1074  void DecisionTree<L, Y>::dot(const std::string& name,
1075  const LabelFormatter& labelFormatter,
1077  bool showZero) const {
1078  std::ofstream os((name + ".dot").c_str());
1079  dot(os, labelFormatter, valueFormatter, showZero);
1080  int result =
1081  system(("dot -Tpdf " + name + ".dot -o " + name + ".pdf >& /dev/null")
1082  .c_str());
1083  if (result == -1)
1084  throw std::runtime_error("DecisionTree::dot system call failed");
1085  }
1086 
1087  template <typename L, typename Y>
1088  std::string DecisionTree<L, Y>::dot(const LabelFormatter& labelFormatter,
1090  bool showZero) const {
1091  std::stringstream ss;
1092  dot(ss, labelFormatter, valueFormatter, showZero);
1093  return ss.str();
1094  }
1095 
1096  /******************************************************************************/
1097  template <typename L, typename Y>
1098  template <typename A, typename B>
1099  std::pair<DecisionTree<L, A>, DecisionTree<L, B>> DecisionTree<L, Y>::split(
1100  std::function<std::pair<A, B>(const Y&)> AB_of_Y) const {
1101  using AB = std::pair<A, B>;
1102  const DecisionTree<L, AB> ab(*this, AB_of_Y);
1103  const DecisionTree<L, A> a(ab, [](const AB& p) { return p.first; });
1104  const DecisionTree<L, B> b(ab, [](const AB& p) { return p.second; });
1105  return {a, b};
1106  }
1107 
1108  /******************************************************************************/
1109 
1110  } // namespace gtsam
gtsam::DecisionTree::Choice::branches
std::vector< NodePtr > & branches()
Definition: DecisionTree-inl.h:293
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:145
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:346
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:462
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:307
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:820
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:975
gtsam::DecisionTree::Choice::apply_g_op_fC
NodePtr apply_g_op_fC(const Choice &fC, const Binary &op) const override
Definition: DecisionTree-inl.h:447
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:317
gtsam::DecisionTree::ValueFormatter
std::function< std::string(Y)> ValueFormatter
Definition: DecisionTree.h:71
gtsam::Visit
Definition: DecisionTree-inl.h:819
B
Definition: test_numpy_dtypes.cpp:301
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:379
gtsam::DecisionTree::Choice
Definition: DecisionTree-inl.h:162
gtsam::DecisionTree::DecisionTree
DecisionTree()
Definition: DecisionTree-inl.h:494
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:56
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:857
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:860
gtsam::DecisionTree::Choice::Choice
Choice(const L &label, size_t count)
Constructor, given choice label and mandatory expected branch count.
Definition: DecisionTree-inl.h:241
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:238
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:232
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:434
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:364
gtsam::DecisionTree::Choice::apply
NodePtr apply(const Unary &op) const override
apply unary operator.
Definition: DecisionTree-inl.h:417
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:863
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:341
gtsam::DecisionTree::Choice::branches
const std::vector< NodePtr > & branches() const
Definition: DecisionTree-inl.h:289
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:397
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:454
gtsam::DecisionTree::Choice::equals
bool equals(const Node &q, const CompareFunc &compare) const override
equality
Definition: DecisionTree-inl.h:351
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:825
gtsam
traits
Definition: SFMdata.h:40
gtsam::VisitLeaf::F
std::function< void(const typename DecisionTree< L, Y >::Leaf &)> F
Definition: DecisionTree-inl.h:858
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:423
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:281
p
float * p
Definition: Tutorial_Map_using.cpp:9
c_str
const char * c_str(Args &&...args)
Definition: internals.h:701
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:467
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:439
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:285
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:247
gtsam::DecisionTree::Choice::push_back
void push_back(NodePtr &&node)
Definition: DecisionTree-inl.h:298
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:292
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:162
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:822
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:34