TableFactor.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 
19 #include <gtsam/base/FastSet.h>
24 
25 #include <utility>
26 
27 using namespace std;
28 
29 namespace gtsam {
30 
31 /* ************************************************************************ */
32 TableFactor::TableFactor() {}
33 
34 /* ************************************************************************ */
35 TableFactor::TableFactor(const DiscreteKeys& dkeys,
36  const TableFactor& potentials)
37  : DiscreteFactor(dkeys.indices(), dkeys.cardinalities()) {
38  sparse_table_ = potentials.sparse_table_;
39  denominators_ = potentials.denominators_;
41  sort(sorted_dkeys_.begin(), sorted_dkeys_.end());
42 }
43 
44 /* ************************************************************************ */
47  : DiscreteFactor(dkeys.indices(), dkeys.cardinalities()),
48  sparse_table_(table.size()) {
50  double denom = table.size();
51  for (const DiscreteKey& dkey : dkeys) {
52  denom /= dkey.second;
53  denominators_.insert(std::pair<Key, double>(dkey.first, denom));
54  }
56  sort(sorted_dkeys_.begin(), sorted_dkeys_.end());
57 }
58 
59 /* ************************************************************************ */
61  const DecisionTree<Key, double>& dtree)
62  : TableFactor(dkeys, DecisionTreeFactor(dkeys, dtree)) {}
63 
73 std::vector<double> ComputeLeafOrdering(const DiscreteKeys& dkeys,
74  const DecisionTreeFactor& dt) {
75  std::vector<double> probs = dt.probabilities();
76  std::vector<double> ordered;
77 
78  size_t n = dkeys[0].second;
79 
80  for (size_t k = 0; k < n; ++k) {
81  for (size_t idx = 0; idx < probs.size(); ++idx) {
82  if (idx % n == k) {
83  ordered.push_back(probs[idx]);
84  }
85  }
86  }
87  return ordered;
88 }
89 
90 /* ************************************************************************ */
92  const DecisionTreeFactor& dtf)
93  : TableFactor(dkeys, ComputeLeafOrdering(dkeys, dtf)) {}
94 
95 /* ************************************************************************ */
97  : TableFactor(c.discreteKeys(), c) {}
98 
99 /* ************************************************************************ */
101  const std::vector<double>& table) {
102  Eigen::SparseVector<double> sparse_table(table.size());
103  // Count number of nonzero elements in table and reserve the space.
104  const uint64_t nnz = std::count_if(table.begin(), table.end(),
105  [](uint64_t i) { return i != 0; });
106  sparse_table.reserve(nnz);
107  for (uint64_t i = 0; i < table.size(); i++) {
108  if (table[i] != 0) sparse_table.insert(i) = table[i];
109  }
110  sparse_table.pruned();
111  sparse_table.data().squeeze();
112  return sparse_table;
113 }
114 
115 /* ************************************************************************ */
117  // Convert string to doubles.
118  std::vector<double> ys;
119  std::istringstream iss(table);
120  std::copy(std::istream_iterator<double>(iss), std::istream_iterator<double>(),
121  std::back_inserter(ys));
122  return Convert(ys);
123 }
124 
125 /* ************************************************************************ */
126 bool TableFactor::equals(const DiscreteFactor& other, double tol) const {
127  if (!dynamic_cast<const TableFactor*>(&other)) {
128  return false;
129  } else {
130  const auto& f(static_cast<const TableFactor&>(other));
131  return sparse_table_.isApprox(f.sparse_table_, tol);
132  }
133 }
134 
135 /* ************************************************************************ */
137  // a b c d => D * (C * (B * (a) + b) + c) + d
138  uint64_t idx = 0, card = 1;
139  for (auto it = sorted_dkeys_.rbegin(); it != sorted_dkeys_.rend(); ++it) {
140  if (values.find(it->first) != values.end()) {
141  idx += card * values.at(it->first);
142  }
143  card *= it->second;
144  }
145  return sparse_table_.coeff(idx);
146 }
147 
148 /* ************************************************************************ */
150  // a b c d => D * (C * (B * (a) + b) + c) + d
151  uint64_t idx = 0, card = 1;
152  for (auto it = keys_.rbegin(); it != keys_.rend(); ++it) {
153  if (values.find(*it) != values.end()) {
154  idx += card * values.at(*it);
155  }
156  card *= cardinality(*it);
157  }
158  return sparse_table_.coeff(idx);
159 }
160 
161 /* ************************************************************************ */
163  return -log(evaluate(values));
164 }
165 
166 /* ************************************************************************ */
167 double TableFactor::error(const HybridValues& values) const {
168  return error(values.discrete());
169 }
170 
171 /* ************************************************************************ */
173  return toDecisionTreeFactor() * f;
174 }
175 
176 /* ************************************************************************ */
178  DiscreteKeys dkeys = discreteKeys();
179  std::vector<double> table;
180  for (auto i = 0; i < sparse_table_.size(); i++) {
181  table.push_back(sparse_table_.coeff(i));
182  }
183  DecisionTreeFactor f(dkeys, table);
184  return f;
185 }
186 
187 /* ************************************************************************ */
189  DiscreteKeys parent_keys) const {
190  if (parent_keys.empty()) return *this;
191 
192  // Unique representation of parent values.
193  uint64_t unique = 0;
194  uint64_t card = 1;
195  for (auto it = keys_.rbegin(); it != keys_.rend(); ++it) {
196  if (parent_assign.find(*it) != parent_assign.end()) {
197  unique += parent_assign.at(*it) * card;
198  card *= cardinality(*it);
199  }
200  }
201 
202  // Find child DiscreteKeys
203  DiscreteKeys child_dkeys;
204  std::sort(parent_keys.begin(), parent_keys.end());
205  std::set_difference(sorted_dkeys_.begin(), sorted_dkeys_.end(),
206  parent_keys.begin(), parent_keys.end(),
207  std::back_inserter(child_dkeys));
208 
209  // Create child sparse table to populate.
210  uint64_t child_card = 1;
211  for (const DiscreteKey& child_dkey : child_dkeys)
212  child_card *= child_dkey.second;
213  Eigen::SparseVector<double> child_sparse_table_(child_card);
214  child_sparse_table_.reserve(child_card);
215 
216  // Populate child sparse table.
217  for (SparseIt it(sparse_table_); it; ++it) {
218  // Create unique representation of parent keys
219  uint64_t parent_unique = uniqueRep(parent_keys, it.index());
220  // Populate the table
221  if (parent_unique == unique) {
222  uint64_t idx = uniqueRep(child_dkeys, it.index());
223  child_sparse_table_.insert(idx) = it.value();
224  }
225  }
226 
227  child_sparse_table_.pruned();
228  child_sparse_table_.data().squeeze();
229  return TableFactor(child_dkeys, child_sparse_table_);
230 }
231 
232 /* ************************************************************************ */
233 double TableFactor::safe_div(const double& a, const double& b) {
234  // The use for safe_div is when we divide the product factor by the sum
235  // factor. If the product or sum is zero, we accord zero probability to the
236  // event.
237  return (a == 0 || b == 0) ? 0 : (a / b);
238 }
239 
240 /* ************************************************************************ */
241 void TableFactor::print(const string& s, const KeyFormatter& formatter) const {
242  cout << s;
243  cout << " f[";
244  for (auto&& key : keys())
245  cout << " (" << formatter(key) << "," << cardinality(key) << "),";
246  cout << " ]" << endl;
247  for (SparseIt it(sparse_table_); it; ++it) {
248  DiscreteValues assignment = findAssignments(it.index());
249  for (auto&& kv : assignment) {
250  cout << "(" << formatter(kv.first) << ", " << kv.second << ")";
251  }
252  cout << " | " << it.value() << " | " << it.index() << endl;
253  }
254  cout << "number of nnzs: " << sparse_table_.nonZeros() << endl;
255 }
256 
257 /* ************************************************************************ */
259  // Initialize new factor.
260  uint64_t cardi = 1;
261  for (auto [key, c] : cardinalities_) cardi *= c;
262  Eigen::SparseVector<double> sparse_table(cardi);
263  sparse_table.reserve(sparse_table_.nonZeros());
264 
265  // Populate
266  for (SparseIt it(sparse_table_); it; ++it) {
267  sparse_table.coeffRef(it.index()) = op(it.value());
268  }
269 
270  // Free unused memory and return.
271  sparse_table.pruned();
272  sparse_table.data().squeeze();
273  return TableFactor(discreteKeys(), sparse_table);
274 }
275 
276 /* ************************************************************************ */
278  // Initialize new factor.
279  uint64_t cardi = 1;
280  for (auto [key, c] : cardinalities_) cardi *= c;
281  Eigen::SparseVector<double> sparse_table(cardi);
282  sparse_table.reserve(sparse_table_.nonZeros());
283 
284  // Populate
285  for (SparseIt it(sparse_table_); it; ++it) {
286  DiscreteValues assignment = findAssignments(it.index());
287  sparse_table.coeffRef(it.index()) = op(assignment, it.value());
288  }
289 
290  // Free unused memory and return.
291  sparse_table.pruned();
292  sparse_table.data().squeeze();
293  return TableFactor(discreteKeys(), sparse_table);
294 }
295 
296 /* ************************************************************************ */
298  if (keys_.empty() && sparse_table_.nonZeros() == 0)
299  return f;
300  else if (f.keys_.empty() && f.sparse_table_.nonZeros() == 0)
301  return *this;
302  // 1. Identify keys for contract and free modes.
303  DiscreteKeys contract_dkeys = contractDkeys(f);
304  DiscreteKeys f_free_dkeys = f.freeDkeys(*this);
305  DiscreteKeys union_dkeys = unionDkeys(f);
306  // 2. Create hash table for input factor f
307  unordered_map<uint64_t, AssignValList> map_f =
308  f.createMap(contract_dkeys, f_free_dkeys);
309  // 3. Initialize multiplied factor.
310  uint64_t card = 1;
311  for (auto u_dkey : union_dkeys) card *= u_dkey.second;
312  Eigen::SparseVector<double> mult_sparse_table(card);
313  mult_sparse_table.reserve(card);
314  // 3. Multiply.
315  for (SparseIt it(sparse_table_); it; ++it) {
316  uint64_t contract_unique = uniqueRep(contract_dkeys, it.index());
317  if (map_f.find(contract_unique) == map_f.end()) continue;
318  for (auto assignVal : map_f[contract_unique]) {
319  uint64_t union_idx = unionRep(union_dkeys, assignVal.first, it.index());
320  mult_sparse_table.insert(union_idx) = op(it.value(), assignVal.second);
321  }
322  }
323  // 4. Free unused memory.
324  mult_sparse_table.pruned();
325  mult_sparse_table.data().squeeze();
326  // 5. Create union keys and return.
327  return TableFactor(union_dkeys, mult_sparse_table);
328 }
329 
330 /* ************************************************************************ */
332  // Find contract modes.
333  DiscreteKeys contract;
334  set_intersection(sorted_dkeys_.begin(), sorted_dkeys_.end(),
335  f.sorted_dkeys_.begin(), f.sorted_dkeys_.end(),
336  back_inserter(contract));
337  return contract;
338 }
339 
340 /* ************************************************************************ */
342  // Find free modes.
343  DiscreteKeys free;
344  set_difference(sorted_dkeys_.begin(), sorted_dkeys_.end(),
345  f.sorted_dkeys_.begin(), f.sorted_dkeys_.end(),
346  back_inserter(free));
347  return free;
348 }
349 
350 /* ************************************************************************ */
352  // Find union modes.
353  DiscreteKeys union_dkeys;
354  set_union(sorted_dkeys_.begin(), sorted_dkeys_.end(), f.sorted_dkeys_.begin(),
355  f.sorted_dkeys_.end(), back_inserter(union_dkeys));
356  return union_dkeys;
357 }
358 
359 /* ************************************************************************ */
361  const DiscreteValues& f_free,
362  const uint64_t idx) const {
363  uint64_t union_idx = 0, card = 1;
364  for (auto it = union_keys.rbegin(); it != union_keys.rend(); it++) {
365  if (f_free.find(it->first) == f_free.end()) {
366  union_idx += keyValueForIndex(it->first, idx) * card;
367  } else {
368  union_idx += f_free.at(it->first) * card;
369  }
370  card *= it->second;
371  }
372  return union_idx;
373 }
374 
375 /* ************************************************************************ */
376 unordered_map<uint64_t, TableFactor::AssignValList> TableFactor::createMap(
377  const DiscreteKeys& contract, const DiscreteKeys& free) const {
378  // 1. Initialize map.
379  unordered_map<uint64_t, AssignValList> map_f;
380  // 2. Iterate over nonzero elements.
381  for (SparseIt it(sparse_table_); it; ++it) {
382  // 3. Create unique representation of contract modes.
383  uint64_t unique_rep = uniqueRep(contract, it.index());
384  // 4. Create assignment for free modes.
385  DiscreteValues free_assignments;
386  for (auto& key : free)
387  free_assignments[key.first] = keyValueForIndex(key.first, it.index());
388  // 5. Populate map.
389  if (map_f.find(unique_rep) == map_f.end()) {
390  map_f[unique_rep] = {make_pair(free_assignments, it.value())};
391  } else {
392  map_f[unique_rep].push_back(make_pair(free_assignments, it.value()));
393  }
394  }
395  return map_f;
396 }
397 
398 /* ************************************************************************ */
400  const uint64_t idx) const {
401  if (dkeys.empty()) return 0;
402  uint64_t unique_rep = 0, card = 1;
403  for (auto it = dkeys.rbegin(); it != dkeys.rend(); it++) {
404  unique_rep += keyValueForIndex(it->first, idx) * card;
405  card *= it->second;
406  }
407  return unique_rep;
408 }
409 
410 /* ************************************************************************ */
411 uint64_t TableFactor::uniqueRep(const DiscreteValues& assignments) const {
412  if (assignments.empty()) return 0;
413  uint64_t unique_rep = 0, card = 1;
414  for (auto it = assignments.rbegin(); it != assignments.rend(); it++) {
415  unique_rep += it->second * card;
416  card *= cardinalities_.at(it->first);
417  }
418  return unique_rep;
419 }
420 
421 /* ************************************************************************ */
423  DiscreteValues assignment;
424  for (Key key : keys_) {
425  assignment[key] = keyValueForIndex(key, idx);
426  }
427  return assignment;
428 }
429 
430 /* ************************************************************************ */
432  Binary op) const {
433  if (nrFrontals > size()) {
434  throw invalid_argument(
435  "TableFactor::combine: invalid number of frontal "
436  "keys " +
437  to_string(nrFrontals) + ", nr.keys=" + std::to_string(size()));
438  }
439  // Find remaining keys.
440  DiscreteKeys remain_dkeys;
441  uint64_t card = 1;
442  for (auto i = nrFrontals; i < keys_.size(); i++) {
443  remain_dkeys.push_back(discreteKey(i));
444  card *= cardinality(keys_[i]);
445  }
446  // Create combined table.
447  Eigen::SparseVector<double> combined_table(card);
448  combined_table.reserve(sparse_table_.nonZeros());
449  // Populate combined table.
450  for (SparseIt it(sparse_table_); it; ++it) {
451  uint64_t idx = uniqueRep(remain_dkeys, it.index());
452  double new_val = op(combined_table.coeff(idx), it.value());
453  combined_table.coeffRef(idx) = new_val;
454  }
455  // Free unused memory.
456  combined_table.pruned();
457  combined_table.data().squeeze();
458  return std::make_shared<TableFactor>(remain_dkeys, combined_table);
459 }
460 
461 /* ************************************************************************ */
463  Binary op) const {
464  if (frontalKeys.size() > size()) {
465  throw invalid_argument(
466  "TableFactor::combine: invalid number of frontal "
467  "keys " +
468  std::to_string(frontalKeys.size()) +
469  ", nr.keys=" + std::to_string(size()));
470  }
471  // Find remaining keys.
472  DiscreteKeys remain_dkeys;
473  uint64_t card = 1;
474  for (Key key : keys_) {
475  if (std::find(frontalKeys.begin(), frontalKeys.end(), key) ==
476  frontalKeys.end()) {
477  remain_dkeys.emplace_back(key, cardinality(key));
478  card *= cardinality(key);
479  }
480  }
481  // Create combined table.
482  Eigen::SparseVector<double> combined_table(card);
483  combined_table.reserve(sparse_table_.nonZeros());
484  // Populate combined table.
485  for (SparseIt it(sparse_table_); it; ++it) {
486  uint64_t idx = uniqueRep(remain_dkeys, it.index());
487  double new_val = op(combined_table.coeff(idx), it.value());
488  combined_table.coeffRef(idx) = new_val;
489  }
490  // Free unused memory.
491  combined_table.pruned();
492  combined_table.data().squeeze();
493  return std::make_shared<TableFactor>(remain_dkeys, combined_table);
494 }
495 
496 /* ************************************************************************ */
497 size_t TableFactor::keyValueForIndex(Key target_key, uint64_t index) const {
498  // http://phrogz.net/lazy-cartesian-product
499  return (index / denominators_.at(target_key)) % cardinality(target_key);
500 }
501 
502 /* ************************************************************************ */
503 std::vector<std::pair<DiscreteValues, double>> TableFactor::enumerate() const {
504  // Get all possible assignments
505  std::vector<std::pair<Key, size_t>> pairs = discreteKeys();
506  // Reverse to make cartesian product output a more natural ordering.
507  std::vector<std::pair<Key, size_t>> rpairs(pairs.rbegin(), pairs.rend());
508  const auto assignments = DiscreteValues::CartesianProduct(rpairs);
509  // Construct unordered_map with values
510  std::vector<std::pair<DiscreteValues, double>> result;
511  for (const auto& assignment : assignments) {
512  result.emplace_back(assignment, operator()(assignment));
513  }
514  return result;
515 }
516 
517 // Print out header.
518 /* ************************************************************************ */
519 string TableFactor::markdown(const KeyFormatter& keyFormatter,
520  const Names& names) const {
521  stringstream ss;
522 
523  // Print out header.
524  ss << "|";
525  for (auto& key : keys()) {
526  ss << keyFormatter(key) << "|";
527  }
528  ss << "value|\n";
529 
530  // Print out separator with alignment hints.
531  ss << "|";
532  for (size_t j = 0; j < size(); j++) ss << ":-:|";
533  ss << ":-:|\n";
534 
535  // Print out all rows.
536  for (SparseIt it(sparse_table_); it; ++it) {
537  DiscreteValues assignment = findAssignments(it.index());
538  ss << "|";
539  for (auto& key : keys()) {
540  size_t index = assignment.at(key);
541  ss << DiscreteValues::Translate(names, key, index) << "|";
542  }
543  ss << it.value() << "|\n";
544  }
545  return ss.str();
546 }
547 
548 /* ************************************************************************ */
549 string TableFactor::html(const KeyFormatter& keyFormatter,
550  const Names& names) const {
551  stringstream ss;
552 
553  // Print out preamble.
554  ss << "<div>\n<table class='TableFactor'>\n <thead>\n";
555 
556  // Print out header row.
557  ss << " <tr>";
558  for (auto& key : keys()) {
559  ss << "<th>" << keyFormatter(key) << "</th>";
560  }
561  ss << "<th>value</th></tr>\n";
562 
563  // Finish header and start body.
564  ss << " </thead>\n <tbody>\n";
565 
566  // Print out all rows.
567  for (SparseIt it(sparse_table_); it; ++it) {
568  DiscreteValues assignment = findAssignments(it.index());
569  ss << " <tr>";
570  for (auto& key : keys()) {
571  size_t index = assignment.at(key);
572  ss << "<th>" << DiscreteValues::Translate(names, key, index) << "</th>";
573  }
574  ss << "<td>" << it.value() << "</td>"; // value
575  ss << "</tr>\n";
576  }
577  ss << " </tbody>\n</table>\n</div>";
578  return ss.str();
579 }
580 
581 /* ************************************************************************ */
582 TableFactor TableFactor::prune(size_t maxNrAssignments) const {
583  const size_t N = maxNrAssignments;
584 
585  // Get the probabilities in the TableFactor so we can threshold.
586  vector<pair<Eigen::Index, double>> probabilities;
587 
588  // Store non-zero probabilities along with their indices in a vector.
589  for (SparseIt it(sparse_table_); it; ++it) {
590  probabilities.emplace_back(it.index(), it.value());
591  }
592 
593  // The number of probabilities can be lower than max_leaves.
594  if (probabilities.size() <= N) return *this;
595 
596  // Sort the vector in descending order based on the element values.
597  sort(probabilities.begin(), probabilities.end(),
598  [](const std::pair<Eigen::Index, double>& a,
599  const std::pair<Eigen::Index, double>& b) {
600  return a.second > b.second;
601  });
602 
603  // Keep the largest N probabilities in the vector.
604  if (probabilities.size() > N) probabilities.resize(N);
605 
606  // Create pruned sparse vector.
607  Eigen::SparseVector<double> pruned_vec(sparse_table_.size());
608  pruned_vec.reserve(probabilities.size());
609 
610  // Populate pruned sparse vector.
611  for (const auto& prob : probabilities) {
612  pruned_vec.insert(prob.first) = prob.second;
613  }
614 
615  // Create pruned decision tree factor and return.
616  return TableFactor(this->discreteKeys(), pruned_vec);
617 }
618 
619 /* ************************************************************************ */
620 } // namespace gtsam
gtsam::TableFactor::markdown
std::string markdown(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as markdown table.
Definition: TableFactor.cpp:519
gtsam::TableFactor
Definition: TableFactor.h:46
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:44
gtsam::HybridValues
Definition: HybridValues.h:37
gtsam::TableFactor::choose
TableFactor choose(const DiscreteValues assignments, DiscreteKeys parent_keys) const
Create a TableFactor that is a subset of this TableFactor.
Definition: TableFactor.cpp:188
s
RealScalar s
Definition: level1_cplx_impl.h:126
Eigen::SparseVector::reserve
void reserve(Index reserveSize)
Definition: SparseVector.h:204
gtsam::TableFactor::sparse_table_
Eigen::SparseVector< double > sparse_table_
SparseVector of nonzero probabilities.
Definition: TableFactor.h:49
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:51
dt
const double dt
Definition: testVelocityConstraint.cpp:15
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::TableFactor::uniqueRep
uint64_t uniqueRep(const DiscreteKeys &keys, const uint64_t idx) const
Create unique representation.
Definition: TableFactor.cpp:399
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
DiscreteConditional.h
gtsam::TableFactor::contractDkeys
DiscreteKeys contractDkeys(const TableFactor &f) const
Definition: TableFactor.cpp:331
gtsam::TableFactor::keyValueForIndex
size_t keyValueForIndex(Key target_key, uint64_t index) const
Uses lazy cartesian product to find nth entry in the cartesian product of arrays in O(1) Example) v0 ...
Definition: TableFactor.cpp:497
result
Values result
Definition: OdometryOptimize.cpp:8
Eigen::SparseCompressedBase::InnerIterator
Definition: SparseCompressedBase.h:158
gtsam::TableFactor::enumerate
std::vector< std::pair< DiscreteValues, double > > enumerate() const
Enumerate all values into a map from values to double.
Definition: TableFactor.cpp:503
test_eigen_tensor.indices
indices
Definition: test_eigen_tensor.py:33
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
ss
static std::stringstream ss
Definition: testBTree.cpp:31
gtsam::TableFactor::unionRep
uint64_t unionRep(const DiscreteKeys &keys, const DiscreteValues &assign, const uint64_t idx) const
Create unique representation of union modes.
Definition: TableFactor.cpp:360
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::TableFactor::findValue
double findValue(const DiscreteValues &values) const
Find value for corresponding DiscreteValues.
Definition: TableFactor.cpp:149
FastSet.h
A thin wrapper around std::set that uses boost's fast_pool_allocator.
Eigen::SparseVector::nonZeros
Index nonZeros() const
Definition: SparseVector.h:140
gtsam::TableFactor::sorted_dkeys_
DiscreteKeys sorted_dkeys_
Sorted DiscreteKeys to use internally.
Definition: TableFactor.h:55
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::TableFactor::findAssignments
DiscreteValues findAssignments(const uint64_t idx) const
Find DiscreteValues for corresponding index.
Definition: TableFactor.cpp:422
gtsam::TableFactor::prune
TableFactor prune(size_t maxNrAssignments) const
Prune the decision tree of discrete variables.
Definition: TableFactor.cpp:582
gtsam::TableFactor::html
std::string html(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as html table.
Definition: TableFactor.cpp:549
gtsam::TableFactor::createMap
std::unordered_map< uint64_t, AssignValList > createMap(const DiscreteKeys &contract, const DiscreteKeys &free) const
Definition: TableFactor.cpp:376
TableFactor.h
gtsam::TableFactor::Convert
static Eigen::SparseVector< double > Convert(const std::vector< double > &table)
Definition: TableFactor.cpp:100
gtsam::TableFactor::combine
shared_ptr combine(size_t nrFrontals, Binary op) const
Definition: TableFactor.cpp:431
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::DiscreteFactor::cardinality
size_t cardinality(Key j) const
Definition: DiscreteFactor.h:93
process_shonan_timing_results.names
dictionary names
Definition: process_shonan_timing_results.py:175
gtsam::TableFactor::Binary
std::function< double(const double, const double)> Binary
Definition: TableFactor.h:99
gtsam::b
const G & b
Definition: Group.h:79
gtsam::DiscreteConditional
Definition: DiscreteConditional.h:37
gtsam::TableFactor::error
double error(const DiscreteValues &values) const override
Calculate error for DiscreteValues x, is -log(probability).
Definition: TableFactor.cpp:162
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::TableFactor::Unary
std::function< double(const double &)> Unary
Definition: TableFactor.h:96
gtsam::TableFactor::UnaryAssignment
std::function< double(const Assignment< Key > &, const double &)> UnaryAssignment
Definition: TableFactor.h:98
gtsam::Symbol::index
std::uint64_t index() const
Definition: inference/Symbol.h:80
gtsam::TableFactor::operator*
TableFactor operator*(const TableFactor &f) const
multiply two TableFactors
Definition: TableFactor.h:185
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:121
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
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
Eigen::SparseVector< double >
std
Definition: BFloat16.h:88
gtsam::TableFactor::safe_div
static double safe_div(const double &a, const double &b)
Definition: TableFactor.cpp:233
gtsam::TableFactor::freeDkeys
DiscreteKeys freeDkeys(const TableFactor &f) const
Return keys in free mode which are the dimensions not involved in the contraction operation.
Definition: TableFactor.cpp:341
gtsam::TableFactor::denominators_
std::map< Key, size_t > denominators_
Map of Keys and their denominators used in keyValueForIndex.
Definition: TableFactor.h:53
gtsam::TableFactor::evaluate
double evaluate(const DiscreteValues &values) const
Definition: TableFactor.h:174
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::TableFactor::equals
bool equals(const DiscreteFactor &other, double tol=1e-9) const override
equality
Definition: TableFactor.cpp:126
gtsam::TableFactor::discreteKey
DiscreteKey discreteKey(size_t i) const
Return ith key in keys_ as a DiscreteKey.
Definition: TableFactor.h:78
gtsam::TableFactor::apply
TableFactor apply(Unary op) const
Definition: TableFactor.cpp:258
gtsam::TableFactor::print
void print(const std::string &s="TableFactor:\n", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
Definition: TableFactor.cpp:241
gtsam::DiscreteFactor::discreteKeys
DiscreteKeys discreteKeys() const
Return all the discrete keys associated with this factor.
Definition: DiscreteFactor.cpp:32
uint64_t
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
N
#define N
Definition: igam.h:9
gtsam::DiscreteFactor
Definition: DiscreteFactor.h:39
gtsam::TableFactor::unionDkeys
DiscreteKeys unionDkeys(const TableFactor &f) const
Return union of DiscreteKeys in two factors.
Definition: TableFactor.cpp:351
gtsam::TableFactor::operator()
double operator()(const DiscreteValues &values) const override
Evaluate probability distribution, sugar.
Definition: TableFactor.cpp:136
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::TableFactor::TableFactor
TableFactor()
Definition: TableFactor.cpp:32
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
HybridValues.h
gtsam::Ordering
Definition: inference/Ordering.h:33
Eigen::SparseVector::coeffRef
Scalar & coeffRef(Index row, Index col)
Definition: SparseVector.h:113
DecisionTreeFactor.h
Eigen::SparseVector::data
Storage & data()
Definition: SparseVector.h:98
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
Eigen::internal::CompressedStorage::squeeze
void squeeze()
Definition: CompressedStorage.h:83
gtsam::TableFactor::shared_ptr
std::shared_ptr< TableFactor > shared_ptr
Definition: TableFactor.h:93
gtsam::TableFactor::toDecisionTreeFactor
DecisionTreeFactor toDecisionTreeFactor() const override
Convert into a decisiontree.
Definition: TableFactor.cpp:177
Eigen::SparseVector::insert
Scalar & insert(Index row, Index col)
Definition: SparseVector.h:172
Eigen::SparseVector::coeff
Scalar coeff(Index row, Index col) const
Definition: SparseVector.h:102
gtsam::ComputeLeafOrdering
std::vector< double > ComputeLeafOrdering(const DiscreteKeys &dkeys, const DecisionTreeFactor &dt)
Compute the correct ordering of the leaves in the decision tree.
Definition: TableFactor.cpp:73


gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:36:55