SymbolicFactorGraph.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 #include <gtsam/base/types.h>
25 
26 namespace gtsam {
27 
28  class SymbolicFactorGraph;
29  class SymbolicConditional;
30  class SymbolicBayesNet;
31  class SymbolicEliminationTree;
32  class SymbolicBayesTree;
33  class SymbolicJunctionTree;
34 
35  /* ************************************************************************* */
37  {
45  static std::pair<std::shared_ptr<ConditionalType>, std::shared_ptr<FactorType> >
47  DefaultEliminate(const FactorGraphType& factors, const Ordering& keys) {
48  return EliminateSymbolic(factors, keys); }
51  const FactorGraphType& graph,
52  std::optional<std::reference_wrapper<const VariableIndex>> variableIndex) {
53  return Ordering::Colamd((*variableIndex).get());
54  }
55  };
56 
57  /* ************************************************************************* */
61  class GTSAM_EXPORT SymbolicFactorGraph :
62  public FactorGraph<SymbolicFactor>,
63  public EliminateableFactorGraph<SymbolicFactorGraph>
64  {
65  public:
66 
70  typedef std::shared_ptr<This> shared_ptr;
71 
74 
77 
79  template<typename ITERATOR>
80  SymbolicFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor) : Base(firstFactor, lastFactor) {}
81 
83  template<class CONTAINER>
84  explicit SymbolicFactorGraph(const CONTAINER& factors) : Base(factors) {}
85 
87  template<class DERIVEDFACTOR>
89 
95  std::initializer_list<std::shared_ptr<SymbolicFactor>> sharedFactors)
96  : Base(sharedFactors) {}
97 
100  emplace_shared<SymbolicFactor>(c);
101  }
102 
110  emplace_shared<SymbolicFactor>(c);
111  return *this;
112  }
113 
115 
118 
119  bool equals(const This& fg, double tol = 1e-9) const;
120 
122  void print(
123  const std::string& s = "SymbolicFactorGraph",
124  const KeyFormatter& formatter = DefaultKeyFormatter) const override {
126  }
127 
129 
132 
134  void push_factor(Key key);
135 
137  void push_factor(Key key1, Key key2);
138 
140  void push_factor(Key key1, Key key2, Key key3);
141 
143  void push_factor(Key key1, Key key2, Key key3, Key key4);
144 
146 
147  private:
148 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
149 
150  friend class boost::serialization::access;
151  template<class ARCHIVE>
152  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
153  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
154  }
155 #endif
156  };
157 
159 template<>
160 struct traits<SymbolicFactorGraph> : public Testable<SymbolicFactorGraph> {
161 };
162 
163 } //\ namespace gtsam
const gtsam::Symbol key('X', 0)
Typedefs for easier changing of types.
const Symbol key3('v', 3)
std::string serialize(const T &input)
serializes to a string
SymbolicFactorGraph(const FactorGraph< DERIVEDFACTOR > &graph)
Variable elimination algorithms for factor graphs.
static Ordering DefaultOrderingFunc(const FactorGraphType &graph, std::optional< std::reference_wrapper< const VariableIndex >> variableIndex)
The default ordering generation function.
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
SymbolicBayesNet BayesNetType
Type of Bayes net from sequential elimination.
const GaussianFactorGraph factors
SymbolicFactorGraph FactorGraphType
Type of the factor graph (e.g. GaussianFactorGraph)
SymbolicFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor)
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
FactorGraph< SymbolicFactor > Base
Typedef to base factor graph type.
const KeyFormatter & formatter
static Ordering Colamd(const FACTOR_GRAPH &graph)
std::pair< std::shared_ptr< SymbolicConditional >, std::shared_ptr< SymbolicFactor > > EliminateSymbolic(const SymbolicFactorGraph &factors, const Ordering &keys)
const Symbol key1('v', 1)
SymbolicFactor FactorType
Type of factors in factor graph.
const Symbol key4('v', 4)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
SymbolicFactorGraph & operator()(SymbolicFactor &&c)
Add a single factor and return a reference. This allows for chaining, e.g., SymbolicFactorGraph bn = ...
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
traits
Definition: chartTesting.h:28
SymbolicFactorGraph(SymbolicFactor &&c)
Construct from a single factor.
static std::pair< std::shared_ptr< ConditionalType >, std::shared_ptr< FactorType > > DefaultEliminate(const FactorGraphType &factors, const Ordering &keys)
The default dense elimination function.
SymbolicConditional ConditionalType
Type of conditionals from elimination.
std::shared_ptr< This > shared_ptr
shared_ptr to this class
SymbolicFactorGraph(std::initializer_list< std::shared_ptr< SymbolicFactor >> sharedFactors)
Factor Graph Base Class.
EliminateableFactorGraph< This > BaseEliminateable
Typedef to base elimination class.
const G double tol
Definition: Group.h:86
SymbolicFactorGraph This
Typedef to this class.
const KeyVector keys
void print(const std::string &s="SymbolicFactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
SymbolicFactorGraph(const CONTAINER &factors)
SymbolicBayesTree BayesTreeType
Type of Bayes tree.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
SymbolicEliminationTree EliminationTreeType
Type of elimination tree.
const Symbol key2('v', 2)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:36:34