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().errorTree();
174 }
175 
176 /* ************************************************************************ */
178  return toDecisionTreeFactor() * f;
179 }
180 
181 /* ************************************************************************ */
183  DiscreteKeys dkeys = discreteKeys();
184  std::vector<double> table;
185  for (auto i = 0; i < sparse_table_.size(); i++) {
186  table.push_back(sparse_table_.coeff(i));
187  }
188  DecisionTreeFactor f(dkeys, table);
189  return f;
190 }
191 
192 /* ************************************************************************ */
194  DiscreteKeys parent_keys) const {
195  if (parent_keys.empty()) return *this;
196 
197  // Unique representation of parent values.
198  uint64_t unique = 0;
199  uint64_t card = 1;
200  for (auto it = keys_.rbegin(); it != keys_.rend(); ++it) {
201  if (parent_assign.find(*it) != parent_assign.end()) {
202  unique += parent_assign.at(*it) * card;
203  card *= cardinality(*it);
204  }
205  }
206 
207  // Find child DiscreteKeys
208  DiscreteKeys child_dkeys;
209  std::sort(parent_keys.begin(), parent_keys.end());
210  std::set_difference(sorted_dkeys_.begin(), sorted_dkeys_.end(),
211  parent_keys.begin(), parent_keys.end(),
212  std::back_inserter(child_dkeys));
213 
214  // Create child sparse table to populate.
215  uint64_t child_card = 1;
216  for (const DiscreteKey& child_dkey : child_dkeys)
217  child_card *= child_dkey.second;
218  Eigen::SparseVector<double> child_sparse_table_(child_card);
219  child_sparse_table_.reserve(child_card);
220 
221  // Populate child sparse table.
222  for (SparseIt it(sparse_table_); it; ++it) {
223  // Create unique representation of parent keys
224  uint64_t parent_unique = uniqueRep(parent_keys, it.index());
225  // Populate the table
226  if (parent_unique == unique) {
227  uint64_t idx = uniqueRep(child_dkeys, it.index());
228  child_sparse_table_.insert(idx) = it.value();
229  }
230  }
231 
232  child_sparse_table_.pruned();
233  child_sparse_table_.data().squeeze();
234  return TableFactor(child_dkeys, child_sparse_table_);
235 }
236 
237 /* ************************************************************************ */
238 double TableFactor::safe_div(const double& a, const double& b) {
239  // The use for safe_div is when we divide the product factor by the sum
240  // factor. If the product or sum is zero, we accord zero probability to the
241  // event.
242  return (a == 0 || b == 0) ? 0 : (a / b);
243 }
244 
245 /* ************************************************************************ */
246 void TableFactor::print(const string& s, const KeyFormatter& formatter) const {
247  cout << s;
248  cout << " f[";
249  for (auto&& key : keys())
250  cout << " (" << formatter(key) << "," << cardinality(key) << "),";
251  cout << " ]" << endl;
252  for (SparseIt it(sparse_table_); it; ++it) {
253  DiscreteValues assignment = findAssignments(it.index());
254  for (auto&& kv : assignment) {
255  cout << "(" << formatter(kv.first) << ", " << kv.second << ")";
256  }
257  cout << " | " << it.value() << " | " << it.index() << endl;
258  }
259  cout << "number of nnzs: " << sparse_table_.nonZeros() << endl;
260 }
261 
262 /* ************************************************************************ */
264  // Initialize new factor.
265  uint64_t cardi = 1;
266  for (auto [key, c] : cardinalities_) cardi *= c;
267  Eigen::SparseVector<double> sparse_table(cardi);
268  sparse_table.reserve(sparse_table_.nonZeros());
269 
270  // Populate
271  for (SparseIt it(sparse_table_); it; ++it) {
272  sparse_table.coeffRef(it.index()) = op(it.value());
273  }
274 
275  // Free unused memory and return.
276  sparse_table.pruned();
277  sparse_table.data().squeeze();
278  return TableFactor(discreteKeys(), sparse_table);
279 }
280 
281 /* ************************************************************************ */
283  // Initialize new factor.
284  uint64_t cardi = 1;
285  for (auto [key, c] : cardinalities_) cardi *= c;
286  Eigen::SparseVector<double> sparse_table(cardi);
287  sparse_table.reserve(sparse_table_.nonZeros());
288 
289  // Populate
290  for (SparseIt it(sparse_table_); it; ++it) {
291  DiscreteValues assignment = findAssignments(it.index());
292  sparse_table.coeffRef(it.index()) = op(assignment, it.value());
293  }
294 
295  // Free unused memory and return.
296  sparse_table.pruned();
297  sparse_table.data().squeeze();
298  return TableFactor(discreteKeys(), sparse_table);
299 }
300 
301 /* ************************************************************************ */
303  if (keys_.empty() && sparse_table_.nonZeros() == 0)
304  return f;
305  else if (f.keys_.empty() && f.sparse_table_.nonZeros() == 0)
306  return *this;
307  // 1. Identify keys for contract and free modes.
308  DiscreteKeys contract_dkeys = contractDkeys(f);
309  DiscreteKeys f_free_dkeys = f.freeDkeys(*this);
310  DiscreteKeys union_dkeys = unionDkeys(f);
311  // 2. Create hash table for input factor f
312  unordered_map<uint64_t, AssignValList> map_f =
313  f.createMap(contract_dkeys, f_free_dkeys);
314  // 3. Initialize multiplied factor.
315  uint64_t card = 1;
316  for (auto u_dkey : union_dkeys) card *= u_dkey.second;
317  Eigen::SparseVector<double> mult_sparse_table(card);
318  mult_sparse_table.reserve(card);
319  // 3. Multiply.
320  for (SparseIt it(sparse_table_); it; ++it) {
321  uint64_t contract_unique = uniqueRep(contract_dkeys, it.index());
322  if (map_f.find(contract_unique) == map_f.end()) continue;
323  for (auto assignVal : map_f[contract_unique]) {
324  uint64_t union_idx = unionRep(union_dkeys, assignVal.first, it.index());
325  mult_sparse_table.insert(union_idx) = op(it.value(), assignVal.second);
326  }
327  }
328  // 4. Free unused memory.
329  mult_sparse_table.pruned();
330  mult_sparse_table.data().squeeze();
331  // 5. Create union keys and return.
332  return TableFactor(union_dkeys, mult_sparse_table);
333 }
334 
335 /* ************************************************************************ */
337  // Find contract modes.
338  DiscreteKeys contract;
339  set_intersection(sorted_dkeys_.begin(), sorted_dkeys_.end(),
340  f.sorted_dkeys_.begin(), f.sorted_dkeys_.end(),
341  back_inserter(contract));
342  return contract;
343 }
344 
345 /* ************************************************************************ */
347  // Find free modes.
348  DiscreteKeys free;
349  set_difference(sorted_dkeys_.begin(), sorted_dkeys_.end(),
350  f.sorted_dkeys_.begin(), f.sorted_dkeys_.end(),
351  back_inserter(free));
352  return free;
353 }
354 
355 /* ************************************************************************ */
357  // Find union modes.
358  DiscreteKeys union_dkeys;
359  set_union(sorted_dkeys_.begin(), sorted_dkeys_.end(), f.sorted_dkeys_.begin(),
360  f.sorted_dkeys_.end(), back_inserter(union_dkeys));
361  return union_dkeys;
362 }
363 
364 /* ************************************************************************ */
366  const DiscreteValues& f_free,
367  const uint64_t idx) const {
368  uint64_t union_idx = 0, card = 1;
369  for (auto it = union_keys.rbegin(); it != union_keys.rend(); it++) {
370  if (f_free.find(it->first) == f_free.end()) {
371  union_idx += keyValueForIndex(it->first, idx) * card;
372  } else {
373  union_idx += f_free.at(it->first) * card;
374  }
375  card *= it->second;
376  }
377  return union_idx;
378 }
379 
380 /* ************************************************************************ */
381 unordered_map<uint64_t, TableFactor::AssignValList> TableFactor::createMap(
382  const DiscreteKeys& contract, const DiscreteKeys& free) const {
383  // 1. Initialize map.
384  unordered_map<uint64_t, AssignValList> map_f;
385  // 2. Iterate over nonzero elements.
386  for (SparseIt it(sparse_table_); it; ++it) {
387  // 3. Create unique representation of contract modes.
388  uint64_t unique_rep = uniqueRep(contract, it.index());
389  // 4. Create assignment for free modes.
390  DiscreteValues free_assignments;
391  for (auto& key : free)
392  free_assignments[key.first] = keyValueForIndex(key.first, it.index());
393  // 5. Populate map.
394  if (map_f.find(unique_rep) == map_f.end()) {
395  map_f[unique_rep] = {make_pair(free_assignments, it.value())};
396  } else {
397  map_f[unique_rep].push_back(make_pair(free_assignments, it.value()));
398  }
399  }
400  return map_f;
401 }
402 
403 /* ************************************************************************ */
405  const uint64_t idx) const {
406  if (dkeys.empty()) return 0;
407  uint64_t unique_rep = 0, card = 1;
408  for (auto it = dkeys.rbegin(); it != dkeys.rend(); it++) {
409  unique_rep += keyValueForIndex(it->first, idx) * card;
410  card *= it->second;
411  }
412  return unique_rep;
413 }
414 
415 /* ************************************************************************ */
416 uint64_t TableFactor::uniqueRep(const DiscreteValues& assignments) const {
417  if (assignments.empty()) return 0;
418  uint64_t unique_rep = 0, card = 1;
419  for (auto it = assignments.rbegin(); it != assignments.rend(); it++) {
420  unique_rep += it->second * card;
421  card *= cardinalities_.at(it->first);
422  }
423  return unique_rep;
424 }
425 
426 /* ************************************************************************ */
428  DiscreteValues assignment;
429  for (Key key : keys_) {
430  assignment[key] = keyValueForIndex(key, idx);
431  }
432  return assignment;
433 }
434 
435 /* ************************************************************************ */
437  Binary op) const {
438  if (nrFrontals > size()) {
439  throw invalid_argument(
440  "TableFactor::combine: invalid number of frontal "
441  "keys " +
442  to_string(nrFrontals) + ", nr.keys=" + std::to_string(size()));
443  }
444  // Find remaining keys.
445  DiscreteKeys remain_dkeys;
446  uint64_t card = 1;
447  for (auto i = nrFrontals; i < keys_.size(); i++) {
448  remain_dkeys.push_back(discreteKey(i));
449  card *= cardinality(keys_[i]);
450  }
451  // Create combined table.
452  Eigen::SparseVector<double> combined_table(card);
453  combined_table.reserve(sparse_table_.nonZeros());
454  // Populate combined table.
455  for (SparseIt it(sparse_table_); it; ++it) {
456  uint64_t idx = uniqueRep(remain_dkeys, it.index());
457  double new_val = op(combined_table.coeff(idx), it.value());
458  combined_table.coeffRef(idx) = new_val;
459  }
460  // Free unused memory.
461  combined_table.pruned();
462  combined_table.data().squeeze();
463  return std::make_shared<TableFactor>(remain_dkeys, combined_table);
464 }
465 
466 /* ************************************************************************ */
468  Binary op) const {
469  if (frontalKeys.size() > size()) {
470  throw invalid_argument(
471  "TableFactor::combine: invalid number of frontal "
472  "keys " +
473  std::to_string(frontalKeys.size()) +
474  ", nr.keys=" + std::to_string(size()));
475  }
476  // Find remaining keys.
477  DiscreteKeys remain_dkeys;
478  uint64_t card = 1;
479  for (Key key : keys_) {
480  if (std::find(frontalKeys.begin(), frontalKeys.end(), key) ==
481  frontalKeys.end()) {
482  remain_dkeys.emplace_back(key, cardinality(key));
483  card *= cardinality(key);
484  }
485  }
486  // Create combined table.
487  Eigen::SparseVector<double> combined_table(card);
488  combined_table.reserve(sparse_table_.nonZeros());
489  // Populate combined table.
490  for (SparseIt it(sparse_table_); it; ++it) {
491  uint64_t idx = uniqueRep(remain_dkeys, it.index());
492  double new_val = op(combined_table.coeff(idx), it.value());
493  combined_table.coeffRef(idx) = new_val;
494  }
495  // Free unused memory.
496  combined_table.pruned();
497  combined_table.data().squeeze();
498  return std::make_shared<TableFactor>(remain_dkeys, combined_table);
499 }
500 
501 /* ************************************************************************ */
502 size_t TableFactor::keyValueForIndex(Key target_key, uint64_t index) const {
503  // http://phrogz.net/lazy-cartesian-product
504  return (index / denominators_.at(target_key)) % cardinality(target_key);
505 }
506 
507 /* ************************************************************************ */
508 std::vector<std::pair<DiscreteValues, double>> TableFactor::enumerate() const {
509  // Get all possible assignments
510  std::vector<std::pair<Key, size_t>> pairs = discreteKeys();
511  // Reverse to make cartesian product output a more natural ordering.
512  std::vector<std::pair<Key, size_t>> rpairs(pairs.rbegin(), pairs.rend());
513  const auto assignments = DiscreteValues::CartesianProduct(rpairs);
514  // Construct unordered_map with values
515  std::vector<std::pair<DiscreteValues, double>> result;
516  for (const auto& assignment : assignments) {
517  result.emplace_back(assignment, operator()(assignment));
518  }
519  return result;
520 }
521 
522 // Print out header.
523 /* ************************************************************************ */
524 string TableFactor::markdown(const KeyFormatter& keyFormatter,
525  const Names& names) const {
526  stringstream ss;
527 
528  // Print out header.
529  ss << "|";
530  for (auto& key : keys()) {
531  ss << keyFormatter(key) << "|";
532  }
533  ss << "value|\n";
534 
535  // Print out separator with alignment hints.
536  ss << "|";
537  for (size_t j = 0; j < size(); j++) ss << ":-:|";
538  ss << ":-:|\n";
539 
540  // Print out all rows.
541  for (SparseIt it(sparse_table_); it; ++it) {
542  DiscreteValues assignment = findAssignments(it.index());
543  ss << "|";
544  for (auto& key : keys()) {
545  size_t index = assignment.at(key);
546  ss << DiscreteValues::Translate(names, key, index) << "|";
547  }
548  ss << it.value() << "|\n";
549  }
550  return ss.str();
551 }
552 
553 /* ************************************************************************ */
554 string TableFactor::html(const KeyFormatter& keyFormatter,
555  const Names& names) const {
556  stringstream ss;
557 
558  // Print out preamble.
559  ss << "<div>\n<table class='TableFactor'>\n <thead>\n";
560 
561  // Print out header row.
562  ss << " <tr>";
563  for (auto& key : keys()) {
564  ss << "<th>" << keyFormatter(key) << "</th>";
565  }
566  ss << "<th>value</th></tr>\n";
567 
568  // Finish header and start body.
569  ss << " </thead>\n <tbody>\n";
570 
571  // Print out all rows.
572  for (SparseIt it(sparse_table_); it; ++it) {
573  DiscreteValues assignment = findAssignments(it.index());
574  ss << " <tr>";
575  for (auto& key : keys()) {
576  size_t index = assignment.at(key);
577  ss << "<th>" << DiscreteValues::Translate(names, key, index) << "</th>";
578  }
579  ss << "<td>" << it.value() << "</td>"; // value
580  ss << "</tr>\n";
581  }
582  ss << " </tbody>\n</table>\n</div>";
583  return ss.str();
584 }
585 
586 /* ************************************************************************ */
587 TableFactor TableFactor::prune(size_t maxNrAssignments) const {
588  const size_t N = maxNrAssignments;
589 
590  // Get the probabilities in the TableFactor so we can threshold.
591  vector<pair<Eigen::Index, double>> probabilities;
592 
593  // Store non-zero probabilities along with their indices in a vector.
594  for (SparseIt it(sparse_table_); it; ++it) {
595  probabilities.emplace_back(it.index(), it.value());
596  }
597 
598  // The number of probabilities can be lower than max_leaves.
599  if (probabilities.size() <= N) return *this;
600 
601  // Sort the vector in descending order based on the element values.
602  sort(probabilities.begin(), probabilities.end(),
603  [](const std::pair<Eigen::Index, double>& a,
604  const std::pair<Eigen::Index, double>& b) {
605  return a.second > b.second;
606  });
607 
608  // Keep the largest N probabilities in the vector.
609  if (probabilities.size() > N) probabilities.resize(N);
610 
611  // Create pruned sparse vector.
612  Eigen::SparseVector<double> pruned_vec(sparse_table_.size());
613  pruned_vec.reserve(probabilities.size());
614 
615  // Populate pruned sparse vector.
616  for (const auto& prob : probabilities) {
617  pruned_vec.insert(prob.first) = prob.second;
618  }
619 
620  // Create pruned decision tree factor and return.
621  return TableFactor(this->discreteKeys(), pruned_vec);
622 }
623 
624 /* ************************************************************************ */
625 } // namespace gtsam
gtsam::TableFactor::markdown
std::string markdown(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as markdown table.
Definition: TableFactor.cpp:524
gtsam::TableFactor
Definition: TableFactor.h:46
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:44
gtsam::TableFactor::error
double error(const DiscreteValues &values) const
Calculate error for DiscreteValues x, is -log(probability).
Definition: TableFactor.cpp:162
gtsam::HybridValues
Definition: HybridValues.h:38
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:193
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:404
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::DecisionTreeFactor::errorTree
AlgebraicDecisionTree< Key > errorTree() const override
Compute error for each assignment and return as a tree.
Definition: DecisionTreeFactor.cpp:66
gtsam::TableFactor::contractDkeys
DiscreteKeys contractDkeys(const TableFactor &f) const
Definition: TableFactor.cpp:336
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:502
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:508
gtsam::AlgebraicDecisionTree< Key >
test_eigen_tensor.indices
indices
Definition: test_eigen_tensor.py:31
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:365
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
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
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
gtsam::Values::end
deref_iterator end() const
Definition: Values.h:206
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:427
gtsam::TableFactor::prune
TableFactor prune(size_t maxNrAssignments) const
Prune the decision tree of discrete variables.
Definition: TableFactor.cpp:587
gtsam::TableFactor::html
std::string html(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as html table.
Definition: TableFactor.cpp:554
gtsam::TableFactor::createMap
std::unordered_map< uint64_t, AssignValList > createMap(const DiscreteKeys &contract, const DiscreteKeys &free) const
Definition: TableFactor.cpp:381
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:436
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
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: chartTesting.h:28
gtsam::Factor::keys_
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:87
gtsam::DiscreteFactor::Names
DiscreteValues::Names Names
Translation table from values to strings.
Definition: DiscreteFactor.h:121
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
leaf::values
leaf::MyValues values
gtsam::Factor::keys
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:142
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:238
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:346
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:263
gtsam::TableFactor::print
void print(const std::string &s="TableFactor:\n", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
Definition: TableFactor.cpp:246
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:356
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:159
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::errorTree
AlgebraicDecisionTree< Key > errorTree() const override
Compute error for each assignment and return as a tree.
Definition: TableFactor.cpp:172
gtsam::TableFactor::toDecisionTreeFactor
DecisionTreeFactor toDecisionTreeFactor() const override
Convert into a decisiontree.
Definition: TableFactor.cpp:182
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::Values::find
deref_iterator find(Key j) const
Definition: Values.h:210
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 Thu Jun 13 2024 03:07:02