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 
20 #pragma once
21 
27 #include <gtsam/base/FastSet.h>
28 
29 #include <string>
30 #include <utility>
31 #include <vector>
32 
33 namespace gtsam {
34 
35 // Forward declarations
36 class DiscreteFactorGraph;
37 class DiscreteConditional;
38 class DiscreteBayesNet;
39 class DiscreteEliminationTree;
40 class DiscreteBayesTree;
41 class DiscreteJunctionTree;
42 
51 GTSAM_EXPORT
52 std::pair<DiscreteConditional::shared_ptr, DiscreteFactor::shared_ptr>
53 EliminateDiscrete(const DiscreteFactorGraph& factors,
54  const Ordering& frontalKeys);
55 
64 GTSAM_EXPORT
65 std::pair<DiscreteConditional::shared_ptr, DiscreteFactor::shared_ptr>
66 EliminateForMPE(const DiscreteFactorGraph& factors,
67  const Ordering& frontalKeys);
68 
70 {
78 
80  static std::pair<std::shared_ptr<ConditionalType>,
81  std::shared_ptr<FactorType> >
84  }
85 
88  const FactorGraphType& graph,
89  std::optional<std::reference_wrapper<const VariableIndex>> variableIndex) {
90  return Ordering::Colamd((*variableIndex).get());
91  }
92 };
93 
99 class GTSAM_EXPORT DiscreteFactorGraph
100  : public FactorGraph<DiscreteFactor>,
101  public EliminateableFactorGraph<DiscreteFactorGraph> {
102  public:
105  using BaseEliminateable =
107  using shared_ptr = std::shared_ptr<This>;
108 
110 
111  using Indices = KeyVector;
112 
115 
117  template <typename ITERATOR>
118  DiscreteFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor)
119  : Base(firstFactor, lastFactor) {}
120 
122  template <class CONTAINER>
123  explicit DiscreteFactorGraph(const CONTAINER& factors) : Base(factors) {}
124 
127  template <class DERIVED_FACTOR>
129 
132 
133  bool equals(const This& fg, double tol = 1e-9) const;
134 
136 
138  template <typename... Args>
139  void add(Args&&... args) {
140  emplace_shared<DecisionTreeFactor>(std::forward<Args>(args)...);
141  }
142 
144  KeySet keys() const;
145 
147  DiscreteKeys discreteKeys() const;
148 
150  DecisionTreeFactor product() const;
151 
156  double operator()(const DiscreteValues& values) const;
157 
159  void print(
160  const std::string& s = "DiscreteFactorGraph",
161  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
162 
169  DiscreteBayesNet sumProduct(
170  OptionalOrderingType orderingType = {}) const;
171 
178  DiscreteBayesNet sumProduct(const Ordering& ordering) const;
179 
186  DiscreteLookupDAG maxProduct(
187  OptionalOrderingType orderingType = {}) const;
188 
195  DiscreteLookupDAG maxProduct(const Ordering& ordering) const;
196 
204  OptionalOrderingType orderingType = {}) const;
205 
212  DiscreteValues optimize(const Ordering& ordering) const;
213 
216 
224  std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
225  const DiscreteFactor::Names& names = {}) const;
226 
234  std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
235  const DiscreteFactor::Names& names = {}) const;
236 
240 
241  using Base::error; // Expose error(const HybridValues&) method..
242 
244 }; // \ DiscreteFactorGraph
245 
247 template <>
248 struct traits<DiscreteFactorGraph> : public Testable<DiscreteFactorGraph> {};
249 
250 } // namespace gtsam
gtsam::EliminateDiscrete
std::pair< DiscreteConditional::shared_ptr, DiscreteFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
Main elimination function for DiscreteFactorGraph.
Definition: DiscreteFactorGraph.cpp:219
gtsam::EliminateForMPE
std::pair< DiscreteConditional::shared_ptr, DiscreteFactor::shared_ptr > EliminateForMPE(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
Alternate elimination function for that creates non-normalized lookup tables.
Definition: DiscreteFactorGraph.cpp:140
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::DiscreteFactorGraph
Definition: DiscreteFactorGraph.h:99
gtsam::DiscreteFactorGraph::DiscreteFactorGraph
DiscreteFactorGraph()
map from keys to values
Definition: DiscreteFactorGraph.h:114
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::EliminationTraits< DiscreteFactorGraph >::EliminationTreeType
DiscreteEliminationTree EliminationTreeType
Type of elimination tree.
Definition: DiscreteFactorGraph.h:75
gtsam::optimize
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Definition: triangulation.cpp:177
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::EliminationTraits< DiscreteFactorGraph >::JunctionTreeType
DiscreteJunctionTree JunctionTreeType
Type of Junction tree.
Definition: DiscreteFactorGraph.h:77
DiscreteLookupDAG.h
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::EliminationTraits< DiscreteFactorGraph >::FactorType
DiscreteFactor FactorType
Type of factors in factor graph.
Definition: DiscreteFactorGraph.h:71
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
gtsam::FastSet
Definition: FastSet.h:51
gtsam::EliminationTraits< DiscreteFactorGraph >::FactorGraphType
DiscreteFactorGraph FactorGraphType
Type of the factor graph (e.g. DiscreteFactorGraph)
Definition: DiscreteFactorGraph.h:72
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::FactorGraph
Definition: BayesTree.h:34
gtsam::DiscreteFactorGraph::DiscreteFactorGraph
DiscreteFactorGraph(const CONTAINER &factors)
Definition: DiscreteFactorGraph.h:123
gtsam::DiscreteJunctionTree
Definition: DiscreteJunctionTree.h:51
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
FastSet.h
A thin wrapper around std::set that uses boost's fast_pool_allocator.
gtsam::EliminationTraits< DiscreteFactorGraph >::DefaultOrderingFunc
static Ordering DefaultOrderingFunc(const FactorGraphType &graph, std::optional< std::reference_wrapper< const VariableIndex >> variableIndex)
The default ordering generation function.
Definition: DiscreteFactorGraph.h:87
gtsam::DiscreteBayesNet
Definition: DiscreteBayesNet.h:38
gtsam::DiscreteEliminationTree
Elimination tree for discrete factors.
Definition: DiscreteEliminationTree.h:31
operator()
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
Definition: IndexedViewMethods.h:73
gtsam::Ordering::Colamd
static Ordering Colamd(const FACTOR_GRAPH &graph)
Definition: inference/Ordering.h:93
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::DiscreteFactorGraph::DiscreteFactorGraph
DiscreteFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor)
Definition: DiscreteFactorGraph.h:118
gtsam::EliminationTraits< DiscreteFactorGraph >::DefaultEliminate
static std::pair< std::shared_ptr< ConditionalType >, std::shared_ptr< FactorType > > DefaultEliminate(const FactorGraphType &factors, const Ordering &keys)
The default dense elimination function.
Definition: DiscreteFactorGraph.h:82
gtsam::EliminationTraits< DiscreteFactorGraph >::BayesTreeType
DiscreteBayesTree BayesTreeType
Type of Bayes tree.
Definition: DiscreteFactorGraph.h:76
DiscreteValues
EliminateableFactorGraph.h
Variable elimination algorithms for factor graphs.
gtsam::EliminationTraits
Definition: BayesTreeCliqueBase.h:33
ordering
static enum @1096 ordering
gtsam::EliminationTraits< DiscreteFactorGraph >::ConditionalType
DiscreteConditional ConditionalType
Type of conditionals from elimination.
Definition: DiscreteFactorGraph.h:73
gtsam::equals
Definition: Testable.h:112
process_shonan_timing_results.names
dictionary names
Definition: process_shonan_timing_results.py:175
gtsam::DiscreteConditional
Definition: DiscreteConditional.h:37
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
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:139
FactorGraph.h
Factor Graph Base Class.
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
args
Definition: pytypes.h:2210
This
#define This
Definition: ActiveSetSolver-inl.h:27
gtsam::DiscreteFactorGraph::add
void add(Args &&... args)
Definition: DiscreteFactorGraph.h:139
gtsam::DiscreteBayesTree
A Bayes tree representing a Discrete distribution.
Definition: DiscreteBayesTree.h:73
product
void product(const MatrixType &m)
Definition: product.h:20
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::html
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
Definition: DiscreteValues.cpp:135
gtsam::DiscreteFactorGraph::Indices
KeyVector Indices
Definition: DiscreteFactorGraph.h:111
gtsam::DiscreteFactor
Definition: DiscreteFactor.h:39
gtsam::EliminationTraits< DiscreteFactorGraph >::BayesNetType
DiscreteBayesNet BayesNetType
Type of Bayes net from sequential elimination.
Definition: DiscreteFactorGraph.h:74
gtsam::EliminateableFactorGraph
Definition: EliminateableFactorGraph.h:55
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Ordering
Definition: inference/Ordering.h:33
DecisionTreeFactor.h
gtsam::DiscreteFactorGraph::DiscreteFactorGraph
DiscreteFactorGraph(const FactorGraph< DERIVED_FACTOR > &graph)
Definition: DiscreteFactorGraph.h:128
gtsam::DiscreteFactorGraph::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to This
Definition: DiscreteFactorGraph.h:107


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:28