DecisionTreeFactor.cpp
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 #include <gtsam/base/FastSet.h>
25 
26 #include <utility>
27 
28 using namespace std;
29 
30 namespace gtsam {
31 
32  /* ************************************************************************ */
33  DecisionTreeFactor::DecisionTreeFactor() {}
34 
35  /* ************************************************************************ */
36  DecisionTreeFactor::DecisionTreeFactor(const DiscreteKeys& keys,
37  const ADT& potentials)
38  : DiscreteFactor(keys.indices(), keys.cardinalities()), ADT(potentials) {}
39 
40  /* ************************************************************************ */
42  : DiscreteFactor(c.keys(), c.cardinalities()),
44 
45  /* ************************************************************************ */
47  double tol) const {
48  if (!dynamic_cast<const DecisionTreeFactor*>(&other)) {
49  return false;
50  } else {
51  const auto& f(static_cast<const DecisionTreeFactor&>(other));
52  return Base::equals(other, tol) && ADT::equals(f, tol);
53  }
54  }
55 
56  /* ************************************************************************ */
58  return -std::log(evaluate(values));
59  }
60 
61  /* ************************************************************************ */
63  return error(values.discrete());
64  }
65 
66  /* ************************************************************************ */
68  const DiscreteFactor::shared_ptr& f) const {
70  if (auto tf = std::dynamic_pointer_cast<TableFactor>(f)) {
71  // If f is a TableFactor, we convert `this` to a TableFactor since this
72  // conversion is cheaper than converting `f` to a DecisionTreeFactor. We
73  // then return a TableFactor.
74  result = std::make_shared<TableFactor>((*tf) * TableFactor(*this));
75 
76  } else if (auto dtf = std::dynamic_pointer_cast<DecisionTreeFactor>(f)) {
77  // If `f` is a DecisionTreeFactor, simply call operator*.
78  result = std::make_shared<DecisionTreeFactor>(this->operator*(*dtf));
79 
80  } else {
81  // Simulate double dispatch in C++
82  // Useful for other classes which inherit from DiscreteFactor and have
83  // only `operator*(DecisionTreeFactor)` defined. Thus, other classes don't
84  // need to be updated.
85  result = std::make_shared<DecisionTreeFactor>(f->operator*(*this));
86  }
87  return result;
88  }
89 
90  /* ************************************************************************ */
92  const DiscreteFactor::shared_ptr& f) const {
93  if (auto tf = std::dynamic_pointer_cast<TableFactor>(f)) {
94  // Check if `f` is a TableFactor. If yes, then
95  // convert `this` to a TableFactor which is cheaper.
96  return std::make_shared<TableFactor>(tf->operator/(TableFactor(*this)));
97 
98  } else if (auto dtf = std::dynamic_pointer_cast<DecisionTreeFactor>(f)) {
99  // If `f` is a DecisionTreeFactor, divide normally.
100  return std::make_shared<DecisionTreeFactor>(this->operator/(*dtf));
101 
102  } else {
103  // Else, convert `f` to a DecisionTreeFactor so we can divide
104  return std::make_shared<DecisionTreeFactor>(
105  this->operator/(f->toDecisionTreeFactor()));
106  }
107  }
108 
109  /* ************************************************************************ */
110  double DecisionTreeFactor::safe_div(const double& a, const double& b) {
111  // The use for safe_div is when we divide the product factor by the sum
112  // factor. If the product or sum is zero, we accord zero probability to the
113  // event.
114  return (a == 0 || b == 0) ? 0 : (a / b);
115  }
116 
117  /* ************************************************************************ */
118  void DecisionTreeFactor::print(const string& s,
119  const KeyFormatter& formatter) const {
120  cout << s;
121  cout << " f[";
122  for (auto&& key : keys()) {
123  cout << " (" << formatter(key) << "," << cardinality(key) << "),";
124  }
125  cout << " ]" << endl;
126  ADT::print("", formatter);
127  }
128 
129  /* ************************************************************************ */
131  // apply operand
132  ADT result = ADT::apply(op);
133  // Make a new factor
135  }
136 
137  /* ************************************************************************ */
139  // apply operand
140  ADT result = ADT::apply(op);
141  // Make a new factor
143  }
144 
145  /* ************************************************************************ */
147  Binary op) const {
148  map<Key, size_t> cs; // new cardinalities
149  // make unique key-cardinality map
150  for (Key j : keys()) cs[j] = cardinality(j);
151  for (Key j : f.keys()) cs[j] = f.cardinality(j);
152  // Convert map into keys
154  keys.reserve(cs.size());
155  for (const auto& key : cs) {
156  keys.emplace_back(key);
157  }
158  // apply operand
159  ADT result = ADT::apply(f, op);
160  // Make a new factor
161  return DecisionTreeFactor(keys, result);
162  }
163 
164  /* ************************************************************************ */
166  Binary op) const {
167  if (nrFrontals > size()) {
168  throw invalid_argument(
169  "DecisionTreeFactor::combine: invalid number of frontal "
170  "keys " +
171  std::to_string(nrFrontals) + ", nr.keys=" + std::to_string(size()));
172  }
173 
174  // sum over nrFrontals keys
175  size_t i;
176  ADT result(*this);
177  for (i = 0; i < nrFrontals; i++) {
178  Key j = keys_[i];
179  result = result.combine(j, cardinality(j), op);
180  }
181 
182  // Create new factor, note we start with keys after nrFrontals:
183  DiscreteKeys dkeys;
184  for (; i < keys_.size(); i++) {
185  Key j = keys_[i];
186  dkeys.push_back(DiscreteKey(j, cardinality(j)));
187  }
188  return std::make_shared<DecisionTreeFactor>(dkeys, result);
189  }
190 
191  /* ************************************************************************ */
193  const Ordering& frontalKeys, Binary op) const {
194  if (frontalKeys.size() > size()) {
195  throw invalid_argument(
196  "DecisionTreeFactor::combine: invalid number of frontal "
197  "keys " +
198  std::to_string(frontalKeys.size()) + ", nr.keys=" +
199  std::to_string(size()));
200  }
201 
202  // sum over nrFrontals keys
203  size_t i;
204  ADT result(*this);
205  for (i = 0; i < frontalKeys.size(); i++) {
206  Key j = frontalKeys[i];
207  result = result.combine(j, cardinality(j), op);
208  }
209 
210  /*
211  Create new factor, note we collect keys that are not in frontalKeys.
212 
213  Due to branch merging, the labels in `result` may be missing some keys.
214  E.g. After branch merging, we may get a ADT like:
215  Leaf [2] 1.0204082
216 
217  Hence, code below traverses the original keys and omits those in
218  frontalKeys. We loop over cardinalities, which is O(n) even for a map, and
219  then "contains" is a binary search on a small vector.
220  */
221  DiscreteKeys dkeys;
222  for (auto&& [key, cardinality] : cardinalities_) {
223  if (!frontalKeys.contains(key)) {
224  dkeys.push_back(DiscreteKey(key, cardinality));
225  }
226  }
227  return std::make_shared<DecisionTreeFactor>(dkeys, result);
228  }
229 
230  /* ************************************************************************ */
231  std::vector<std::pair<DiscreteValues, double>> DecisionTreeFactor::enumerate()
232  const {
233  // Get all possible assignments
234  DiscreteKeys pairs = discreteKeys();
235  // Reverse to make cartesian product output a more natural ordering.
236  DiscreteKeys rpairs(pairs.rbegin(), pairs.rend());
237  const auto assignments = DiscreteValues::CartesianProduct(rpairs);
238 
239  // Construct unordered_map with values
240  std::vector<std::pair<DiscreteValues, double>> result;
241  for (const auto& assignment : assignments) {
242  result.emplace_back(assignment, evaluate(assignment));
243  }
244  return result;
245  }
246 
247  /* ************************************************************************ */
248  std::vector<double> DecisionTreeFactor::probabilities() const {
249  // Set of all keys
250  std::set<Key> allKeys(keys().begin(), keys().end());
251 
252  std::vector<double> probs;
253 
254  /* An operation that takes each leaf probability, and computes the
255  * nrAssignments by checking the difference between the keys in the factor
256  * and the keys in the assignment.
257  * The nrAssignments is then used to append
258  * the correct number of leaf probability values to the `probs` vector
259  * defined above.
260  */
261  auto op = [&](const Assignment<Key>& a, double p) {
262  // Get all the keys in the current assignment
263  std::set<Key> assignment_keys;
264  for (auto&& [k, _] : a) {
265  assignment_keys.insert(k);
266  }
267 
268  // Find the keys missing in the assignment
269  std::vector<Key> diff;
270  std::set_difference(allKeys.begin(), allKeys.end(),
271  assignment_keys.begin(), assignment_keys.end(),
272  std::back_inserter(diff));
273 
274  // Compute the total number of assignments in the (pruned) subtree
275  size_t nrAssignments = 1;
276  for (auto&& k : diff) {
277  nrAssignments *= cardinalities_.at(k);
278  }
279  // Add p `nrAssignments` times to the probs vector.
280  probs.insert(probs.end(), nrAssignments, p);
281 
282  return p;
283  };
284 
285  // Go through the tree
286  this->visitWith(op);
287 
288  return probs;
289  }
290 
291  /* ************************************************************************ */
292  static std::string valueFormatter(const double& v) {
293  std::stringstream ss;
294  ss << std::setw(4) << std::setprecision(2) << std::fixed << v;
295  return ss.str();
296  }
297 
299  void DecisionTreeFactor::dot(std::ostream& os,
300  const KeyFormatter& keyFormatter,
301  bool showZero) const {
302  ADT::dot(os, keyFormatter, valueFormatter, showZero);
303  }
304 
306  void DecisionTreeFactor::dot(const std::string& name,
307  const KeyFormatter& keyFormatter,
308  bool showZero) const {
309  ADT::dot(name, keyFormatter, valueFormatter, showZero);
310  }
311 
313  std::string DecisionTreeFactor::dot(const KeyFormatter& keyFormatter,
314  bool showZero) const {
315  return ADT::dot(keyFormatter, valueFormatter, showZero);
316  }
317 
318  // Print out header.
319  /* ************************************************************************ */
320  string DecisionTreeFactor::markdown(const KeyFormatter& keyFormatter,
321  const Names& names) const {
322  stringstream ss;
323 
324  // Print out header.
325  ss << "|";
326  for (auto& key : keys()) {
327  ss << keyFormatter(key) << "|";
328  }
329  ss << "value|\n";
330 
331  // Print out separator with alignment hints.
332  ss << "|";
333  for (size_t j = 0; j < size(); j++) ss << ":-:|";
334  ss << ":-:|\n";
335 
336  // Print out all rows.
337  auto rows = enumerate();
338  for (const auto& kv : rows) {
339  ss << "|";
340  auto assignment = kv.first;
341  for (auto& key : keys()) {
342  size_t index = assignment.at(key);
343  ss << DiscreteValues::Translate(names, key, index) << "|";
344  }
345  ss << kv.second << "|\n";
346  }
347  return ss.str();
348  }
349 
350  /* ************************************************************************ */
351  string DecisionTreeFactor::html(const KeyFormatter& keyFormatter,
352  const Names& names) const {
353  stringstream ss;
354 
355  // Print out preamble.
356  ss << "<div>\n<table class='DecisionTreeFactor'>\n <thead>\n";
357 
358  // Print out header row.
359  ss << " <tr>";
360  for (auto& key : keys()) {
361  ss << "<th>" << keyFormatter(key) << "</th>";
362  }
363  ss << "<th>value</th></tr>\n";
364 
365  // Finish header and start body.
366  ss << " </thead>\n <tbody>\n";
367 
368  // Print out all rows.
369  auto rows = enumerate();
370  for (const auto& kv : rows) {
371  ss << " <tr>";
372  auto assignment = kv.first;
373  for (auto& key : keys()) {
374  size_t index = assignment.at(key);
375  ss << "<th>" << DiscreteValues::Translate(names, key, index) << "</th>";
376  }
377  ss << "<td>" << kv.second << "</td>"; // value
378  ss << "</tr>\n";
379  }
380  ss << " </tbody>\n</table>\n</div>";
381  return ss.str();
382  }
383 
384  /* ************************************************************************ */
386  const vector<double>& table)
387  : DiscreteFactor(keys.indices(), keys.cardinalities()),
389 
390  /* ************************************************************************ */
392  const string& table)
393  : DiscreteFactor(keys.indices(), keys.cardinalities()),
395 
400  class MinHeap {
401  std::vector<double> v_;
402 
403  public:
405  MinHeap() {}
406 
408  void push(double x) {
409  v_.push_back(x);
410  std::push_heap(v_.begin(), v_.end(), std::greater<double>{});
411  }
412 
414  void push(double x, size_t n) {
415  for (size_t i = 0; i < n; ++i) {
416  v_.push_back(x);
417  std::push_heap(v_.begin(), v_.end(), std::greater<double>{});
418  }
419  }
420 
422  double pop() {
423  std::pop_heap(v_.begin(), v_.end(), std::greater<double>{});
424  double x = v_.back();
425  v_.pop_back();
426  return x;
427  }
428 
430  double top() { return v_.at(0); }
431 
437  void print(const std::string& s = "") {
438  std::cout << (s.empty() ? "" : s + " ");
439  for (size_t i = 0; i < v_.size(); i++) {
440  std::cout << v_.at(i);
441  if (v_.size() > 1 && i < v_.size() - 1) std::cout << ", ";
442  }
443  std::cout << std::endl;
444  }
445 
447  bool empty() const { return v_.empty(); }
448 
450  size_t size() const { return v_.size(); }
451  };
452 
453  /* ************************************************************************ */
454  double DecisionTreeFactor::computeThreshold(const size_t N) const {
455  // Set of all keys
456  std::set<Key> allKeys = this->labels();
457  MinHeap min_heap;
458 
459  auto op = [&](const Assignment<Key>& a, double p) {
460  // Get all the keys in the current assignment
461  std::set<Key> assignment_keys;
462  for (auto&& [k, _] : a) {
463  assignment_keys.insert(k);
464  }
465 
466  // Find the keys missing in the assignment
467  std::vector<Key> diff;
468  std::set_difference(allKeys.begin(), allKeys.end(),
469  assignment_keys.begin(), assignment_keys.end(),
470  std::back_inserter(diff));
471 
472  // Compute the total number of assignments in the (pruned) subtree
473  size_t nrAssignments = 1;
474  for (auto&& k : diff) {
475  nrAssignments *= cardinalities_.at(k);
476  }
477 
478  // If min-heap is empty, fill it initially.
479  // This is because there is nothing at the top.
480  if (min_heap.empty()) {
481  min_heap.push(p, std::min(nrAssignments, N));
482 
483  } else {
484  for (size_t i = 0; i < std::min(nrAssignments, N); ++i) {
485  // If p is larger than the smallest element,
486  // then we insert into the min heap.
487  // We check against the top each time because the
488  // heap maintains the smallest element at the top.
489  if (p > min_heap.top()) {
490  if (min_heap.size() == N) {
491  min_heap.pop();
492  }
493  min_heap.push(p);
494  } else {
495  // p is <= min value so move to the next one
496  break;
497  }
498  }
499  }
500  return p;
501  };
502  this->visitWith(op);
503 
504  return min_heap.top();
505  }
506 
507  /* ************************************************************************ */
508  DecisionTreeFactor DecisionTreeFactor::prune(size_t maxNrAssignments) const {
509  const size_t N = maxNrAssignments;
510 
511  double threshold = computeThreshold(N);
512 
513  // Now threshold the decision tree
514  size_t total = 0;
515  auto thresholdFunc = [threshold, &total, N](const double& value) {
516  // There is a possible case where the `threshold` is equal to 0.0
517  // In that case `(value < threshold) == false`
518  // which increases the leaf total erroneously.
519  // Hence we check for 0.0 explicitly.
520  if (fpEqual(value, 0.0, 1e-12)) {
521  return 0.0;
522  }
523 
524  // Check if value is less than the threshold and
525  // we haven't exceeded the maximum number of leaves.
526  if (value < threshold || total >= N) {
527  return 0.0;
528  } else {
529  total += 1;
530  return value;
531  }
532  };
533  DecisionTree<Key, double> thresholded(*this, thresholdFunc);
534 
535  // Create pruned decision tree factor and return.
536  return DecisionTreeFactor(this->discreteKeys(), thresholded);
537  }
538 
539  /* ************************************************************************ */
540 } // namespace gtsam
gtsam::TableFactor
Definition: TableFactor.h:54
name
Annotation for function names.
Definition: attr.h:51
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:45
gtsam::HybridValues
Definition: HybridValues.h:37
gtsam::MinHeap
Min-Heap class to help with pruning. The top element is always the smallest value.
Definition: DecisionTreeFactor.cpp:400
gtsam::DecisionTreeFactor::DecisionTreeFactor
DecisionTreeFactor()
Definition: DecisionTreeFactor.cpp:33
gtsam::MinHeap::push
void push(double x)
Push value onto the heap.
Definition: DecisionTreeFactor.cpp:408
gtsam::DecisionTreeFactor::computeThreshold
double computeThreshold(const size_t N) const
Compute the probability value which is the threshold above which only N leaves are present.
Definition: DecisionTreeFactor.cpp:454
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::DecisionTreeFactor::dot
void dot(std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, bool showZero=true) const
Definition: DecisionTreeFactor.cpp:299
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::DiscreteFactor::cardinalities_
std::map< Key, size_t > cardinalities_
Map of Keys and their cardinalities.
Definition: DiscreteFactor.h:57
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::DecisionTreeFactor::apply
DecisionTreeFactor apply(Unary op) const
Definition: DecisionTreeFactor.cpp:130
gtsam::DecisionTree< Key, double >::labels
std::set< Key > labels() const
Definition: DecisionTree-inl.h:959
gtsam::DecisionTreeFactor::prune
DecisionTreeFactor prune(size_t maxNrAssignments) const
Prune the decision tree of discrete variables.
Definition: DecisionTreeFactor.cpp:508
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::DecisionTreeFactor::error
double error(const DiscreteValues &values) const override
Calculate error for DiscreteValues x, is -log(probability).
Definition: DecisionTreeFactor.cpp:57
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
log
const EIGEN_DEVICE_FUNC LogReturnType log() const
Definition: ArrayCwiseUnaryOps.h:128
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
gtsam::AlgebraicDecisionTree< Key >::equals
bool equals(const AlgebraicDecisionTree &other, double tol=1e-9) const
Equality method customized to value type double.
Definition: AlgebraicDecisionTree.h:263
gtsam::MinHeap::pop
double pop()
Pop the top value of the heap.
Definition: DecisionTreeFactor.cpp:422
DiscreteConditional.h
os
ofstream os("timeSchurFactors.csv")
gtsam::Factor::begin
const_iterator begin() const
Definition: Factor.h:146
gtsam::DecisionTreeFactor::shared_ptr
std::shared_ptr< DecisionTreeFactor > shared_ptr
Definition: DecisionTreeFactor.h:51
result
Values result
Definition: OdometryOptimize.cpp:8
rows
int rows
Definition: Tutorial_commainit_02.cpp:1
gtsam::MinHeap::print
void print(const std::string &s="")
Print the heap as a sequence.
Definition: DecisionTreeFactor.cpp:437
gtsam::AlgebraicDecisionTree< Key >
test_eigen_tensor.indices
indices
Definition: test_eigen_tensor.py:33
ss
static std::stringstream ss
Definition: testBTree.cpp:31
gtsam::MinHeap::v_
std::vector< double > v_
Definition: DecisionTreeFactor.cpp:401
n
int n
Definition: BiCGSTAB_simple.cpp:1
FastSet.h
A thin wrapper around std::set that uses boost's fast_pool_allocator.
table
ArrayXXf table(10, 4)
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::DiscreteValues::CartesianProduct
static std::vector< DiscreteValues > CartesianProduct(const DiscreteKeys &keys)
Return a vector of DiscreteValues, one for each possible combination of values.
Definition: DiscreteValues.h:85
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::MinHeap::empty
bool empty() const
Return true if heap is empty.
Definition: DecisionTreeFactor.cpp:447
gtsam::DecisionTreeFactor::equals
bool equals(const DiscreteFactor &other, double tol=1e-9) const override
equality
Definition: DecisionTreeFactor.cpp:46
gtsam::DecisionTreeFactor::multiply
virtual DiscreteFactor::shared_ptr multiply(const DiscreteFactor::shared_ptr &f) const override
Multiply factors, DiscreteFactor::shared_ptr edition.
Definition: DecisionTreeFactor.cpp:67
gtsam::fpEqual
bool fpEqual(double a, double b, double tol, bool check_relative_also)
Definition: Vector.cpp:42
gtsam::DecisionTree< Key, double >::dot
void dot(std::ostream &os, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter, bool showZero=true) const
Definition: DecisionTree-inl.h:1061
gtsam::DecisionTreeFactor::print
void print(const std::string &s="DecisionTreeFactor:\n", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
Definition: DecisionTreeFactor.cpp:118
gtsam::Assignment< Key >
gtsam::DecisionTree< Key, double >::visitWith
void visitWith(Func f) const
Visit all leaves in depth-first fashion.
Definition: DecisionTree-inl.h:922
gtsam::DecisionTreeFactor::evaluate
virtual double evaluate(const Assignment< Key > &values) const override
Definition: DecisionTreeFactor.h:140
gtsam::DecisionTree< Key, double >::apply
DecisionTree apply(const Unary &op) const
Definition: DecisionTree-inl.h:1000
gtsam::Factor::end
const_iterator end() const
Definition: Factor.h:149
TableFactor.h
gtsam::DecisionTreeFactor::operator/
DecisionTreeFactor operator/(const DecisionTreeFactor &f) const
Divide by factor f (safely). Division of a factor by another factor results in a function which inv...
Definition: DecisionTreeFactor.h:183
gtsam::DiscreteFactor::Binary
std::function< double(const double, const double)> Binary
Definition: DiscreteFactor.h:53
key
const gtsam::Symbol key('X', 0)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::DecisionTree< Key, double >
gtsam::MinHeap::top
double top()
Return the top value of the heap without popping it.
Definition: DecisionTreeFactor.cpp:430
gtsam::DiscreteFactor::cardinality
size_t cardinality(Key j) const
Definition: DiscreteFactor.h:99
process_shonan_timing_results.names
dictionary names
Definition: process_shonan_timing_results.py:175
gtsam::b
const G & b
Definition: Group.h:79
gtsam::DiscreteConditional
Definition: DiscreteConditional.h:37
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::DecisionTreeFactor::combine
shared_ptr combine(size_t nrFrontals, Binary op) const
Definition: DecisionTreeFactor.cpp:165
gtsam
traits
Definition: SFMdata.h:40
gtsam::Factor::keys_
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:88
gtsam::DiscreteFactor::shared_ptr
std::shared_ptr< DiscreteFactor > shared_ptr
shared_ptr to this class
Definition: DiscreteFactor.h:45
gtsam::DiscreteFactor::Names
DiscreteValues::Names Names
Translation table from values to strings.
Definition: DiscreteFactor.h:172
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
gtsam::AlgebraicDecisionTree< Key >::print
void print(const std::string &s="", const typename Base::LabelFormatter &labelFormatter=&DefaultFormatter) const
print method customized to value type double.
Definition: AlgebraicDecisionTree.h:251
gtsam::Factor::keys
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:143
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std
Definition: BFloat16.h:88
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::DecisionTreeFactor::html
std::string html(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as html table.
Definition: DecisionTreeFactor.cpp:351
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::DecisionTreeFactor::enumerate
std::vector< std::pair< DiscreteValues, double > > enumerate() const
Enumerate all values into a map from values to double.
Definition: DecisionTreeFactor.cpp:231
min
#define min(a, b)
Definition: datatypes.h:19
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::DiscreteFactor::discreteKeys
DiscreteKeys discreteKeys() const
Return all the discrete keys associated with this factor.
Definition: DiscreteFactor.cpp:37
N
#define N
Definition: igam.h:9
gtsam::DiscreteFactor
Definition: DiscreteFactor.h:40
gtsam::MinHeap::MinHeap
MinHeap()
Default constructor.
Definition: DecisionTreeFactor.cpp:405
gtsam::DiscreteFactor::UnaryAssignment
std::function< double(const Assignment< Key > &, const double &)> UnaryAssignment
Definition: DiscreteFactor.h:52
gtsam::DiscreteValues::Translate
static std::string Translate(const Names &names, Key key, size_t index)
Translate an integer index value for given key to a string.
Definition: DiscreteValues.cpp:78
gtsam::valueFormatter
static std::string valueFormatter(const double &v)
Definition: DecisionTreeFactor.cpp:292
gtsam::Factor::size
size_t size() const
Definition: Factor.h:160
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
_
constexpr descr< N - 1 > _(char const (&text)[N])
Definition: descr.h:109
gtsam::DiscreteFactor::Unary
std::function< double(const double &)> Unary
Definition: DiscreteFactor.h:50
HybridValues.h
gtsam::Ordering
Definition: inference/Ordering.h:33
DecisionTreeFactor.h
gtsam::DecisionTreeFactor::markdown
std::string markdown(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as markdown table.
Definition: DecisionTreeFactor.cpp:320
gtsam::Ordering::contains
bool contains(const Key &key) const
Check if key exists in ordering.
Definition: Ordering.cpp:304
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::MinHeap::push
void push(double x, size_t n)
Push value x, n number of times.
Definition: DecisionTreeFactor.cpp:414
gtsam::DecisionTreeFactor::probabilities
std::vector< double > probabilities() const
Get all the probabilities in order of assignment values.
Definition: DecisionTreeFactor.cpp:248
gtsam::DecisionTreeFactor::safe_div
static double safe_div(const double &a, const double &b)
Definition: DecisionTreeFactor.cpp:110
gtsam::MinHeap::size
size_t size() const
Return the size of the heap.
Definition: DecisionTreeFactor.cpp:450
gtsam::DiscreteFactor::equals
virtual bool equals(const DiscreteFactor &lf, double tol=1e-9) const
equals
Definition: DiscreteFactor.cpp:32


gtsam
Author(s):
autogenerated on Tue Jan 7 2025 04:02:08