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>
24 
25 #include <utility>
26 
27 using namespace std;
28 
29 namespace gtsam {
30 
31  /* ************************************************************************ */
32  DecisionTreeFactor::DecisionTreeFactor() {}
33 
34  /* ************************************************************************ */
35  DecisionTreeFactor::DecisionTreeFactor(const DiscreteKeys& keys,
36  const ADT& potentials)
37  : DiscreteFactor(keys.indices(), keys.cardinalities()), ADT(potentials) {}
38 
39  /* ************************************************************************ */
41  : DiscreteFactor(c.keys(), c.cardinalities()),
43 
44  /* ************************************************************************ */
46  double tol) const {
47  if (!dynamic_cast<const DecisionTreeFactor*>(&other)) {
48  return false;
49  } else {
50  const auto& f(static_cast<const DecisionTreeFactor&>(other));
51  return Base::equals(other, tol) && ADT::equals(f, tol);
52  }
53  }
54 
55  /* ************************************************************************ */
57  return -std::log(evaluate(values));
58  }
59 
60  /* ************************************************************************ */
62  return error(values.discrete());
63  }
64 
65  /* ************************************************************************ */
66  double DecisionTreeFactor::safe_div(const double& a, const double& b) {
67  // The use for safe_div is when we divide the product factor by the sum
68  // factor. If the product or sum is zero, we accord zero probability to the
69  // event.
70  return (a == 0 || b == 0) ? 0 : (a / b);
71  }
72 
73  /* ************************************************************************ */
74  void DecisionTreeFactor::print(const string& s,
75  const KeyFormatter& formatter) const {
76  cout << s;
77  cout << " f[";
78  for (auto&& key : keys()) {
79  cout << " (" << formatter(key) << "," << cardinality(key) << "),";
80  }
81  cout << " ]" << endl;
82  ADT::print("", formatter);
83  }
84 
85  /* ************************************************************************ */
87  // apply operand
88  ADT result = ADT::apply(op);
89  // Make a new factor
91  }
92 
93  /* ************************************************************************ */
95  // apply operand
96  ADT result = ADT::apply(op);
97  // Make a new factor
99  }
100 
101  /* ************************************************************************ */
103  Binary op) const {
104  map<Key, size_t> cs; // new cardinalities
105  // make unique key-cardinality map
106  for (Key j : keys()) cs[j] = cardinality(j);
107  for (Key j : f.keys()) cs[j] = f.cardinality(j);
108  // Convert map into keys
110  keys.reserve(cs.size());
111  for (const auto& key : cs) {
112  keys.emplace_back(key);
113  }
114  // apply operand
115  ADT result = ADT::apply(f, op);
116  // Make a new factor
117  return DecisionTreeFactor(keys, result);
118  }
119 
120  /* ************************************************************************ */
122  Binary op) const {
123  if (nrFrontals > size()) {
124  throw invalid_argument(
125  "DecisionTreeFactor::combine: invalid number of frontal "
126  "keys " +
127  std::to_string(nrFrontals) + ", nr.keys=" + std::to_string(size()));
128  }
129 
130  // sum over nrFrontals keys
131  size_t i;
132  ADT result(*this);
133  for (i = 0; i < nrFrontals; i++) {
134  Key j = keys_[i];
135  result = result.combine(j, cardinality(j), op);
136  }
137 
138  // Create new factor, note we start with keys after nrFrontals:
139  DiscreteKeys dkeys;
140  for (; i < keys_.size(); i++) {
141  Key j = keys_[i];
142  dkeys.push_back(DiscreteKey(j, cardinality(j)));
143  }
144  return std::make_shared<DecisionTreeFactor>(dkeys, result);
145  }
146 
147  /* ************************************************************************ */
149  const Ordering& frontalKeys, Binary op) const {
150  if (frontalKeys.size() > size()) {
151  throw invalid_argument(
152  "DecisionTreeFactor::combine: invalid number of frontal "
153  "keys " +
154  std::to_string(frontalKeys.size()) + ", nr.keys=" +
155  std::to_string(size()));
156  }
157 
158  // sum over nrFrontals keys
159  size_t i;
160  ADT result(*this);
161  for (i = 0; i < frontalKeys.size(); i++) {
162  Key j = frontalKeys[i];
163  result = result.combine(j, cardinality(j), op);
164  }
165 
166  /*
167  Create new factor, note we collect keys that are not in frontalKeys.
168 
169  Due to branch merging, the labels in `result` may be missing some keys.
170  E.g. After branch merging, we may get a ADT like:
171  Leaf [2] 1.0204082
172 
173  Hence, code below traverses the original keys and omits those in
174  frontalKeys. We loop over cardinalities, which is O(n) even for a map, and
175  then "contains" is a binary search on a small vector.
176  */
177  DiscreteKeys dkeys;
178  for (auto&& [key, cardinality] : cardinalities_) {
179  if (!frontalKeys.contains(key)) {
180  dkeys.push_back(DiscreteKey(key, cardinality));
181  }
182  }
183  return std::make_shared<DecisionTreeFactor>(dkeys, result);
184  }
185 
186  /* ************************************************************************ */
187  std::vector<std::pair<DiscreteValues, double>> DecisionTreeFactor::enumerate()
188  const {
189  // Get all possible assignments
190  DiscreteKeys pairs = discreteKeys();
191  // Reverse to make cartesian product output a more natural ordering.
192  DiscreteKeys rpairs(pairs.rbegin(), pairs.rend());
193  const auto assignments = DiscreteValues::CartesianProduct(rpairs);
194 
195  // Construct unordered_map with values
196  std::vector<std::pair<DiscreteValues, double>> result;
197  for (const auto& assignment : assignments) {
198  result.emplace_back(assignment, evaluate(assignment));
199  }
200  return result;
201  }
202 
203  /* ************************************************************************ */
204  std::vector<double> DecisionTreeFactor::probabilities() const {
205  // Set of all keys
206  std::set<Key> allKeys(keys().begin(), keys().end());
207 
208  std::vector<double> probs;
209 
210  /* An operation that takes each leaf probability, and computes the
211  * nrAssignments by checking the difference between the keys in the factor
212  * and the keys in the assignment.
213  * The nrAssignments is then used to append
214  * the correct number of leaf probability values to the `probs` vector
215  * defined above.
216  */
217  auto op = [&](const Assignment<Key>& a, double p) {
218  // Get all the keys in the current assignment
219  std::set<Key> assignment_keys;
220  for (auto&& [k, _] : a) {
221  assignment_keys.insert(k);
222  }
223 
224  // Find the keys missing in the assignment
225  std::vector<Key> diff;
226  std::set_difference(allKeys.begin(), allKeys.end(),
227  assignment_keys.begin(), assignment_keys.end(),
228  std::back_inserter(diff));
229 
230  // Compute the total number of assignments in the (pruned) subtree
231  size_t nrAssignments = 1;
232  for (auto&& k : diff) {
233  nrAssignments *= cardinalities_.at(k);
234  }
235  // Add p `nrAssignments` times to the probs vector.
236  probs.insert(probs.end(), nrAssignments, p);
237 
238  return p;
239  };
240 
241  // Go through the tree
242  this->visitWith(op);
243 
244  return probs;
245  }
246 
247  /* ************************************************************************ */
248  static std::string valueFormatter(const double& v) {
249  std::stringstream ss;
250  ss << std::setw(4) << std::setprecision(2) << std::fixed << v;
251  return ss.str();
252  }
253 
255  void DecisionTreeFactor::dot(std::ostream& os,
256  const KeyFormatter& keyFormatter,
257  bool showZero) const {
258  ADT::dot(os, keyFormatter, valueFormatter, showZero);
259  }
260 
262  void DecisionTreeFactor::dot(const std::string& name,
263  const KeyFormatter& keyFormatter,
264  bool showZero) const {
265  ADT::dot(name, keyFormatter, valueFormatter, showZero);
266  }
267 
269  std::string DecisionTreeFactor::dot(const KeyFormatter& keyFormatter,
270  bool showZero) const {
271  return ADT::dot(keyFormatter, valueFormatter, showZero);
272  }
273 
274  // Print out header.
275  /* ************************************************************************ */
276  string DecisionTreeFactor::markdown(const KeyFormatter& keyFormatter,
277  const Names& names) const {
278  stringstream ss;
279 
280  // Print out header.
281  ss << "|";
282  for (auto& key : keys()) {
283  ss << keyFormatter(key) << "|";
284  }
285  ss << "value|\n";
286 
287  // Print out separator with alignment hints.
288  ss << "|";
289  for (size_t j = 0; j < size(); j++) ss << ":-:|";
290  ss << ":-:|\n";
291 
292  // Print out all rows.
293  auto rows = enumerate();
294  for (const auto& kv : rows) {
295  ss << "|";
296  auto assignment = kv.first;
297  for (auto& key : keys()) {
298  size_t index = assignment.at(key);
299  ss << DiscreteValues::Translate(names, key, index) << "|";
300  }
301  ss << kv.second << "|\n";
302  }
303  return ss.str();
304  }
305 
306  /* ************************************************************************ */
307  string DecisionTreeFactor::html(const KeyFormatter& keyFormatter,
308  const Names& names) const {
309  stringstream ss;
310 
311  // Print out preamble.
312  ss << "<div>\n<table class='DecisionTreeFactor'>\n <thead>\n";
313 
314  // Print out header row.
315  ss << " <tr>";
316  for (auto& key : keys()) {
317  ss << "<th>" << keyFormatter(key) << "</th>";
318  }
319  ss << "<th>value</th></tr>\n";
320 
321  // Finish header and start body.
322  ss << " </thead>\n <tbody>\n";
323 
324  // Print out all rows.
325  auto rows = enumerate();
326  for (const auto& kv : rows) {
327  ss << " <tr>";
328  auto assignment = kv.first;
329  for (auto& key : keys()) {
330  size_t index = assignment.at(key);
331  ss << "<th>" << DiscreteValues::Translate(names, key, index) << "</th>";
332  }
333  ss << "<td>" << kv.second << "</td>"; // value
334  ss << "</tr>\n";
335  }
336  ss << " </tbody>\n</table>\n</div>";
337  return ss.str();
338  }
339 
340  /* ************************************************************************ */
342  const vector<double>& table)
343  : DiscreteFactor(keys.indices(), keys.cardinalities()),
345 
346  /* ************************************************************************ */
348  const string& table)
349  : DiscreteFactor(keys.indices(), keys.cardinalities()),
351 
356  class MinHeap {
357  std::vector<double> v_;
358 
359  public:
361  MinHeap() {}
362 
364  void push(double x) {
365  v_.push_back(x);
366  std::push_heap(v_.begin(), v_.end(), std::greater<double>{});
367  }
368 
370  void push(double x, size_t n) {
371  for (size_t i = 0; i < n; ++i) {
372  v_.push_back(x);
373  std::push_heap(v_.begin(), v_.end(), std::greater<double>{});
374  }
375  }
376 
378  double pop() {
379  std::pop_heap(v_.begin(), v_.end(), std::greater<double>{});
380  double x = v_.back();
381  v_.pop_back();
382  return x;
383  }
384 
386  double top() { return v_.at(0); }
387 
393  void print(const std::string& s = "") {
394  std::cout << (s.empty() ? "" : s + " ");
395  for (size_t i = 0; i < v_.size(); i++) {
396  std::cout << v_.at(i);
397  if (v_.size() > 1 && i < v_.size() - 1) std::cout << ", ";
398  }
399  std::cout << std::endl;
400  }
401 
403  bool empty() const { return v_.empty(); }
404 
406  size_t size() const { return v_.size(); }
407  };
408 
409  /* ************************************************************************ */
410  double DecisionTreeFactor::computeThreshold(const size_t N) const {
411  // Set of all keys
412  std::set<Key> allKeys = this->labels();
413  MinHeap min_heap;
414 
415  auto op = [&](const Assignment<Key>& a, double p) {
416  // Get all the keys in the current assignment
417  std::set<Key> assignment_keys;
418  for (auto&& [k, _] : a) {
419  assignment_keys.insert(k);
420  }
421 
422  // Find the keys missing in the assignment
423  std::vector<Key> diff;
424  std::set_difference(allKeys.begin(), allKeys.end(),
425  assignment_keys.begin(), assignment_keys.end(),
426  std::back_inserter(diff));
427 
428  // Compute the total number of assignments in the (pruned) subtree
429  size_t nrAssignments = 1;
430  for (auto&& k : diff) {
431  nrAssignments *= cardinalities_.at(k);
432  }
433 
434  // If min-heap is empty, fill it initially.
435  // This is because there is nothing at the top.
436  if (min_heap.empty()) {
437  min_heap.push(p, std::min(nrAssignments, N));
438 
439  } else {
440  for (size_t i = 0; i < std::min(nrAssignments, N); ++i) {
441  // If p is larger than the smallest element,
442  // then we insert into the min heap.
443  // We check against the top each time because the
444  // heap maintains the smallest element at the top.
445  if (p > min_heap.top()) {
446  if (min_heap.size() == N) {
447  min_heap.pop();
448  }
449  min_heap.push(p);
450  } else {
451  // p is <= min value so move to the next one
452  break;
453  }
454  }
455  }
456  return p;
457  };
458  this->visitWith(op);
459 
460  return min_heap.top();
461  }
462 
463  /* ************************************************************************ */
464  DecisionTreeFactor DecisionTreeFactor::prune(size_t maxNrAssignments) const {
465  const size_t N = maxNrAssignments;
466 
467  double threshold = computeThreshold(N);
468 
469  // Now threshold the decision tree
470  size_t total = 0;
471  auto thresholdFunc = [threshold, &total, N](const double& value) {
472  // There is a possible case where the `threshold` is equal to 0.0
473  // In that case `(value < threshold) == false`
474  // which increases the leaf total erroneously.
475  // Hence we check for 0.0 explicitly.
476  if (fpEqual(value, 0.0, 1e-12)) {
477  return 0.0;
478  }
479 
480  // Check if value is less than the threshold and
481  // we haven't exceeded the maximum number of leaves.
482  if (value < threshold || total >= N) {
483  return 0.0;
484  } else {
485  total += 1;
486  return value;
487  }
488  };
489  DecisionTree<Key, double> thresholded(*this, thresholdFunc);
490 
491  // Create pruned decision tree factor and return.
492  return DecisionTreeFactor(this->discreteKeys(), thresholded);
493  }
494 
495  /* ************************************************************************ */
496 } // namespace gtsam
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:356
gtsam::DecisionTreeFactor::DecisionTreeFactor
DecisionTreeFactor()
Definition: DecisionTreeFactor.cpp:32
gtsam::MinHeap::push
void push(double x)
Push value onto the heap.
Definition: DecisionTreeFactor.cpp:364
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:410
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:255
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:56
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:86
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:464
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:56
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:378
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:393
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:357
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:403
gtsam::DecisionTreeFactor::equals
bool equals(const DiscreteFactor &other, double tol=1e-9) const override
equality
Definition: DecisionTreeFactor.cpp:45
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:74
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
gtsam::DiscreteFactor::Binary
std::function< double(const double, const double)> Binary
Definition: DiscreteFactor.h:52
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:386
gtsam::DiscreteFactor::cardinality
size_t cardinality(Key j) const
Definition: DiscreteFactor.h:98
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:121
gtsam
traits
Definition: SFMdata.h:40
gtsam::Factor::keys_
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:88
gtsam::DiscreteFactor::Names
DiscreteValues::Names Names
Translation table from values to strings.
Definition: DiscreteFactor.h:139
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:307
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:187
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:39
gtsam::MinHeap::MinHeap
MinHeap()
Default constructor.
Definition: DecisionTreeFactor.cpp:361
gtsam::DiscreteFactor::UnaryAssignment
std::function< double(const Assignment< Key > &, const double &)> UnaryAssignment
Definition: DiscreteFactor.h:51
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:248
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:49
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:276
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:370
gtsam::DecisionTreeFactor::probabilities
std::vector< double > probabilities() const
Get all the probabilities in order of assignment values.
Definition: DecisionTreeFactor.cpp:204
gtsam::DecisionTreeFactor::safe_div
static double safe_div(const double &a, const double &b)
Definition: DecisionTreeFactor.cpp:66
gtsam::MinHeap::size
size_t size() const
Return the size of the heap.
Definition: DecisionTreeFactor.cpp:406
gtsam::DiscreteFactor::equals
virtual bool equals(const DiscreteFactor &lf, double tol=1e-9) const
equals
Definition: DiscreteFactor.cpp:32


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:26