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 
24 #include <Eigen/Sparse>
25 #include <algorithm>
26 #include <map>
27 #include <memory>
28 #include <stdexcept>
29 #include <string>
30 #include <utility>
31 #include <vector>
32 
33 namespace gtsam {
34 
35 class HybridValues;
36 
45 class GTSAM_EXPORT TableFactor : public DiscreteFactor {
46  protected:
48  std::map<Key, size_t> cardinalities_;
51 
52  private:
54  std::map<Key, size_t> denominators_;
57 
72  size_t keyValueForIndex(Key target_key, uint64_t index) const;
73 
79  DiscreteKey discreteKey(size_t i) const {
80  return DiscreteKey(keys_[i], cardinalities_.at(keys_[i]));
81  }
82 
85  static Eigen::SparseVector<double> Convert(const std::vector<double>& table);
86 
88  static Eigen::SparseVector<double> Convert(const std::string& table);
89 
90  public:
91  // typedefs needed to play nice with gtsam
92  typedef TableFactor This;
93  typedef DiscreteFactor Base;
94  typedef std::shared_ptr<TableFactor> shared_ptr;
96  typedef std::vector<std::pair<DiscreteValues, double>> AssignValList;
97  using Binary = std::function<double(const double, const double)>;
98 
99  public:
101  struct Ring {
102  static inline double zero() { return 0.0; }
103  static inline double one() { return 1.0; }
104  static inline double add(const double& a, const double& b) { return a + b; }
105  static inline double max(const double& a, const double& b) {
106  return std::max(a, b);
107  }
108  static inline double mul(const double& a, const double& b) { return a * b; }
109  static inline double div(const double& a, const double& b) {
110  return (a == 0 || b == 0) ? 0 : (a / b);
111  }
112  static inline double id(const double& x) { return x; }
113  };
114 
117 
119  TableFactor();
120 
122  TableFactor(const DiscreteKeys& keys, const TableFactor& potentials);
123 
125  TableFactor(const DiscreteKeys& keys,
126  const Eigen::SparseVector<double>& table);
127 
129  TableFactor(const DiscreteKeys& keys, const std::vector<double>& table)
130  : TableFactor(keys, Convert(table)) {}
131 
133  TableFactor(const DiscreteKeys& keys, const std::string& table)
134  : TableFactor(keys, Convert(table)) {}
135 
137  template <class SOURCE>
138  TableFactor(const DiscreteKey& key, SOURCE table)
139  : TableFactor(DiscreteKeys{key}, table) {}
140 
142  TableFactor(const DiscreteKey& key, const std::vector<double>& row)
143  : TableFactor(DiscreteKeys{key}, row) {}
144 
148 
150  bool equals(const DiscreteFactor& other, double tol = 1e-9) const override;
151 
152  // print
153  void print(
154  const std::string& s = "TableFactor:\n",
155  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
156 
157  // /// @}
158  // /// @name Standard Interface
159  // /// @{
160 
163  double evaluate(const DiscreteValues& values) const {
164  return operator()(values);
165  }
166 
168  double operator()(const DiscreteValues& values) const override;
169 
171  double error(const DiscreteValues& values) const;
172 
175  return apply(f, Ring::mul);
176  };
177 
179  DecisionTreeFactor operator*(const DecisionTreeFactor& f) const override;
180 
181  static double safe_div(const double& a, const double& b);
182 
183  size_t cardinality(Key j) const { return cardinalities_.at(j); }
184 
187  return apply(f, safe_div);
188  }
189 
191  DecisionTreeFactor toDecisionTreeFactor() const override;
192 
194  TableFactor choose(const DiscreteValues assignments,
195  DiscreteKeys parent_keys) const;
196 
198  shared_ptr sum(size_t nrFrontals) const {
199  return combine(nrFrontals, Ring::add);
200  }
201 
203  shared_ptr sum(const Ordering& keys) const {
204  return combine(keys, Ring::add);
205  }
206 
208  shared_ptr max(size_t nrFrontals) const {
209  return combine(nrFrontals, Ring::max);
210  }
211 
213  shared_ptr max(const Ordering& keys) const {
214  return combine(keys, Ring::max);
215  }
216 
220 
226  TableFactor apply(const TableFactor& f, Binary op) const;
227 
229  DiscreteKeys contractDkeys(const TableFactor& f) const;
230 
232  DiscreteKeys freeDkeys(const TableFactor& f) const;
233 
235  DiscreteKeys unionDkeys(const TableFactor& f) const;
236 
238  uint64_t unionRep(const DiscreteKeys& keys, const DiscreteValues& assign,
239  const uint64_t idx) const;
240 
243  std::unordered_map<uint64_t, AssignValList> createMap(
244  const DiscreteKeys& contract, const DiscreteKeys& free) const;
245 
247  uint64_t uniqueRep(const DiscreteKeys& keys, const uint64_t idx) const;
248 
250  uint64_t uniqueRep(const DiscreteValues& assignments) const;
251 
253  DiscreteValues findAssignments(const uint64_t idx) const;
254 
256  double findValue(const DiscreteValues& values) const;
257 
264  shared_ptr combine(size_t nrFrontals, Binary op) const;
265 
272  shared_ptr combine(const Ordering& keys, Binary op) const;
273 
275  std::vector<std::pair<DiscreteValues, double>> enumerate() const;
276 
278  DiscreteKeys discreteKeys() const;
279 
298  TableFactor prune(size_t maxNrAssignments) const;
299 
303 
311  std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
312  const Names& names = {}) const override;
313 
321  std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
322  const Names& names = {}) const override;
323 
327 
332  double error(const HybridValues& values) const override;
333 
335 };
336 
337 // traits
338 template <>
339 struct traits<TableFactor> : public Testable<TableFactor> {};
340 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const gtsam::Symbol key('X', 0)
static double mul(const double &a, const double &b)
Definition: TableFactor.h:108
shared_ptr max(size_t nrFrontals) const
Create new factor by maximizing over all values with the same separator.
Definition: TableFactor.h:208
#define max(a, b)
Definition: datatypes.h:20
std::map< Key, size_t > denominators_
Map of Keys and their denominators used in keyValueForIndex.
Definition: TableFactor.h:54
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:221
static int mul(const int &a, const int &b)
static double zero()
Definition: TableFactor.h:102
shared_ptr max(const Ordering &keys) const
Create new factor by maximizing over all values with the same separator.
Definition: TableFactor.h:213
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:398
static const T & choose(int layout, const T &col, const T &row)
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
Eigen::SparseVector< double >::InnerIterator SparseIt
Definition: TableFactor.h:95
leaf::MyValues values
TableFactor(const DiscreteKeys &keys, const std::string &table)
Definition: TableFactor.h:133
static double max(const double &a, const double &b)
Definition: TableFactor.h:105
double evaluate(const DiscreteValues &values) const
Definition: TableFactor.h:163
std::shared_ptr< TableFactor > shared_ptr
Definition: TableFactor.h:94
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:52
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
DiscreteKeys sorted_dkeys_
Sorted DiscreteKeys to use internally.
Definition: TableFactor.h:56
shared_ptr sum(const Ordering &keys) const
Create new factor by summing all values with the same separator values.
Definition: TableFactor.h:203
const KeyFormatter & formatter
DiscreteFactor Base
Typedef to base class.
Definition: TableFactor.h:93
std::map< Key, size_t > cardinalities_
Map of Keys and their cardinalities.
Definition: TableFactor.h:48
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
TableFactor(const DiscreteKeys &keys, const std::vector< double > &table)
Definition: TableFactor.h:129
size_t cardinality(Key j) const
Definition: TableFactor.h:183
TableFactor operator/(const TableFactor &f) const
divide by factor f (safely)
Definition: TableFactor.h:186
TableFactor(const DiscreteKey &key, const std::vector< double > &row)
Single-key specialization, with vector of doubles.
Definition: TableFactor.h:142
Eigen::SparseVector< double > sparse_table_
SparseVector of nonzero probabilities.
Definition: TableFactor.h:50
static double id(const double &x)
Definition: TableFactor.h:112
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
static double div(const double &a, const double &b)
Definition: TableFactor.h:109
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
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
DiscreteValues::Names Names
Translation table from values to strings.
traits
Definition: chartTesting.h:28
TableFactor(const DiscreteKey &key, SOURCE table)
Single-key specialization.
Definition: TableFactor.h:138
specialized key for discrete variables
static int add(const int &a, const int &b)
ArrayXXf table(10, 4)
static double one()
Definition: TableFactor.h:103
std::vector< std::pair< DiscreteValues, double > > AssignValList
Definition: TableFactor.h:96
TableFactor operator*(const TableFactor &f) const
multiply two TableFactors
Definition: TableFactor.h:174
static double add(const double &a, const double &b)
Definition: TableFactor.h:104
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
static double error
Definition: testRot3.cpp:37
const G double tol
Definition: Group.h:86
const KeyVector keys
TableFactor This
Definition: TableFactor.h:92
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
shared_ptr sum(size_t nrFrontals) const
Create new factor by summing all values with the same separator values.
Definition: TableFactor.h:198
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
std::ptrdiff_t j
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


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