TableFactor.h
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 
18 #pragma once
19 
23 #include <gtsam/discrete/Ring.h>
25 
26 #include <Eigen/Sparse>
27 #include <algorithm>
28 #include <map>
29 #include <memory>
30 #include <stdexcept>
31 #include <string>
32 #include <utility>
33 #include <vector>
34 
35 #if GTSAM_ENABLE_BOOST_SERIALIZATION
37 
38 #include <boost/serialization/nvp.hpp>
39 #endif
40 
41 namespace gtsam {
42 
43 class DiscreteConditional;
44 class HybridValues;
45 
54 class GTSAM_EXPORT TableFactor : public DiscreteFactor {
55  protected:
58 
59  private:
61  std::map<Key, size_t> denominators_;
64 
79  size_t keyValueForIndex(Key target_key, uint64_t index) const;
80 
86  DiscreteKey discreteKey(size_t i) const {
87  return DiscreteKey(keys_[i], cardinalities_.at(keys_[i]));
88  }
89 
94  static Eigen::SparseVector<double> Convert(const DiscreteKeys& keys,
95  const std::vector<double>& table);
96 
98  static Eigen::SparseVector<double> Convert(const DiscreteKeys& keys,
99  const std::string& table);
100 
101  public:
102  // typedefs needed to play nice with gtsam
103  typedef TableFactor This;
105  typedef std::shared_ptr<TableFactor> shared_ptr;
107  typedef std::vector<std::pair<DiscreteValues, double>> AssignValList;
108 
111 
113  TableFactor();
114 
116  TableFactor(const DiscreteKeys& keys, const TableFactor& potentials);
117 
121 
123  TableFactor(const DiscreteKeys& keys, const std::vector<double>& table)
124  : TableFactor(keys, Convert(keys, table)) {}
125 
127  TableFactor(const DiscreteKeys& keys, const std::string& table)
128  : TableFactor(keys, Convert(keys, table)) {}
129 
131  template <class SOURCE>
134 
136  TableFactor(const DiscreteKey& key, const std::vector<double>& row)
138 
140  TableFactor(const DiscreteKeys& keys, const DecisionTreeFactor& dtf);
141  TableFactor(const DecisionTreeFactor& dtf);
142 
144  TableFactor(const DiscreteKeys& keys, const DecisionTree<Key, double>& dtree);
145 
147  explicit TableFactor(const DiscreteConditional& c);
148 
152 
154  bool equals(const DiscreteFactor& other, double tol = 1e-9) const override;
155 
156  // print
157  void print(
158  const std::string& s = "TableFactor:\n",
159  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
160 
161  // /// @}
162  // /// @name Standard Interface
163  // /// @{
164 
166  Eigen::SparseVector<double> sparseTable() const { return sparse_table_; }
167 
169  double evaluate(const Assignment<Key>& values) const override;
170 
172  double error(const DiscreteValues& values) const override;
173 
176  return apply(f, Ring::mul);
177  };
178 
180  DecisionTreeFactor operator*(const DecisionTreeFactor& f) const override;
181 
196  virtual DiscreteFactor::shared_ptr multiply(
197  const DiscreteFactor::shared_ptr& f) const override;
198 
199  static double safe_div(const double& a, const double& b);
200 
203  return apply(f, safe_div);
204  }
205 
208  const DiscreteFactor::shared_ptr& f) const override;
209 
211  DecisionTreeFactor toDecisionTreeFactor() const override;
212 
214  TableFactor choose(const DiscreteValues assignments,
215  DiscreteKeys parent_keys) const;
216 
218  DiscreteFactor::shared_ptr sum(size_t nrFrontals) const override {
219  return combine(nrFrontals, Ring::add);
220  }
221 
223  DiscreteFactor::shared_ptr sum(const Ordering& keys) const override {
224  return combine(keys, Ring::add);
225  }
226 
228  DiscreteFactor::shared_ptr max(size_t nrFrontals) const override {
229  return combine(nrFrontals, Ring::max);
230  }
231 
233  DiscreteFactor::shared_ptr max(const Ordering& keys) const override {
234  return combine(keys, Ring::max);
235  }
236 
240 
245  TableFactor apply(Unary op) const;
251  TableFactor apply(UnaryAssignment op) const;
252 
258  TableFactor apply(const TableFactor& f, Binary op) const;
259 
267  DiscreteKeys contractDkeys(const TableFactor& f) const;
268 
273  DiscreteKeys freeDkeys(const TableFactor& f) const;
274 
276  DiscreteKeys unionDkeys(const TableFactor& f) const;
277 
279  uint64_t unionRep(const DiscreteKeys& keys, const DiscreteValues& assign,
280  const uint64_t idx) const;
281 
284  std::unordered_map<uint64_t, AssignValList> createMap(
285  const DiscreteKeys& contract, const DiscreteKeys& free) const;
286 
288  uint64_t uniqueRep(const DiscreteKeys& keys, const uint64_t idx) const;
289 
291  uint64_t uniqueRep(const DiscreteValues& assignments) const;
292 
294  DiscreteValues findAssignments(const uint64_t idx) const;
295 
297  double findValue(const DiscreteValues& values) const;
298 
305  shared_ptr combine(size_t nrFrontals, Binary op) const;
306 
313  shared_ptr combine(const Ordering& keys, Binary op) const;
314 
316  std::vector<std::pair<DiscreteValues, double>> enumerate() const;
317 
336  TableFactor prune(size_t maxNrAssignments) const;
337 
342  uint64_t nrValues() const override { return sparse_table_.nonZeros(); }
343 
347 
355  std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
356  const Names& names = {}) const override;
357 
365  std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
366  const Names& names = {}) const override;
367 
371 
376  double error(const HybridValues& values) const override;
377 
379 
380  private:
381 #if GTSAM_ENABLE_BOOST_SERIALIZATION
382 
383  friend class boost::serialization::access;
384  template <class ARCHIVE>
385  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
386  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
387  ar& BOOST_SERIALIZATION_NVP(sparse_table_);
388  ar& BOOST_SERIALIZATION_NVP(denominators_);
389  ar& BOOST_SERIALIZATION_NVP(sorted_dkeys_);
390  }
391 #endif
392 };
393 
394 // traits
395 template <>
396 struct traits<TableFactor> : public Testable<TableFactor> {};
397 } // namespace gtsam
gtsam::TableFactor
Definition: TableFactor.h:54
gtsam::markdown
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
Definition: DiscreteValues.cpp:130
MatrixSerialization.h
Serialization for matrices.
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:45
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.h:218
gtsam::TableFactor::This
TableFactor This
Definition: TableFactor.h:103
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:202
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::TableFactor::sparse_table_
Eigen::SparseVector< double > sparse_table_
SparseVector of nonzero probabilities.
Definition: TableFactor.h:57
gtsam::TableFactor::TableFactor
TableFactor(const DiscreteKeys &keys, const std::vector< double > &table)
Definition: TableFactor.h:123
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
Ordering.h
Variable ordering for the elimination algorithm.
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
HybridValues
gtsam::TableFactor::Base
DiscreteFactor Base
Typedef to base class.
Definition: TableFactor.h:104
DiscreteFactor
Discrete values for.
Eigen::SparseCompressedBase::InnerIterator
Definition: SparseCompressedBase.h:158
Ring::mul
static double mul(const double &a, const double &b)
Definition: Ring.h:31
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::operator*
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:52
gtsam::TableFactor::TableFactor
TableFactor(const DiscreteKeys &keys, const std::string &table)
Definition: TableFactor.h:127
gtsam::TableFactor::sum
DiscreteFactor::shared_ptr sum(const Ordering &keys) const override
Create new factor by summing all values with the same separator values.
Definition: TableFactor.h:223
gtsam::TableFactor::max
DiscreteFactor::shared_ptr max(const Ordering &keys) const override
Create new factor by maximizing over all values with the same separator.
Definition: TableFactor.h:233
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
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:63
table
ArrayXXf table(10, 4)
gtsam::row
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:221
gtsam::TableFactor::TableFactor
TableFactor(const DiscreteKey &key, SOURCE table)
Single-key specialization.
Definition: TableFactor.h:132
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
DiscreteFactor.h
gtsam::TableFactor::nrValues
uint64_t nrValues() const override
Definition: TableFactor.h:342
Ring::max
static double max(const double &a, const double &b)
Definition: Ring.h:28
gtsam::TableFactor::AssignValList
std::vector< std::pair< DiscreteValues, double > > AssignValList
Definition: TableFactor.h:107
gtsam::TableFactor::sparseTable
Eigen::SparseVector< double > sparseTable() const
Getter for the underlying sparse vector.
Definition: TableFactor.h:166
gtsam::Assignment< Key >
gtsam::TableFactor::TableFactor
TableFactor(const DiscreteKey &key, const std::vector< double > &row)
Single-key specialization, with vector of doubles.
Definition: TableFactor.h:136
DiscreteKey.h
specialized key for discrete variables
key
const gtsam::Symbol key('X', 0)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
process_shonan_timing_results.names
dictionary names
Definition: process_shonan_timing_results.py:175
gtsam::b
const G & b
Definition: Group.h:79
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::TableFactor::operator*
TableFactor operator*(const TableFactor &f) const
multiply two TableFactors
Definition: TableFactor.h:175
Ring::add
static double add(const double &a, const double &b)
Definition: Ring.h:27
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::DiscreteFactor::shared_ptr
std::shared_ptr< DiscreteFactor > shared_ptr
shared_ptr to this class
Definition: DiscreteFactor.h:45
error
static double error
Definition: testRot3.cpp:37
gtsam::traits
Definition: Group.h:36
operator/
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE CwiseBinaryOp< internal::scalar_quotient_op< Scalar, typename OtherDerived::Scalar >, const Derived, const OtherDerived > operator/(const EIGEN_CURRENT_STORAGE_BASE_CLASS< OtherDerived > &other) const
Definition: ArrayCwiseBinaryOps.h:21
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
Eigen::SparseVector< double >
gtsam::TableFactor::denominators_
std::map< Key, size_t > denominators_
Map of Keys and their denominators used in keyValueForIndex.
Definition: TableFactor.h:61
Ring.h
Real Ring definition.
gtsam::apply
DecisionTree< L, Y > apply(const DecisionTree< L, Y > &f, const typename DecisionTree< L, Y >::Unary &op)
Apply unary operator op to DecisionTree f.
Definition: DecisionTree.h:460
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::TableFactor::SparseIt
Eigen::SparseVector< double >::InnerIterator SparseIt
Definition: TableFactor.h:106
gtsam::TableFactor::discreteKey
DiscreteKey discreteKey(size_t i) const
Return ith key in keys_ as a DiscreteKey.
Definition: TableFactor.h:86
uint64_t
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
gtsam::html
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
Definition: DiscreteValues.cpp:135
gtsam::DiscreteFactor
Definition: DiscreteFactor.h:40
gtsam::TableFactor::max
DiscreteFactor::shared_ptr max(size_t nrFrontals) const override
Create new factor by maximizing over all values with the same separator.
Definition: TableFactor.h:228
Base
Definition: test_virtual_functions.cpp:156
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::Ordering
Definition: inference/Ordering.h:33
DecisionTreeFactor.h
choose
static const T & choose(int layout, const T &col, const T &row)
Definition: cxx11_tensor_block_access.cpp:27
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::TableFactor::shared_ptr
std::shared_ptr< TableFactor > shared_ptr
Definition: TableFactor.h:105


gtsam
Author(s):
autogenerated on Tue Jan 7 2025 04:05:13