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> >
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
key1
const Symbol key1('v', 1)
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
gtsam::SymbolicFactorGraph::SymbolicFactorGraph
SymbolicFactorGraph(SymbolicFactor &&c)
Construct from a single factor.
Definition: SymbolicFactorGraph.h:99
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
types.h
Typedefs for easier changing of types.
gtsam::EliminationTraits< SymbolicFactorGraph >::ConditionalType
SymbolicConditional ConditionalType
Type of conditionals from elimination.
Definition: SymbolicFactorGraph.h:40
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::SymbolicFactorGraph::BaseEliminateable
EliminateableFactorGraph< This > BaseEliminateable
Typedef to base elimination class.
Definition: SymbolicFactorGraph.h:69
gtsam::SymbolicFactorGraph::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: SymbolicFactorGraph.h:70
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::SymbolicBayesTree
Definition: SymbolicBayesTree.h:48
SymbolicFactor.h
gtsam::SymbolicFactorGraph::SymbolicFactorGraph
SymbolicFactorGraph(std::initializer_list< std::shared_ptr< SymbolicFactor >> sharedFactors)
Definition: SymbolicFactorGraph.h:94
gtsam::EliminationTraits< SymbolicFactorGraph >::BayesNetType
SymbolicBayesNet BayesNetType
Type of Bayes net from sequential elimination.
Definition: SymbolicFactorGraph.h:41
gtsam::SymbolicFactorGraph::print
void print(const std::string &s="SymbolicFactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
Definition: SymbolicFactorGraph.h:122
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::EliminationTraits< SymbolicFactorGraph >::EliminationTreeType
SymbolicEliminationTree EliminationTreeType
Type of elimination tree.
Definition: SymbolicFactorGraph.h:42
gtsam::FactorGraph
Definition: BayesTree.h:34
gtsam::SymbolicJunctionTree
Definition: SymbolicJunctionTree.h:50
key2
const Symbol key2('v', 2)
gtsam::SymbolicFactorGraph::SymbolicFactorGraph
SymbolicFactorGraph(const CONTAINER &factors)
Definition: SymbolicFactorGraph.h:84
gtsam::Ordering::Colamd
static Ordering Colamd(const FACTOR_GRAPH &graph)
Definition: inference/Ordering.h:93
gtsam::EliminationTraits< SymbolicFactorGraph >::DefaultOrderingFunc
static Ordering DefaultOrderingFunc(const FactorGraphType &graph, std::optional< std::reference_wrapper< const VariableIndex >> variableIndex)
The default ordering generation function.
Definition: SymbolicFactorGraph.h:50
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::SymbolicFactorGraph
Definition: SymbolicFactorGraph.h:61
gtsam::SymbolicFactorGraph::This
SymbolicFactorGraph This
Typedef to this class.
Definition: SymbolicFactorGraph.h:67
key3
const Symbol key3('v', 3)
gtsam::EliminationTraits< SymbolicFactorGraph >::FactorGraphType
SymbolicFactorGraph FactorGraphType
Type of the factor graph (e.g. GaussianFactorGraph)
Definition: SymbolicFactorGraph.h:39
EliminateableFactorGraph.h
Variable elimination algorithms for factor graphs.
gtsam::EliminationTraits
Definition: BayesTreeCliqueBase.h:33
gtsam::equals
Definition: Testable.h:112
key
const gtsam::Symbol key('X', 0)
gtsam::SymbolicConditional
Definition: SymbolicConditional.h:36
gtsam::SymbolicFactorGraph::SymbolicFactorGraph
SymbolicFactorGraph()
Definition: SymbolicFactorGraph.h:76
gtsam::SymbolicFactorGraph::SymbolicFactorGraph
SymbolicFactorGraph(const FactorGraph< DERIVEDFACTOR > &graph)
Definition: SymbolicFactorGraph.h:88
gtsam::EliminationTraits< SymbolicFactorGraph >::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: SymbolicFactorGraph.h:47
gtsam
traits
Definition: chartTesting.h:28
gtsam::Testable
Definition: Testable.h:152
gtsam::EliminationTraits< SymbolicFactorGraph >::FactorType
SymbolicFactor FactorType
Type of factors in factor graph.
Definition: SymbolicFactorGraph.h:38
gtsam::traits
Definition: Group.h:36
FactorGraph.h
Factor Graph Base Class.
gtsam::SymbolicFactor
Definition: SymbolicFactor.h:38
This
#define This
Definition: ActiveSetSolver-inl.h:27
gtsam::SymbolicFactorGraph::SymbolicFactorGraph
SymbolicFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor)
Definition: SymbolicFactorGraph.h:80
gtsam::tol
const G double tol
Definition: Group.h:79
key4
const Symbol key4('v', 4)
Base
Definition: test_virtual_functions.cpp:156
gtsam::EliminateableFactorGraph
Definition: EliminateableFactorGraph.h:55
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::SymbolicFactorGraph::Base
FactorGraph< SymbolicFactor > Base
Typedef to base factor graph type.
Definition: SymbolicFactorGraph.h:68
gtsam::SymbolicBayesNet
Definition: SymbolicBayesNet.h:32
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::SymbolicFactorGraph::operator()
SymbolicFactorGraph & operator()(SymbolicFactor &&c)
Add a single factor and return a reference. This allows for chaining, e.g., SymbolicFactorGraph bn = ...
Definition: SymbolicFactorGraph.h:109
gtsam::EliminationTraits< SymbolicFactorGraph >::JunctionTreeType
SymbolicJunctionTree JunctionTreeType
Definition: SymbolicFactorGraph.h:44
gtsam::SymbolicEliminationTree
Definition: SymbolicEliminationTree.h:27
gtsam::EliminationTraits< SymbolicFactorGraph >::BayesTreeType
SymbolicBayesTree BayesTreeType
Type of Bayes tree.
Definition: SymbolicFactorGraph.h:43
gtsam::EliminateSymbolic
std::pair< std::shared_ptr< SymbolicConditional >, std::shared_ptr< SymbolicFactor > > EliminateSymbolic(const SymbolicFactorGraph &factors, const Ordering &keys)
Definition: SymbolicFactor.cpp:36


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:07:02