DiscreteFactor.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 
19 #pragma once
20 
21 #include <gtsam/base/Testable.h>
24 #include <gtsam/inference/Factor.h>
26 
27 #include <string>
28 namespace gtsam {
29 
30 class DecisionTreeFactor;
31 class DiscreteConditional;
32 class HybridValues;
33 
40 class GTSAM_EXPORT DiscreteFactor : public Factor {
41  public:
42  // typedefs needed to play nice with gtsam
43  typedef DiscreteFactor This;
44  typedef std::shared_ptr<DiscreteFactor>
46  typedef Factor Base;
47 
49 
50  using Unary = std::function<double(const double&)>;
51  using UnaryAssignment =
52  std::function<double(const Assignment<Key>&, const double&)>;
53  using Binary = std::function<double(const double, const double)>;
54 
55  protected:
57  std::map<Key, size_t> cardinalities_;
58 
59  public:
62 
65 
71  template <typename CONTAINER>
72  DiscreteFactor(const CONTAINER& keys,
73  const std::map<Key, size_t> cardinalities = {})
74  : Base(keys), cardinalities_(cardinalities) {}
75 
79 
81  virtual bool equals(const DiscreteFactor& lf, double tol = 1e-9) const;
82 
84  void print(
85  const std::string& s = "DiscreteFactor\n",
86  const KeyFormatter& formatter = DefaultKeyFormatter) const override {
88  }
89 
93 
95  DiscreteKeys discreteKeys() const;
96 
97  std::map<Key, size_t> cardinalities() const { return cardinalities_; }
98 
99  size_t cardinality(Key j) const { return cardinalities_.at(j); }
100 
110  virtual double evaluate(const Assignment<Key>& values) const = 0;
111 
113  double operator()(const DiscreteValues& values) const {
114  return evaluate(values);
115  }
116 
118  virtual double error(const DiscreteValues& values) const;
119 
124  double error(const HybridValues& c) const override;
125 
127  virtual AlgebraicDecisionTree<Key> errorTree() const;
128 
130  virtual DiscreteFactor::shared_ptr operator*(double s) const = 0;
131 
134  virtual DecisionTreeFactor operator*(const DecisionTreeFactor&) const = 0;
135 
143  virtual DiscreteFactor::shared_ptr multiply(
144  const DiscreteFactor::shared_ptr& df) const = 0;
145 
148  const DiscreteFactor::shared_ptr& df) const = 0;
149 
150  virtual DecisionTreeFactor toDecisionTreeFactor() const = 0;
151 
153  virtual DiscreteFactor::shared_ptr sum(size_t nrFrontals) const = 0;
154 
156  virtual DiscreteFactor::shared_ptr sum(const Ordering& keys) const = 0;
157 
159  virtual double max() const = 0;
160 
162  virtual DiscreteFactor::shared_ptr max(size_t nrFrontals) const = 0;
163 
165  virtual DiscreteFactor::shared_ptr max(const Ordering& keys) const = 0;
166 
174 
179  virtual uint64_t nrValues() const = 0;
180 
182  virtual DiscreteFactor::shared_ptr restrict(
183  const DiscreteValues& assignment) const = 0;
184 
188 
191 
199  virtual std::string markdown(
200  const KeyFormatter& keyFormatter = DefaultKeyFormatter,
201  const Names& names = {}) const = 0;
202 
210  virtual std::string html(
211  const KeyFormatter& keyFormatter = DefaultKeyFormatter,
212  const Names& names = {}) const = 0;
213 
215 
216  private:
217 #if GTSAM_ENABLE_BOOST_SERIALIZATION
218 
219  friend class boost::serialization::access;
220  template <class ARCHIVE>
221  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
222  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
223  ar& BOOST_SERIALIZATION_NVP(cardinalities_);
224  }
225 #endif
226 };
227 // DiscreteFactor
228 
229 // traits
230 template <>
231 struct traits<DiscreteFactor> : public Testable<DiscreteFactor> {};
232 
233 } // namespace gtsam
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
gtsam::markdown
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
Definition: DiscreteValues.cpp:148
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:45
gtsam::HybridValues
Definition: HybridValues.h:37
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::DiscreteFactor::cardinalities
std::map< Key, size_t > cardinalities() const
Definition: DiscreteFactor.h:97
Testable.h
Concept check for values that can be used in unit tests.
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::DiscreteFactor::cardinalities_
std::map< Key, size_t > cardinalities_
Map of Keys and their cardinalities.
Definition: DiscreteFactor.h:57
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:247
Ordering.h
Variable ordering for the elimination algorithm.
gtsam::Factor
Definition: Factor.h:70
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
HybridValues
DiscreteFactor
Discrete values for.
Factor.h
The base class for all factors.
gtsam::DiscreteFactor::DiscreteFactor
DiscreteFactor()
Definition: DiscreteFactor.h:64
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::AlgebraicDecisionTree< Key >
gtsam::operator*
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:52
AlgebraicDecisionTree.h
Algebraic Decision Trees.
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
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::DiscreteFactor::print
void print(const std::string &s="DiscreteFactor\n", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
Definition: DiscreteFactor.h:84
gtsam::DiscreteFactor::This
DiscreteFactor This
This class.
Definition: DiscreteFactor.h:43
gtsam::Assignment< Key >
gtsam::DiscreteFactor::DiscreteFactor
DiscreteFactor(const CONTAINER &keys, const std::map< Key, size_t > cardinalities={})
Definition: DiscreteFactor.h:72
gtsam::DiscreteFactor::Binary
std::function< double(const double, const double)> Binary
Definition: DiscreteFactor.h:53
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
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
DiscreteValues.h
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
gtsam::DiscreteFactor::Names
DiscreteValues::Names Names
Translation table from values to strings.
Definition: DiscreteFactor.h:190
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::scale
static double scale(double x, double a, double b, double t1, double t2)
Scale x from [a, b] to [t1, t2].
Definition: Chebyshev.cpp:35
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::DiscreteFactor::Base
Factor Base
Our base class.
Definition: DiscreteFactor.h:46
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:153
gtsam::DiscreteFactor
Definition: DiscreteFactor.h:40
gtsam::DiscreteValues::Names
std::map< Key, std::vector< std::string > > Names
Translation table from values to strings.
Definition: DiscreteValues.h:158
gtsam::DiscreteFactor::UnaryAssignment
std::function< double(const Assignment< Key > &, const double &)> UnaryAssignment
Definition: DiscreteFactor.h:52
Base
Definition: test_virtual_functions.cpp:156
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
max
#define max(a, b)
Definition: datatypes.h:20
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::DiscreteFactor::operator()
double operator()(const DiscreteValues &values) const
Find value for given assignment of values to variables.
Definition: DiscreteFactor.h:113


gtsam
Author(s):
autogenerated on Sun Feb 16 2025 04:01:18