symbolicExampleGraphs.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2023, 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 
12 /*
13  * @file symbolicExampleGraphs.h
14  * @date sept 15, 2012
15  * @author Frank Dellaert
16  * @author Michael Kaess
17  * @author Viorela Ila
18  * @author Richard Roberts
19  */
20 
21 #pragma once
22 
29 #include <gtsam/inference/Symbol.h>
30 
31 namespace gtsam {
32  namespace {
33 
34  // A small helper class to replace Boost's `list_of` function.
35  template <typename T>
36  struct ChainedVector {
39 
40  ChainedVector(const T& c) { result.push_back(c); }
41 
42  ChainedVector& operator()(const T& c) {
43  result.push_back(c);
44  return *this;
45  }
46 
47  operator Result() { return result; }
48  };
49 
50  const SymbolicFactorGraph simpleTestGraph1 {
51  std::make_shared<SymbolicFactor>(0,1),
52  std::make_shared<SymbolicFactor>(0,2),
53  std::make_shared<SymbolicFactor>(1,4),
54  std::make_shared<SymbolicFactor>(2,4),
55  std::make_shared<SymbolicFactor>(3,4)};
56 
57  const SymbolicBayesNet simpleTestGraph1BayesNet {
58  std::make_shared<SymbolicConditional>(0,1,2),
59  std::make_shared<SymbolicConditional>(1,2,4),
60  std::make_shared<SymbolicConditional>(2,4),
61  std::make_shared<SymbolicConditional>(3,4),
62  std::make_shared<SymbolicConditional>(4)};
63 
64  const SymbolicFactorGraph simpleTestGraph2 {
65  std::make_shared<SymbolicFactor>(0,1),
66  std::make_shared<SymbolicFactor>(0,2),
67  std::make_shared<SymbolicFactor>(1,3),
68  std::make_shared<SymbolicFactor>(1,4),
69  std::make_shared<SymbolicFactor>(2,3),
70  std::make_shared<SymbolicFactor>(4,5)};
71 
73  const SymbolicFactorGraph simpleChain {
74  std::make_shared<SymbolicFactor>(1,0),
75  std::make_shared<SymbolicFactor>(0,2),
76  std::make_shared<SymbolicFactor>(2,3)};
77 
78  /* ************************************************************************* *
79  * 2 3
80  * 0 1 : 2
81  ****************************************************************************/
82  SymbolicBayesTree __simpleChainBayesTree() {
83  SymbolicBayesTree result;
84  result.insertRoot(std::make_shared<SymbolicBayesTreeClique>(
85  std::make_shared<SymbolicConditional>(
87  result.addClique(std::make_shared<SymbolicBayesTreeClique>(
88  std::make_shared<SymbolicConditional>(
90  result.roots().front());
91  return result;
92  }
93 
94  const SymbolicBayesTree simpleChainBayesTree = __simpleChainBayesTree();
95 
96  /* ************************************************************************* */
97  // Keys for ASIA example from the tutorial with A and D evidence
98  const Key _X_ = symbol_shorthand::X(0),
99  _T_ = symbol_shorthand::T(0),
100  _S_ = symbol_shorthand::S(0),
101  _E_ = symbol_shorthand::E(0),
104 
105  // Factor graph for Asia example
106  const SymbolicFactorGraph asiaGraph = {
107  std::make_shared<SymbolicFactor>(_T_),
108  std::make_shared<SymbolicFactor>(_S_),
109  std::make_shared<SymbolicFactor>(_T_, _E_, _L_),
110  std::make_shared<SymbolicFactor>(_L_, _S_),
111  std::make_shared<SymbolicFactor>(_S_, _B_),
112  std::make_shared<SymbolicFactor>(_E_, _B_),
113  std::make_shared<SymbolicFactor>(_E_, _X_)};
114 
115  const SymbolicBayesNet asiaBayesNet = {
116  std::make_shared<SymbolicConditional>(_T_, _E_, _L_),
117  std::make_shared<SymbolicConditional>(_X_, _E_),
118  std::make_shared<SymbolicConditional>(_E_, _B_, _L_),
119  std::make_shared<SymbolicConditional>(_S_, _B_, _L_),
120  std::make_shared<SymbolicConditional>(_L_, _B_),
121  std::make_shared<SymbolicConditional>(_B_)};
122 
123  /* ************************************************************************* */
124  // Allow creating Cliques and Keys in `list_of` chaining style:
125  using sharedClique = SymbolicBayesTreeClique::shared_ptr;
126  using Children = ChainedVector<sharedClique>;
127  using Keys = ChainedVector<Key>;
128 
129  inline sharedClique LeafClique(const Keys::Result& keys,
130  DenseIndex nrFrontals) {
131  return std::make_shared<SymbolicBayesTreeClique>(
132  std::make_shared<SymbolicConditional>(
133  SymbolicConditional::FromKeys(keys, nrFrontals)));
134  }
135 
136  inline sharedClique NodeClique(const Keys::Result& keys,
137  DenseIndex nrFrontals,
138  const Children::Result& children) {
139  sharedClique clique = LeafClique(keys, nrFrontals);
140  clique->children.assign(children.begin(), children.end());
141  for (auto&& child : children) child->parent_ = clique;
142  return clique;
143  }
144 
145  /* ************************************************************************* */
146  // BayesTree for Asia example
147  SymbolicBayesTree __asiaBayesTree() {
148  SymbolicBayesTree result;
149  result.insertRoot(LeafClique({_E_, _L_, _B_}, 3));
150  result.addClique(LeafClique({_S_, _B_, _L_}, 1), result.roots().front());
151  result.addClique(LeafClique({_T_, _E_, _L_}, 1), result.roots().front());
152  result.addClique(LeafClique({_X_, _E_}, 1), result.roots().front());
153  return result;
154  }
155 
156  const SymbolicBayesTree asiaBayesTree = __asiaBayesTree();
157 
158  /* ************************************************************************* */
159  const Ordering asiaOrdering{_X_, _T_, _S_, _E_, _L_, _B_};
160  } // namespace
161 } // namespace gtsam
gtsam::symbol_shorthand::E
Key E(std::uint64_t j)
Definition: inference/Symbol.h:152
gtsam.examples.DogLegOptimizerExample.type
type
Definition: DogLegOptimizerExample.py:111
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::symbol_shorthand::S
Key S(std::uint64_t j)
Definition: inference/Symbol.h:166
Ordering.h
Variable ordering for the elimination algorithm.
SymbolicBayesTree.h
SymbolicFactor.h
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
result
Values result
Definition: OdometryOptimize.cpp:8
SymbolicConditional.h
gtsam::symbol_shorthand::X
Key X(std::uint64_t j)
Definition: inference/Symbol.h:171
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
_L_
static const Key _L_
Definition: testSymbolicBayesNet.cpp:31
Symbol.h
gtsam::symbol_shorthand::L
Key L(std::uint64_t j)
Definition: inference/Symbol.h:159
Eigen::Triplet< double >
gtsam::symbol_shorthand::B
Key B(std::uint64_t j)
Definition: inference/Symbol.h:149
SymbolicFactorGraph.h
gtsam
traits
Definition: chartTesting.h:28
gtsam::SymbolicBayesTreeClique::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: SymbolicBayesTree.h:39
_B_
static const Key _B_
Definition: testSymbolicBayesNet.cpp:33
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
gtsam::symbol_shorthand::T
Key T(std::uint64_t j)
Definition: inference/Symbol.h:167
gtsam::SymbolicConditional::FromKeys
static SymbolicConditional FromKeys(const CONTAINER &keys, size_t nrFrontals)
Definition: SymbolicConditional.h:88
FastDefaultAllocator.h
An easy way to control which allocator is used for Fast* collections.
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::Result
std::pair< std::shared_ptr< GaussianConditional >, GaussianMixtureFactor::sharedFactor > Result
Definition: HybridGaussianFactorGraph.cpp:280


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:03:48