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 
76  const DiscreteKeys& dkeys, const DecisionTreeFactor& dt) {
77  // SparseVector needs to know the maximum possible index,
78  // so we compute the product of cardinalities.
79  size_t cardinalityProduct = 1;
80  for (auto&& [_, c] : dt.cardinalities()) {
81  cardinalityProduct *= c;
82  }
83  Eigen::SparseVector<double> sparseTable(cardinalityProduct);
84  size_t nrValues = 0;
85  dt.visit([&nrValues](double x) {
86  if (x > 0) nrValues += 1;
87  });
88  sparseTable.reserve(nrValues);
89 
90  KeySet allKeys(dt.keys().begin(), dt.keys().end());
91 
92  // Compute denominators to be used in computing sparse table indices
93  std::map<Key, size_t> denominators;
94  double denom = sparseTable.size();
95  for (const DiscreteKey& dkey : dkeys) {
96  denom /= dkey.second;
97  denominators.insert(std::pair<Key, double>(dkey.first, denom));
98  }
99 
110  auto op = [&](const Assignment<Key>& assignment, double p) {
111  // Check if greater than 1e-11 because we consider
112  // smaller than that as numerically 0
113  if (p > 1e-11) {
114  // Get all the keys involved in this assignment
115  KeySet assignmentKeys;
116  for (auto&& [k, _] : assignment) {
117  assignmentKeys.insert(k);
118  }
119 
120  // Find the keys missing in the assignment
121  KeyVector diff;
122  std::set_difference(allKeys.begin(), allKeys.end(),
123  assignmentKeys.begin(), assignmentKeys.end(),
124  std::back_inserter(diff));
125 
126  // Generate all assignments using the missing keys
127  DiscreteKeys extras;
128  for (auto&& key : diff) {
129  extras.push_back({key, dt.cardinality(key)});
130  }
131  auto&& extraAssignments = DiscreteValues::CartesianProduct(extras);
132 
133  for (auto&& extra : extraAssignments) {
134  // Create new assignment using the extra assignment
135  DiscreteValues updatedAssignment(assignment);
136  updatedAssignment.insert(extra);
137 
138  // Generate index and add to the sparse vector.
139  Eigen::Index idx = 0;
140  // We go in reverse since a DecisionTree has the highest label first
141  for (auto&& it = updatedAssignment.rbegin();
142  it != updatedAssignment.rend(); it++) {
143  idx += it->second * denominators.at(it->first);
144  }
145  sparseTable.coeffRef(idx) = p;
146  }
147  }
148  };
149 
150  // Visit each leaf in `dt` to get the Assignment and leaf value
151  // to populate the sparseTable.
152  dt.visitWith(op);
153 
154  return sparseTable;
155 }
156 
157 /* ************************************************************************ */
159  const DecisionTreeFactor& dtf)
160  : TableFactor(dkeys, ComputeSparseTable(dkeys, dtf)) {}
161 
162 /* ************************************************************************ */
164  : TableFactor(dtf.discreteKeys(), dtf) {}
165 
166 /* ************************************************************************ */
168  : TableFactor(c.discreteKeys(), c) {}
169 
170 /* ************************************************************************ */
172  const DiscreteKeys& keys, const std::vector<double>& table) {
173  size_t max_size = 1;
174  for (auto&& [_, cardinality] : keys.cardinalities()) {
175  max_size *= cardinality;
176  }
177  if (table.size() != max_size) {
178  throw std::runtime_error(
179  "The cardinalities of the keys don't match the number of values in the "
180  "input.");
181  }
182 
183  Eigen::SparseVector<double> sparse_table(table.size());
184  // Count number of nonzero elements in table and reserve the space.
185  const uint64_t nnz = std::count_if(table.begin(), table.end(),
186  [](uint64_t i) { return i != 0; });
187  sparse_table.reserve(nnz);
188  for (uint64_t i = 0; i < table.size(); i++) {
189  if (table[i] != 0) sparse_table.insert(i) = table[i];
190  }
191  sparse_table.pruned();
192  sparse_table.data().squeeze();
193  return sparse_table;
194 }
195 
196 /* ************************************************************************ */
198  const std::string& table) {
199  // Convert string to doubles.
200  std::vector<double> ys;
201  std::istringstream iss(table);
202  std::copy(std::istream_iterator<double>(iss), std::istream_iterator<double>(),
203  std::back_inserter(ys));
204  return Convert(keys, ys);
205 }
206 
207 /* ************************************************************************ */
208 bool TableFactor::equals(const DiscreteFactor& other, double tol) const {
209  if (!dynamic_cast<const TableFactor*>(&other)) {
210  return false;
211  } else {
212  const auto& f(static_cast<const TableFactor&>(other));
213  return Base::equals(other, tol) &&
214  sparse_table_.isApprox(f.sparse_table_, tol);
215  }
216 }
217 
218 /* ************************************************************************ */
220  // a b c d => D * (C * (B * (a) + b) + c) + d
221  uint64_t idx = 0, card = 1;
222  for (auto it = sorted_dkeys_.rbegin(); it != sorted_dkeys_.rend(); ++it) {
223  if (values.find(it->first) != values.end()) {
224  idx += card * values.at(it->first);
225  }
226  card *= it->second;
227  }
228  return sparse_table_.coeff(idx);
229 }
230 
231 /* ************************************************************************ */
233  // a b c d => D * (C * (B * (a) + b) + c) + d
234  uint64_t idx = 0, card = 1;
235  for (auto it = keys_.rbegin(); it != keys_.rend(); ++it) {
236  if (values.find(*it) != values.end()) {
237  idx += card * values.at(*it);
238  }
239  card *= cardinality(*it);
240  }
241  return sparse_table_.coeff(idx);
242 }
243 
244 /* ************************************************************************ */
246  return -log(evaluate(values));
247 }
248 
249 /* ************************************************************************ */
250 double TableFactor::error(const HybridValues& values) const {
251  return error(values.discrete());
252 }
253 
254 /* ************************************************************************ */
256  return toDecisionTreeFactor() * f;
257 }
258 
259 /* ************************************************************************ */
261  const DiscreteFactor::shared_ptr& f) const {
263  if (auto tf = std::dynamic_pointer_cast<TableFactor>(f)) {
264  // If `f` is a TableFactor, we can simply call `operator*`.
265  result = std::make_shared<TableFactor>(this->operator*(*tf));
266 
267  } else if (auto dtf = std::dynamic_pointer_cast<DecisionTreeFactor>(f)) {
268  // If `f` is a DecisionTreeFactor, we convert to a TableFactor which is
269  // cheaper than converting `this` to a DecisionTreeFactor.
270  result = std::make_shared<TableFactor>(this->operator*(TableFactor(*dtf)));
271 
272  } else {
273  // Simulate double dispatch in C++
274  // Useful for other classes which inherit from DiscreteFactor and have
275  // only `operator*(DecisionTreeFactor)` defined. Thus, other classes don't
276  // need to be updated to know about TableFactor.
277  // Those classes can be specialized to use TableFactor
278  // if efficiency is a problem.
279  result = std::make_shared<DecisionTreeFactor>(
280  f->operator*(this->toDecisionTreeFactor()));
281  }
282  return result;
283 }
284 
285 /* ************************************************************************ */
287  const DiscreteFactor::shared_ptr& f) const {
288  if (auto tf = std::dynamic_pointer_cast<TableFactor>(f)) {
289  return std::make_shared<TableFactor>(this->operator/(*tf));
290  } else if (auto dtf = std::dynamic_pointer_cast<DecisionTreeFactor>(f)) {
291  return std::make_shared<TableFactor>(
292  this->operator/(TableFactor(f->discreteKeys(), *dtf)));
293  } else {
294  TableFactor divisor(f->toDecisionTreeFactor());
295  return std::make_shared<TableFactor>(this->operator/(divisor));
296  }
297 }
298 
299 /* ************************************************************************ */
301  DiscreteKeys dkeys = discreteKeys();
302 
303  // If no keys, then return empty DecisionTreeFactor
304  if (dkeys.size() == 0) {
306  // We can have an empty sparse_table_ or one with a single value.
307  if (sparse_table_.size() != 0) {
309  }
310  return DecisionTreeFactor(dkeys, tree);
311  }
312 
313  std::vector<double> table(sparse_table_.size(), 0.0);
314  for (SparseIt it(sparse_table_); it; ++it) {
315  table[it.index()] = it.value();
316  }
317 
319  DecisionTreeFactor f(dkeys, tree);
320  return f;
321 }
322 
323 /* ************************************************************************ */
325  DiscreteKeys parent_keys) const {
326  if (parent_keys.empty()) return *this;
327 
328  // Unique representation of parent values.
329  uint64_t unique = 0;
330  uint64_t card = 1;
331  for (auto it = keys_.rbegin(); it != keys_.rend(); ++it) {
332  if (parent_assign.find(*it) != parent_assign.end()) {
333  unique += parent_assign.at(*it) * card;
334  card *= cardinality(*it);
335  }
336  }
337 
338  // Find child DiscreteKeys
339  DiscreteKeys child_dkeys;
340  std::sort(parent_keys.begin(), parent_keys.end());
341  std::set_difference(sorted_dkeys_.begin(), sorted_dkeys_.end(),
342  parent_keys.begin(), parent_keys.end(),
343  std::back_inserter(child_dkeys));
344 
345  // Create child sparse table to populate.
346  uint64_t child_card = 1;
347  for (const DiscreteKey& child_dkey : child_dkeys)
348  child_card *= child_dkey.second;
349  Eigen::SparseVector<double> child_sparse_table_(child_card);
350  child_sparse_table_.reserve(child_card);
351 
352  // Populate child sparse table.
353  for (SparseIt it(sparse_table_); it; ++it) {
354  // Create unique representation of parent keys
355  uint64_t parent_unique = uniqueRep(parent_keys, it.index());
356  // Populate the table
357  if (parent_unique == unique) {
358  uint64_t idx = uniqueRep(child_dkeys, it.index());
359  child_sparse_table_.insert(idx) = it.value();
360  }
361  }
362 
363  child_sparse_table_.pruned();
364  child_sparse_table_.data().squeeze();
365  return TableFactor(child_dkeys, child_sparse_table_);
366 }
367 
368 /* ************************************************************************ */
369 double TableFactor::safe_div(const double& a, const double& b) {
370  // The use for safe_div is when we divide the product factor by the sum
371  // factor. If the product or sum is zero, we accord zero probability to the
372  // event.
373  return (a == 0 || b == 0) ? 0 : (a / b);
374 }
375 
376 /* ************************************************************************ */
377 void TableFactor::print(const string& s, const KeyFormatter& formatter) const {
378  cout << s;
379  cout << " f[";
380  for (auto&& key : keys())
381  cout << " (" << formatter(key) << "," << cardinality(key) << "),";
382  cout << " ]" << endl;
383  for (SparseIt it(sparse_table_); it; ++it) {
384  DiscreteValues assignment = findAssignments(it.index());
385  for (auto&& kv : assignment) {
386  cout << "(" << formatter(kv.first) << ", " << kv.second << ")";
387  }
388  cout << " | " << std::setw(10) << std::left << it.value() << " | "
389  << it.index() << endl;
390  }
391  cout << "number of nnzs: " << sparse_table_.nonZeros() << endl;
392 }
393 
394 /* ************************************************************************ */
396  return combine(nrFrontals, Ring::add);
397 }
398 
399 /* ************************************************************************ */
401  return combine(keys, Ring::add);
402 }
403 
404 /* ************************************************************************ */
405 double TableFactor::max() const {
406  double max_value = std::numeric_limits<double>::lowest();
408  max_value = std::max(max_value, it.value());
409  }
410  return max_value;
411 }
412 
413 /* ************************************************************************ */
415  return combine(nrFrontals, Ring::max);
416 }
417 
418 /* ************************************************************************ */
420  return combine(keys, Ring::max);
421 }
422 
423 /* ************************************************************************ */
425  // Initialize new factor.
426  uint64_t cardi = 1;
427  for (auto [key, c] : cardinalities_) cardi *= c;
428  Eigen::SparseVector<double> sparse_table(cardi);
429  sparse_table.reserve(sparse_table_.nonZeros());
430 
431  // Populate
432  for (SparseIt it(sparse_table_); it; ++it) {
433  sparse_table.coeffRef(it.index()) = op(it.value());
434  }
435 
436  // Free unused memory and return.
437  sparse_table.pruned();
438  sparse_table.data().squeeze();
439  return TableFactor(discreteKeys(), sparse_table);
440 }
441 
442 /* ************************************************************************ */
444  // Initialize new factor.
445  uint64_t cardi = 1;
446  for (auto [key, c] : cardinalities_) cardi *= c;
447  Eigen::SparseVector<double> sparse_table(cardi);
448  sparse_table.reserve(sparse_table_.nonZeros());
449 
450  // Populate
451  for (SparseIt it(sparse_table_); it; ++it) {
452  DiscreteValues assignment = findAssignments(it.index());
453  sparse_table.coeffRef(it.index()) = op(assignment, it.value());
454  }
455 
456  // Free unused memory and return.
457  sparse_table.pruned();
458  sparse_table.data().squeeze();
459  return TableFactor(discreteKeys(), sparse_table);
460 }
461 
462 /* ************************************************************************ */
464  if (keys_.empty() && sparse_table_.nonZeros() == 0)
465  return f;
466  else if (f.keys_.empty() && f.sparse_table_.nonZeros() == 0)
467  return *this;
468  // 1. Identify keys for contract and free modes.
469  DiscreteKeys contract_dkeys = contractDkeys(f);
470  DiscreteKeys f_free_dkeys = f.freeDkeys(*this);
471  DiscreteKeys union_dkeys = unionDkeys(f);
472  // 2. Create hash table for input factor f
473  unordered_map<uint64_t, AssignValList> map_f =
474  f.createMap(contract_dkeys, f_free_dkeys);
475  // 3. Initialize multiplied factor.
476  uint64_t card = 1;
477  for (auto u_dkey : union_dkeys) card *= u_dkey.second;
478  Eigen::SparseVector<double> mult_sparse_table(card);
479  mult_sparse_table.reserve(card);
480  // 3. Multiply.
481  for (SparseIt it(sparse_table_); it; ++it) {
482  uint64_t contract_unique = uniqueRep(contract_dkeys, it.index());
483  if (map_f.find(contract_unique) == map_f.end()) continue;
484  for (auto assignVal : map_f[contract_unique]) {
485  uint64_t union_idx = unionRep(union_dkeys, assignVal.first, it.index());
486  mult_sparse_table.insert(union_idx) = op(it.value(), assignVal.second);
487  }
488  }
489  // 4. Free unused memory.
490  mult_sparse_table.pruned();
491  mult_sparse_table.data().squeeze();
492  // 5. Create union keys and return.
493  return TableFactor(union_dkeys, mult_sparse_table);
494 }
495 
496 /* ************************************************************************ */
498  // Find contract modes.
499  DiscreteKeys contract;
500  set_intersection(sorted_dkeys_.begin(), sorted_dkeys_.end(),
501  f.sorted_dkeys_.begin(), f.sorted_dkeys_.end(),
502  back_inserter(contract));
503  return contract;
504 }
505 
506 /* ************************************************************************ */
508  // Find free modes.
509  DiscreteKeys free;
510  set_difference(sorted_dkeys_.begin(), sorted_dkeys_.end(),
511  f.sorted_dkeys_.begin(), f.sorted_dkeys_.end(),
512  back_inserter(free));
513  return free;
514 }
515 
516 /* ************************************************************************ */
518  // Find union modes.
519  DiscreteKeys union_dkeys;
520  set_union(sorted_dkeys_.begin(), sorted_dkeys_.end(), f.sorted_dkeys_.begin(),
521  f.sorted_dkeys_.end(), back_inserter(union_dkeys));
522  return union_dkeys;
523 }
524 
525 /* ************************************************************************ */
527  const DiscreteValues& f_free,
528  const uint64_t idx) const {
529  uint64_t union_idx = 0, card = 1;
530  for (auto it = union_keys.rbegin(); it != union_keys.rend(); it++) {
531  if (f_free.find(it->first) == f_free.end()) {
532  union_idx += keyValueForIndex(it->first, idx) * card;
533  } else {
534  union_idx += f_free.at(it->first) * card;
535  }
536  card *= it->second;
537  }
538  return union_idx;
539 }
540 
541 /* ************************************************************************ */
542 unordered_map<uint64_t, TableFactor::AssignValList> TableFactor::createMap(
543  const DiscreteKeys& contract, const DiscreteKeys& free) const {
544  // 1. Initialize map.
545  unordered_map<uint64_t, AssignValList> map_f;
546  // 2. Iterate over nonzero elements.
547  for (SparseIt it(sparse_table_); it; ++it) {
548  // 3. Create unique representation of contract modes.
549  uint64_t unique_rep = uniqueRep(contract, it.index());
550  // 4. Create assignment for free modes.
551  DiscreteValues free_assignments;
552  for (auto& key : free)
553  free_assignments[key.first] = keyValueForIndex(key.first, it.index());
554  // 5. Populate map.
555  if (map_f.find(unique_rep) == map_f.end()) {
556  map_f[unique_rep] = {make_pair(free_assignments, it.value())};
557  } else {
558  map_f[unique_rep].push_back(make_pair(free_assignments, it.value()));
559  }
560  }
561  return map_f;
562 }
563 
564 /* ************************************************************************ */
566  const uint64_t idx) const {
567  if (dkeys.empty()) return 0;
568  uint64_t unique_rep = 0, card = 1;
569  for (auto it = dkeys.rbegin(); it != dkeys.rend(); it++) {
570  unique_rep += keyValueForIndex(it->first, idx) * card;
571  card *= it->second;
572  }
573  return unique_rep;
574 }
575 
576 /* ************************************************************************ */
577 uint64_t TableFactor::uniqueRep(const DiscreteValues& assignments) const {
578  if (assignments.empty()) return 0;
579  uint64_t unique_rep = 0, card = 1;
580  for (auto it = assignments.rbegin(); it != assignments.rend(); it++) {
581  unique_rep += it->second * card;
582  card *= cardinalities_.at(it->first);
583  }
584  return unique_rep;
585 }
586 
587 /* ************************************************************************ */
589  DiscreteValues assignment;
590  for (Key key : keys_) {
591  assignment[key] = keyValueForIndex(key, idx);
592  }
593  return assignment;
594 }
595 
596 /* ************************************************************************ */
598  Binary op) const {
599  if (nrFrontals > size()) {
600  throw invalid_argument(
601  "TableFactor::combine: invalid number of frontal "
602  "keys " +
603  to_string(nrFrontals) + ", nr.keys=" + std::to_string(size()));
604  }
605  // Find remaining keys.
606  DiscreteKeys remain_dkeys;
607  uint64_t card = 1;
608  for (auto i = nrFrontals; i < keys_.size(); i++) {
609  remain_dkeys.push_back(discreteKey(i));
610  card *= cardinality(keys_[i]);
611  }
612  // Create combined table.
613  Eigen::SparseVector<double> combined_table(card);
614  combined_table.reserve(sparse_table_.nonZeros());
615  // Populate combined table.
616  for (SparseIt it(sparse_table_); it; ++it) {
617  uint64_t idx = uniqueRep(remain_dkeys, it.index());
618  double new_val = op(combined_table.coeff(idx), it.value());
619  combined_table.coeffRef(idx) = new_val;
620  }
621  // Free unused memory.
622  combined_table.pruned();
623  combined_table.data().squeeze();
624  return std::make_shared<TableFactor>(remain_dkeys, combined_table);
625 }
626 
627 /* ************************************************************************ */
629  Binary op) const {
630  if (frontalKeys.size() > size()) {
631  throw invalid_argument(
632  "TableFactor::combine: invalid number of frontal "
633  "keys " +
634  std::to_string(frontalKeys.size()) +
635  ", nr.keys=" + std::to_string(size()));
636  }
637  // Find remaining keys.
638  DiscreteKeys remain_dkeys;
639  uint64_t card = 1;
640  for (Key key : keys_) {
641  if (std::find(frontalKeys.begin(), frontalKeys.end(), key) ==
642  frontalKeys.end()) {
643  remain_dkeys.emplace_back(key, cardinality(key));
644  card *= cardinality(key);
645  }
646  }
647  // Create combined table.
648  Eigen::SparseVector<double> combined_table(card);
649  combined_table.reserve(sparse_table_.nonZeros());
650  // Populate combined table.
651  for (SparseIt it(sparse_table_); it; ++it) {
652  uint64_t idx = uniqueRep(remain_dkeys, it.index());
653  double new_val = op(combined_table.coeff(idx), it.value());
654  combined_table.coeffRef(idx) = new_val;
655  }
656  // Free unused memory.
657  combined_table.pruned();
658  combined_table.data().squeeze();
659  return std::make_shared<TableFactor>(remain_dkeys, combined_table);
660 }
661 
662 /* ************************************************************************ */
663 size_t TableFactor::keyValueForIndex(Key target_key, uint64_t index) const {
664  // http://phrogz.net/lazy-cartesian-product
665  return (index / denominators_.at(target_key)) % cardinality(target_key);
666 }
667 
668 /* ************************************************************************ */
669 std::vector<std::pair<DiscreteValues, double>> TableFactor::enumerate() const {
670  // Get all possible assignments
671  std::vector<std::pair<Key, size_t>> pairs = discreteKeys();
672  // Reverse to make cartesian product output a more natural ordering.
673  std::vector<std::pair<Key, size_t>> rpairs(pairs.rbegin(), pairs.rend());
674  const auto assignments = DiscreteValues::CartesianProduct(rpairs);
675  // Construct unordered_map with values
676  std::vector<std::pair<DiscreteValues, double>> result;
677  for (const auto& assignment : assignments) {
678  result.emplace_back(assignment, operator()(assignment));
679  }
680  return result;
681 }
682 
683 // Print out header.
684 /* ************************************************************************ */
685 string TableFactor::markdown(const KeyFormatter& keyFormatter,
686  const Names& names) const {
687  stringstream ss;
688 
689  // Print out header.
690  ss << "|";
691  for (auto& key : keys()) {
692  ss << keyFormatter(key) << "|";
693  }
694  ss << "value|\n";
695 
696  // Print out separator with alignment hints.
697  ss << "|";
698  for (size_t j = 0; j < size(); j++) ss << ":-:|";
699  ss << ":-:|\n";
700 
701  // Print out all rows.
702  for (SparseIt it(sparse_table_); it; ++it) {
703  DiscreteValues assignment = findAssignments(it.index());
704  ss << "|";
705  for (auto& key : keys()) {
706  size_t index = assignment.at(key);
707  ss << DiscreteValues::Translate(names, key, index) << "|";
708  }
709  ss << it.value() << "|\n";
710  }
711  return ss.str();
712 }
713 
714 /* ************************************************************************ */
715 string TableFactor::html(const KeyFormatter& keyFormatter,
716  const Names& names) const {
717  stringstream ss;
718 
719  // Print out preamble.
720  ss << "<div>\n<table class='TableFactor'>\n <thead>\n";
721 
722  // Print out header row.
723  ss << " <tr>";
724  for (auto& key : keys()) {
725  ss << "<th>" << keyFormatter(key) << "</th>";
726  }
727  ss << "<th>value</th></tr>\n";
728 
729  // Finish header and start body.
730  ss << " </thead>\n <tbody>\n";
731 
732  // Print out all rows.
733  for (SparseIt it(sparse_table_); it; ++it) {
734  DiscreteValues assignment = findAssignments(it.index());
735  ss << " <tr>";
736  for (auto& key : keys()) {
737  size_t index = assignment.at(key);
738  ss << "<th>" << DiscreteValues::Translate(names, key, index) << "</th>";
739  }
740  ss << "<td>" << it.value() << "</td>"; // value
741  ss << "</tr>\n";
742  }
743  ss << " </tbody>\n</table>\n</div>";
744  return ss.str();
745 }
746 
747 /* ************************************************************************ */
748 TableFactor TableFactor::prune(size_t maxNrAssignments) const {
749  const size_t N = maxNrAssignments;
750 
751  // Get the probabilities in the TableFactor so we can threshold.
752  vector<pair<Eigen::Index, double>> probabilities;
753 
754  // Store non-zero probabilities along with their indices in a vector.
755  for (SparseIt it(sparse_table_); it; ++it) {
756  probabilities.emplace_back(it.index(), it.value());
757  }
758 
759  // The number of probabilities can be lower than max_leaves.
760  if (probabilities.size() <= N) return *this;
761 
762  // Sort the vector in descending order based on the element values.
763  sort(probabilities.begin(), probabilities.end(),
764  [](const std::pair<Eigen::Index, double>& a,
765  const std::pair<Eigen::Index, double>& b) {
766  return a.second > b.second;
767  });
768 
769  // Keep the largest N probabilities in the vector.
770  if (probabilities.size() > N) probabilities.resize(N);
771 
772  // Create pruned sparse vector.
773  Eigen::SparseVector<double> pruned_vec(sparse_table_.size());
774  pruned_vec.reserve(probabilities.size());
775 
776  // Populate pruned sparse vector.
777  for (const auto& prob : probabilities) {
778  pruned_vec.insert(prob.first) = prob.second;
779  }
780 
781  // Create pruned decision tree factor and return.
782  return TableFactor(this->discreteKeys(), pruned_vec);
783 }
784 
785 /* ************************************************************************ */
787  const DiscreteValues& assignment) const {
788  throw std::runtime_error("TableFactor::restrict not implemented");
789 }
790 
791 /* ************************************************************************ */
792 } // namespace gtsam
gtsam::TableFactor::markdown
std::string markdown(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as markdown table.
Definition: TableFactor.cpp:685
gtsam::TableFactor
Definition: TableFactor.h:54
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:45
gtsam::HybridValues
Definition: HybridValues.h:37
gtsam::TableFactor::sum
DiscreteFactor::shared_ptr sum(size_t nrFrontals) const override
Create new factor by summing all values with the same separator values.
Definition: TableFactor.cpp:395
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::TableFactor::operator/
TableFactor operator/(const TableFactor &f) const
divide by factor f (safely)
Definition: TableFactor.h:208
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
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:57
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
tree
Definition: testExpression.cpp:212
gtsam::DiscreteFactor::cardinalities_
std::map< Key, size_t > cardinalities_
Map of Keys and their cardinalities.
Definition: DiscreteFactor.h:57
pybind_wrapper_test_script.this
this
Definition: pybind_wrapper_test_script.py:38
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
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:565
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:247
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::FastSet< Key >
DiscreteConditional.h
gtsam::TableFactor::contractDkeys
DiscreteKeys contractDkeys(const TableFactor &f) const
Definition: TableFactor.cpp:497
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:663
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:91
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:669
gtsam::AlgebraicDecisionTree< Key >
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:526
gtsam::TableFactor::findValue
double findValue(const DiscreteValues &values) const
Find value for corresponding DiscreteValues.
Definition: TableFactor.cpp:232
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::multiply
virtual DiscreteFactor::shared_ptr multiply(const DiscreteFactor::shared_ptr &f) const override
Multiply factors, DiscreteFactor::shared_ptr edition.
Definition: TableFactor.cpp:260
gtsam::TableFactor::sorted_dkeys_
DiscreteKeys sorted_dkeys_
Sorted DiscreteKeys to use internally.
Definition: TableFactor.h:63
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:148
left
static char left
Definition: blas_interface.hh:62
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::max
double max() const override
Find the maximum value in the factor.
Definition: TableFactor.cpp:405
gtsam::TableFactor::findAssignments
DiscreteValues findAssignments(const uint64_t idx) const
Find DiscreteValues for corresponding index.
Definition: TableFactor.cpp:588
gtsam::TableFactor::prune
TableFactor prune(size_t maxNrAssignments) const
Prune the decision tree of discrete variables.
Definition: TableFactor.cpp:748
Ring::max
static double max(const double &a, const double &b)
Definition: Ring.h:28
gtsam::TableFactor::html
std::string html(const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override
Render as html table.
Definition: TableFactor.cpp:715
gtsam::TableFactor::createMap
std::unordered_map< uint64_t, AssignValList > createMap(const DiscreteKeys &contract, const DiscreteKeys &free) const
Definition: TableFactor.cpp:542
gtsam::Assignment< Key >
TableFactor.h
gtsam::DiscreteFactor::Binary
std::function< double(const double, const double)> Binary
Definition: DiscreteFactor.h:53
gtsam::TableFactor::Convert
static Eigen::SparseVector< double > Convert(const DiscreteKeys &keys, const std::vector< double > &table)
Definition: TableFactor.cpp:171
gtsam::TableFactor::combine
shared_ptr combine(size_t nrFrontals, Binary op) const
Definition: TableFactor.cpp:597
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: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:38
gtsam::TableFactor::error
double error(const DiscreteValues &values) const override
Calculate error for DiscreteValues x, is -log(probability).
Definition: TableFactor.cpp:245
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::Symbol::index
std::uint64_t index() const
Definition: inference/Symbol.h:80
Ring::add
static double add(const double &a, const double &b)
Definition: Ring.h:27
gtsam
traits
Definition: ABC.h:17
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:190
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
gtsam::TableFactor::operator*
DiscreteFactor::shared_ptr operator*(double s) const override
multiply with a scalar
Definition: TableFactor.h:175
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:369
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:507
gtsam::TableFactor::denominators_
std::map< Key, size_t > denominators_
Map of Keys and their denominators used in keyValueForIndex.
Definition: TableFactor.h:61
gtsam::DiscreteValues::insert
std::pair< iterator, bool > insert(const value_type &value)
Definition: DiscreteValues.h:71
gtsam::TableFactor::choose
TableFactor choose(const DiscreteValues parentAssignments, DiscreteKeys parent_keys) const
Create a TableFactor that is a subset of this TableFactor.
Definition: TableFactor.cpp:324
p
float * p
Definition: Tutorial_Map_using.cpp:9
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:208
gtsam::TableFactor::restrict
DiscreteFactor::shared_ptr restrict(const DiscreteValues &assignment) const override
Restrict the factor to the given assignment.
Definition: TableFactor.cpp:786
gtsam::TableFactor::discreteKey
DiscreteKey discreteKey(size_t i) const
Return ith key in keys_ as a DiscreteKey.
Definition: TableFactor.h:86
gtsam::TableFactor::apply
TableFactor apply(Unary op) const
Definition: TableFactor.cpp:424
gtsam::TableFactor::print
void print(const std::string &s="TableFactor:\n", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
Definition: TableFactor.cpp:377
gtsam::DiscreteFactor::discreteKeys
DiscreteKeys discreteKeys() const
Return all the discrete keys associated with this factor.
Definition: DiscreteFactor.cpp:37
gtsam::TableFactor::evaluate
double evaluate(const Assignment< Key > &values) const override
Evaluate probability distribution, is just look up in TableFactor.
Definition: TableFactor.cpp:219
uint64_t
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
N
#define N
Definition: igam.h:9
gtsam::DiscreteFactor
Definition: DiscreteFactor.h:40
gtsam::DiscreteFactor::UnaryAssignment
std::function< double(const Assignment< Key > &, const double &)> UnaryAssignment
Definition: DiscreteFactor.h:52
gtsam::TableFactor::unionDkeys
DiscreteKeys unionDkeys(const TableFactor &f) const
Return union of DiscreteKeys in two factors.
Definition: TableFactor.cpp:517
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:96
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
gtsam::DiscreteFactor::Unary
std::function< double(const double &)> Unary
Definition: DiscreteFactor.h:50
_
constexpr descr< N - 1 > _(char const (&text)[N])
Definition: descr.h:109
max
#define max(a, b)
Definition: datatypes.h:20
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:105
k
static constexpr double k
Definition: GEKF_Rot3Example.cpp:31
gtsam::TableFactor::toDecisionTreeFactor
DecisionTreeFactor toDecisionTreeFactor() const override
Convert into a decisiontree.
Definition: TableFactor.cpp:300
Eigen::SparseVector::insert
Scalar & insert(Index row, Index col)
Definition: SparseVector.h:172
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74
gtsam::ComputeSparseTable
static Eigen::SparseVector< double > ComputeSparseTable(const DiscreteKeys &dkeys, const DecisionTreeFactor &dt)
Compute the indexing of the leaves in the decision tree based on the assignment and add the (index,...
Definition: TableFactor.cpp:75
Eigen::SparseVector::coeff
Scalar coeff(Index row, Index col) const
Definition: SparseVector.h:102
gtsam::DiscreteFactor::equals
virtual bool equals(const DiscreteFactor &lf, double tol=1e-9) const
equals
Definition: DiscreteFactor.cpp:32


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:04:20