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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:36:35