DiscreteConditional.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 
24 
25 #include <memory>
26 #include <string>
27 #include <vector>
28 
29 namespace gtsam {
30 
37 class GTSAM_EXPORT DiscreteConditional
38  : public DecisionTreeFactor,
39  public Conditional<DecisionTreeFactor, DiscreteConditional> {
40  public:
41  // typedefs needed to play nice with gtsam
43  typedef std::shared_ptr<This> shared_ptr;
47 
49 
52 
55 
57  DiscreteConditional(size_t nFrontals, const DecisionTreeFactor& f);
58 
63  DiscreteConditional(size_t nFrontals, const DiscreteKeys& keys,
64  const ADT& potentials);
65 
67  explicit DiscreteConditional(const Signature& signature);
68 
77  const Signature::Table& table)
78  : DiscreteConditional(Signature(key, parents, table)) {}
79 
90  const std::string& spec)
91  : DiscreteConditional(Signature(key, parents, spec)) {}
92 
94  DiscreteConditional(const DiscreteKey& key, const std::string& spec)
95  : DiscreteConditional(Signature(key, {}, spec)) {}
96 
102  const DecisionTreeFactor& marginal);
103 
110  const DecisionTreeFactor& marginal,
111  const Ordering& orderedKeys);
112 
129 
131  DiscreteConditional marginal(Key key) const;
132 
136 
138  void print(
139  const std::string& s = "Discrete Conditional: ",
140  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
141 
143  bool equals(const DiscreteFactor& other, double tol = 1e-9) const override;
144 
148 
150  double logProbability(const DiscreteValues& x) const {
151  return -error(x);
152  }
153 
156  const std::string& s = "Discrete Conditional: ",
157  const KeyFormatter& formatter = DefaultKeyFormatter) const {
158  static_cast<const BaseConditional*>(this)->print(s, formatter);
159  }
160 
162  double evaluate(const DiscreteValues& values) const {
163  return ADT::operator()(values);
164  }
165 
167  using DecisionTreeFactor::operator();
168 
182  shared_ptr choose(const DiscreteValues& given) const;
183 
186  const DiscreteValues& frontalValues) const;
187 
189  DecisionTreeFactor::shared_ptr likelihood(size_t frontal) const;
190 
196  size_t sample(const DiscreteValues& parentsValues) const;
197 
199  size_t sample(size_t parent_value) const;
200 
202  size_t sample() const;
203 
208  size_t argmax() const;
209 
213 
215  void sampleInPlace(DiscreteValues* parentsValues) const;
216 
218  std::vector<DiscreteValues> frontalAssignments() const;
219 
221  std::vector<DiscreteValues> allAssignments() const;
222 
226 
228  std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
229  const Names& names = {}) const override;
230 
232  std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
233  const Names& names = {}) const override;
234 
235 
239 
244  double evaluate(const HybridValues& x) const override;
245 
246  using BaseConditional::operator();
247 
252  double logProbability(const HybridValues& x) const override {
253  return -error(x);
254  }
255 
261  double logNormalizationConstant() const override { return 0.0; }
262 
264 
265  protected:
268  bool forceComplete) const;
269 
270  private:
271 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
272 
273  friend class boost::serialization::access;
274  template <class Archive>
275  void serialize(Archive& ar, const unsigned int /*version*/) {
276  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor);
277  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional);
278  }
279 #endif
280 };
281 // DiscreteConditional
282 
283 // traits
284 template <>
285 struct traits<DiscreteConditional> : public Testable<DiscreteConditional> {};
286 
287 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const gtsam::Symbol key('X', 0)
Conditional< BaseFactor, This > BaseConditional
Typedef to our conditional base class.
DiscreteConditional This
Typedef to this class.
signatures for conditional densities
DiscreteConditional()
Default constructor needed for serialization.
std::string serialize(const T &input)
serializes to a string
double evaluate(const DiscreteValues &values) const
Evaluate, just look up in AlgebraicDecisonTree.
double logNormalizationConstant() const override
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.
leaf::MyValues values
DiscreteConditional(const DiscreteKey &key, const std::string &spec)
No-parent specialization; can also use DiscreteDistribution.
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:52
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
double error(const DiscreteValues &values) const
Calculate error for DiscreteValues x, is -log(probability).
DiscreteConditional(const DiscreteKey &key, const DiscreteKeys &parents, const std::string &spec)
const KeyFormatter & formatter
void printSignature(const std::string &s="Discrete Conditional: ", const KeyFormatter &formatter=DefaultKeyFormatter) const
print index signature only
std::vector< Row > Table
Definition: Signature.h:60
double logProbability(const HybridValues &x) const override
< HybridValues version
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
double logProbability(const DiscreteValues &x) const
Log-probability is just -error(x).
DiscreteConditional(const DiscreteKey &key, const DiscreteKeys &parents, const Signature::Table &table)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
DecisionTreeFactor BaseFactor
Typedef to our factor base class.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
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
DiscreteValues::Names Names
Translation table from values to strings.
traits
Definition: chartTesting.h:28
std::shared_ptr< DecisionTreeFactor > shared_ptr
ArrayXXf table(10, 4)
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
std::shared_ptr< This > shared_ptr
shared_ptr to this class
const KeyVector keys
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
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
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:34:10