DiscreteFactorGraph.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 
26 #include <gtsam/base/FastSet.h>
27 
28 #include <string>
29 #include <utility>
30 #include <vector>
31 
32 namespace gtsam {
33 
34 // Forward declarations
35 class DiscreteFactorGraph;
36 class DiscreteConditional;
37 class DiscreteBayesNet;
38 class DiscreteEliminationTree;
39 class DiscreteBayesTree;
40 class DiscreteJunctionTree;
41 
50 GTSAM_EXPORT std::pair<std::shared_ptr<DiscreteConditional>, DecisionTreeFactor::shared_ptr>
51 EliminateDiscrete(const DiscreteFactorGraph& factors, const Ordering& keys);
52 
53 /* ************************************************************************* */
55 {
63  static std::pair<std::shared_ptr<ConditionalType>,
65  std::shared_ptr<FactorType> >
66  DefaultEliminate(const FactorGraphType& factors, const Ordering& keys) {
67  return EliminateDiscrete(factors, keys);
68  }
71  const FactorGraphType& graph,
72  std::optional<std::reference_wrapper<const VariableIndex>> variableIndex) {
73  return Ordering::Colamd((*variableIndex).get());
74  }
75 };
76 
77 /* ************************************************************************* */
83 class GTSAM_EXPORT DiscreteFactorGraph
84  : public FactorGraph<DiscreteFactor>,
85  public EliminateableFactorGraph<DiscreteFactorGraph> {
86  public:
89  using BaseEliminateable =
91  using shared_ptr = std::shared_ptr<This>;
92 
94 
95  using Indices = KeyVector;
96 
99 
101  template <typename ITERATOR>
102  DiscreteFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor)
103  : Base(firstFactor, lastFactor) {}
104 
106  template <class CONTAINER>
107  explicit DiscreteFactorGraph(const CONTAINER& factors) : Base(factors) {}
108 
111  template <class DERIVEDFACTOR>
113 
116 
117  bool equals(const This& fg, double tol = 1e-9) const;
118 
120 
122  template <typename... Args>
123  void add(Args&&... args) {
124  emplace_shared<DecisionTreeFactor>(std::forward<Args>(args)...);
125  }
126 
128  KeySet keys() const;
129 
131  DiscreteKeys discreteKeys() const;
132 
134  DecisionTreeFactor product() const;
135 
140  double operator()(const DiscreteValues& values) const;
141 
143  void print(
144  const std::string& s = "DiscreteFactorGraph",
145  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
146 
153  DiscreteBayesNet sumProduct(
154  OptionalOrderingType orderingType = {}) const;
155 
162  DiscreteBayesNet sumProduct(const Ordering& ordering) const;
163 
170  DiscreteLookupDAG maxProduct(
171  OptionalOrderingType orderingType = {}) const;
172 
179  DiscreteLookupDAG maxProduct(const Ordering& ordering) const;
180 
188  OptionalOrderingType orderingType = {}) const;
189 
196  DiscreteValues optimize(const Ordering& ordering) const;
197 
200 
208  std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
209  const DiscreteFactor::Names& names = {}) const;
210 
218  std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
219  const DiscreteFactor::Names& names = {}) const;
220 
224 
225  using Base::error; // Expose error(const HybridValues&) method..
226 
228 }; // \ DiscreteFactorGraph
229 
230 std::pair<DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr> //
232  const Ordering& frontalKeys);
233 
235 template <>
236 struct traits<DiscreteFactorGraph> : public Testable<DiscreteFactorGraph> {};
237 
238 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
DiscreteFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor)
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
Main elimination function for DiscreteFactorGraph.
DiscreteEliminationTree EliminationTreeType
Type of elimination tree.
Variable elimination algorithms for factor graphs.
A Bayes tree representing a Discrete distribution.
Definition: pytypes.h:2012
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
leaf::MyValues values
const GaussianFactorGraph factors
DiscreteFactor FactorType
Type of factors in factor graph.
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
static enum @1107 ordering
const KeyFormatter & formatter
static Ordering Colamd(const FACTOR_GRAPH &graph)
DiscreteBayesNet BayesNetType
Type of Bayes net from sequential elimination.
std::shared_ptr< This > shared_ptr
shared_ptr to This
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
DiscreteFactorGraph FactorGraphType
Type of the factor graph (e.g. DiscreteFactorGraph)
static std::pair< std::shared_ptr< ConditionalType >, std::shared_ptr< FactorType > > DefaultEliminate(const FactorGraphType &factors, const Ordering &keys)
The default dense elimination function.
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
static Ordering DefaultOrderingFunc(const FactorGraphType &graph, std::optional< std::reference_wrapper< const VariableIndex >> variableIndex)
The default ordering generation function.
DiscreteFactorGraph()
map from keys to values
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
DiscreteFactorGraph(const FactorGraph< DERIVEDFACTOR > &graph)
DiscreteValues::Names Names
Translation table from values to strings.
traits
Definition: chartTesting.h:28
std::shared_ptr< DecisionTreeFactor > shared_ptr
DiscreteConditional ConditionalType
Type of conditionals from elimination.
Factor Graph Base Class.
Elimination tree for discrete factors.
static double error
Definition: testRot3.cpp:37
DiscreteFactorGraph(const CONTAINER &factors)
const G double tol
Definition: Group.h:86
const KeyVector keys
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateForMPE(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
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
A thin wrapper around std::set that uses boost&#39;s fast_pool_allocator.
void product(const MatrixType &m)
Definition: product.h:20
DiscreteBayesTree BayesTreeType
Type of Bayes tree.
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