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 
22 #include <gtsam/discrete/Ring.h>
24 
25 #include <Eigen/Sparse>
26 #include <algorithm>
27 #include <map>
28 #include <memory>
29 #include <stdexcept>
30 #include <string>
31 #include <utility>
32 #include <vector>
33 
34 namespace gtsam {
35 
36 class DiscreteConditional;
37 class HybridValues;
38 
47 class GTSAM_EXPORT TableFactor : public DiscreteFactor {
48  protected:
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 
87  static Eigen::SparseVector<double> Convert(const DiscreteKeys& keys,
88  const std::vector<double>& table);
89 
91  static Eigen::SparseVector<double> Convert(const DiscreteKeys& keys,
92  const std::string& table);
93 
94  public:
95  // typedefs needed to play nice with gtsam
96  typedef TableFactor This;
97  typedef DiscreteFactor Base;
98  typedef std::shared_ptr<TableFactor> shared_ptr;
100  typedef std::vector<std::pair<DiscreteValues, double>> AssignValList;
101 
102  public:
105 
107  TableFactor();
108 
110  TableFactor(const DiscreteKeys& keys, const TableFactor& potentials);
111 
115 
117  TableFactor(const DiscreteKeys& keys, const std::vector<double>& table)
118  : TableFactor(keys, Convert(keys, table)) {}
119 
121  TableFactor(const DiscreteKeys& keys, const std::string& table)
122  : TableFactor(keys, Convert(keys, table)) {}
123 
125  template <class SOURCE>
128 
130  TableFactor(const DiscreteKey& key, const std::vector<double>& row)
132 
134  TableFactor(const DiscreteKeys& keys, const DecisionTreeFactor& dtf);
135  TableFactor(const DecisionTreeFactor& dtf);
136 
138  TableFactor(const DiscreteKeys& keys, const DecisionTree<Key, double>& dtree);
139 
141  explicit TableFactor(const DiscreteConditional& c);
142 
146 
148  bool equals(const DiscreteFactor& other, double tol = 1e-9) const override;
149 
150  // print
151  void print(
152  const std::string& s = "TableFactor:\n",
153  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
154 
155  // /// @}
156  // /// @name Standard Interface
157  // /// @{
158 
160  double evaluate(const Assignment<Key>& values) const override;
161 
163  double error(const DiscreteValues& values) const override;
164 
167  return apply(f, Ring::mul);
168  };
169 
171  DecisionTreeFactor operator*(const DecisionTreeFactor& f) const override;
172 
173  static double safe_div(const double& a, const double& b);
174 
177  return apply(f, safe_div);
178  }
179 
181  DecisionTreeFactor toDecisionTreeFactor() const override;
182 
184  TableFactor choose(const DiscreteValues assignments,
185  DiscreteKeys parent_keys) const;
186 
188  shared_ptr sum(size_t nrFrontals) const {
189  return combine(nrFrontals, Ring::add);
190  }
191 
193  shared_ptr sum(const Ordering& keys) const {
194  return combine(keys, Ring::add);
195  }
196 
198  shared_ptr max(size_t nrFrontals) const {
199  return combine(nrFrontals, Ring::max);
200  }
201 
203  shared_ptr max(const Ordering& keys) const {
204  return combine(keys, Ring::max);
205  }
206 
210 
215  TableFactor apply(Unary op) const;
221  TableFactor apply(UnaryAssignment op) const;
222 
228  TableFactor apply(const TableFactor& f, Binary op) const;
229 
237  DiscreteKeys contractDkeys(const TableFactor& f) const;
238 
243  DiscreteKeys freeDkeys(const TableFactor& f) const;
244 
246  DiscreteKeys unionDkeys(const TableFactor& f) const;
247 
249  uint64_t unionRep(const DiscreteKeys& keys, const DiscreteValues& assign,
250  const uint64_t idx) const;
251 
254  std::unordered_map<uint64_t, AssignValList> createMap(
255  const DiscreteKeys& contract, const DiscreteKeys& free) const;
256 
258  uint64_t uniqueRep(const DiscreteKeys& keys, const uint64_t idx) const;
259 
261  uint64_t uniqueRep(const DiscreteValues& assignments) const;
262 
264  DiscreteValues findAssignments(const uint64_t idx) const;
265 
267  double findValue(const DiscreteValues& values) const;
268 
275  shared_ptr combine(size_t nrFrontals, Binary op) const;
276 
283  shared_ptr combine(const Ordering& keys, Binary op) const;
284 
286  std::vector<std::pair<DiscreteValues, double>> enumerate() const;
287 
306  TableFactor prune(size_t maxNrAssignments) const;
307 
311 
319  std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
320  const Names& names = {}) const override;
321 
329  std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
330  const Names& names = {}) const override;
331 
335 
340  double error(const HybridValues& values) const override;
341 
343 };
344 
345 // traits
346 template <>
347 struct traits<TableFactor> : public Testable<TableFactor> {};
348 } // namespace gtsam
gtsam::TableFactor
Definition: TableFactor.h:47
gtsam::markdown
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
Definition: DiscreteValues.cpp:130
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:45
gtsam::TableFactor::max
shared_ptr max(size_t nrFrontals) const
Create new factor by maximizing over all values with the same separator.
Definition: TableFactor.h:198
gtsam::TableFactor::This
TableFactor This
Definition: TableFactor.h:96
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:176
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::TableFactor::sparse_table_
Eigen::SparseVector< double > sparse_table_
SparseVector of nonzero probabilities.
Definition: TableFactor.h:50
gtsam::TableFactor::TableFactor
TableFactor(const DiscreteKeys &keys, const std::vector< double > &table)
Definition: TableFactor.h:117
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::TableFactor::sum
shared_ptr sum(size_t nrFrontals) const
Create new factor by summing all values with the same separator values.
Definition: TableFactor.h:188
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:97
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:121
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
gtsam::TableFactor::sorted_dkeys_
DiscreteKeys sorted_dkeys_
Sorted DiscreteKeys to use internally.
Definition: TableFactor.h:56
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:126
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
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:100
DiscreteValues
gtsam::TableFactor::max
shared_ptr max(const Ordering &keys) const
Create new factor by maximizing over all values with the same separator.
Definition: TableFactor.h:203
gtsam::TableFactor::TableFactor
TableFactor(const DiscreteKey &key, const std::vector< double > &row)
Single-key specialization, with vector of doubles.
Definition: TableFactor.h:130
gtsam::TableFactor::sum
shared_ptr sum(const Ordering &keys) const
Create new factor by summing all values with the same separator values.
Definition: TableFactor.h:193
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:166
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:44
error
static double error
Definition: testRot3.cpp:37
gtsam::traits
Definition: Group.h:36
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:54
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:99
gtsam::TableFactor::discreteKey
DiscreteKey discreteKey(size_t i) const
Return ith key in keys_ as a DiscreteKey.
Definition: TableFactor.h:79
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:39
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::Ordering
Definition: inference/Ordering.h:33
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:98


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:14:23