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 #include <boost/make_shared.hpp>
28 
29 namespace gtsam {
30 
31 // Forward declarations
32 class DiscreteFactorGraph;
33 class DiscreteFactor;
34 class DiscreteConditional;
35 class DiscreteBayesNet;
36 class DiscreteEliminationTree;
37 class DiscreteBayesTree;
38 class DiscreteJunctionTree;
39 
41 GTSAM_EXPORT std::pair<boost::shared_ptr<DiscreteConditional>, DecisionTreeFactor::shared_ptr>
42 EliminateDiscrete(const DiscreteFactorGraph& factors, const Ordering& keys);
43 
44 /* ************************************************************************* */
46 {
54  static std::pair<boost::shared_ptr<ConditionalType>, boost::shared_ptr<FactorType> >
56  DefaultEliminate(const FactorGraphType& factors, const Ordering& keys) {
57  return EliminateDiscrete(factors, keys); }
58 };
59 
60 /* ************************************************************************* */
65 class GTSAM_EXPORT DiscreteFactorGraph: public FactorGraph<DiscreteFactor>,
66 public EliminateableFactorGraph<DiscreteFactorGraph> {
67 public:
68 
72  typedef boost::shared_ptr<This> shared_ptr;
73 
75  typedef KeyVector Indices;
77  typedef boost::shared_ptr<Values> sharedValues;
78 
81 
83  template<typename ITERATOR>
84  DiscreteFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor) : Base(firstFactor, lastFactor) {}
85 
87  template<class CONTAINER>
88  explicit DiscreteFactorGraph(const CONTAINER& factors) : Base(factors) {}
89 
91  template<class DERIVEDFACTOR>
93 
95  virtual ~DiscreteFactorGraph() {}
96 
99 
100  bool equals(const This& fg, double tol = 1e-9) const;
101 
103 
104  template<class SOURCE>
105  void add(const DiscreteKey& j, SOURCE table) {
107  keys.push_back(j);
108  push_back(boost::make_shared<DecisionTreeFactor>(keys, table));
109  }
110 
111  template<class SOURCE>
112  void add(const DiscreteKey& j1, const DiscreteKey& j2, SOURCE table) {
114  keys.push_back(j1);
115  keys.push_back(j2);
116  push_back(boost::make_shared<DecisionTreeFactor>(keys, table));
117  }
118 
120  template<class SOURCE>
121  void add(const DiscreteKeys& keys, SOURCE table) {
122  push_back(boost::make_shared<DecisionTreeFactor>(keys, table));
123  }
124 
126  KeySet keys() const;
127 
129  DecisionTreeFactor product() const;
130 
132  double operator()(const DiscreteFactor::Values & values) const;
133 
135  void print(
136  const std::string& s = "DiscreteFactorGraph",
137  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
138 
144 
145 
146 // /** Permute the variables in the factors */
147 // GTSAM_EXPORT void permuteWithInverse(const Permutation& inversePermutation);
148 //
149 // /** Apply a reduction, which is a remapping of variable indices. */
150 // GTSAM_EXPORT void reduceWithInverse(const internal::Reduction& inverseReduction);
151 
152 }; // \ DiscreteFactorGraph
153 
155 template<> struct traits<DiscreteFactorGraph> : public Testable<DiscreteFactorGraph> {};
156 
157 } // \ namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
DiscreteFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor)
void add(const DiscreteKey &j, SOURCE table)
DiscreteEliminationTree EliminationTreeType
Type of elimination tree.
Variable elimination algorithms for factor graphs.
EliminateableFactorGraph< This > BaseEliminateable
Typedef to base elimination class.
static std::pair< boost::shared_ptr< ConditionalType >, boost::shared_ptr< FactorType > > DefaultEliminate(const FactorGraphType &factors, const Ordering &keys)
The default dense elimination function.
leaf::MyValues values
DiscreteFactor FactorType
Type of factors in factor graph.
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
NonlinearFactorGraph graph
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
virtual ~DiscreteFactorGraph()
Destructor.
const KeyFormatter & formatter
void add(const DiscreteKey &j1, const DiscreteKey &j2, SOURCE table)
DiscreteFactorGraph This
Typedef to this class.
DiscreteBayesNet BayesNetType
Type of Bayes net from sequential elimination.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
DiscreteFactorGraph FactorGraphType
Type of the factor graph (e.g. DiscreteFactorGraph)
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:34
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
DiscreteFactorGraph(const FactorGraph< DERIVEDFACTOR > &graph)
traits
Definition: chartTesting.h:28
FactorGraph< DiscreteFactor > Base
Typedef to base factor graph type.
ArrayXXf table(10, 4)
boost::shared_ptr< Values > sharedValues
DiscreteConditional ConditionalType
Type of conditionals from elimination.
void add(const DiscreteKeys &keys, SOURCE table)
Factor Graph Base Class.
boost::shared_ptr< DecisionTreeFactor > shared_ptr
DiscreteFactorGraph(const CONTAINER &factors)
const G double tol
Definition: Group.h:83
const KeyVector keys
A thin wrapper around std::set that uses boost&#39;s fast_pool_allocator.
std::ptrdiff_t j
boost::shared_ptr< Values > sharedValues
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:37


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:59