BayesTree.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 
18 // \callgraph
19 
20 #pragma once
21 
22 #include <memory>
23 
24 #include <gtsam/inference/Key.h>
25 #include <gtsam/base/FastList.h>
27 #include <gtsam/base/FastVector.h>
28 
29 #include <string>
30 
31 namespace gtsam {
32 
33  // Forward declarations
34  template<class FACTOR> class FactorGraph;
35  template<class BAYESTREE, class GRAPH> class EliminatableClusterTree;
36 
37  /* ************************************************************************* */
39  struct GTSAM_EXPORT BayesTreeCliqueStats {
44  void print(const std::string& s = "") const ;
45  };
46 
48  struct GTSAM_EXPORT BayesTreeCliqueData {
51  BayesTreeCliqueStats getStats() const;
52  };
53 
54  /* ************************************************************************* */
65  template<class CLIQUE>
66  class BayesTree
67  {
68  protected:
70  typedef std::shared_ptr<This> shared_ptr;
71 
72  public:
73  typedef CLIQUE Clique;
74  typedef std::shared_ptr<Clique> sharedClique;
75  typedef Clique Node;
77  typedef typename CLIQUE::ConditionalType ConditionalType;
78  typedef std::shared_ptr<ConditionalType> sharedConditional;
79  typedef typename CLIQUE::BayesNetType BayesNetType;
80  typedef std::shared_ptr<BayesNetType> sharedBayesNet;
81  typedef typename CLIQUE::FactorType FactorType;
82  typedef std::shared_ptr<FactorType> sharedFactor;
83  typedef typename CLIQUE::FactorGraphType FactorGraphType;
84  typedef std::shared_ptr<FactorGraphType> sharedFactorGraph;
85  typedef typename FactorGraphType::Eliminate Eliminate;
86  typedef typename CLIQUE::EliminationTraitsType EliminationTraitsType;
87 
90 
93 
96 
97  protected:
98 
101 
104 
107 
110 
112  BayesTree(const This& other);
113 
115 
117  ~BayesTree();
118 
120  This& operator=(const This& other);
121 
124 
126  bool equals(const This& other, double tol = 1e-9) const;
127 
128  public:
130  void print(const std::string& s = "",
131  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
133 
136 
138  size_t size() const;
139 
141  inline bool empty() const {
142  return nodes_.empty();
143  }
144 
146  const Nodes& nodes() const { return nodes_; }
147 
149  sharedClique operator[](Key j) const { return nodes_.at(j); }
150 
152  const Roots& roots() const { return roots_; }
153 
155  const sharedClique& clique(Key j) const {
156  typename Nodes::const_iterator c = nodes_.find(j);
157  if(c == nodes_.end())
158  throw std::out_of_range("Requested the BayesTree clique for a key that is not in the BayesTree");
159  else
160  return c->second;
161  }
162 
165 
167  size_t numCachedSeparatorMarginals() const;
168 
174  sharedConditional marginalFactor(Key j, const Eliminate& function = EliminationTraitsType::DefaultEliminate) const;
175 
180  sharedFactorGraph joint(Key j1, Key j2, const Eliminate& function = EliminationTraitsType::DefaultEliminate) const;
181 
186  sharedBayesNet jointBayesNet(Key j1, Key j2, const Eliminate& function = EliminationTraitsType::DefaultEliminate) const;
187 
190 
192  void dot(std::ostream& os, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
193 
195  std::string dot(
196  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
197 
199  void saveGraph(const std::string& filename,
200  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
201 
205 
210  template<class CONTAINER>
211  Key findParentClique(const CONTAINER& parents) const;
212 
214  void clear();
215 
217  void deleteCachedShortcuts();
218 
223  void removePath(sharedClique clique, BayesNetType* bn, Cliques* orphans);
224 
229  void removeTop(const KeyVector& keys, BayesNetType* bn, Cliques* orphans);
230 
233  Cliques removeSubtree(const sharedClique& subtree);
234 
238  void insertRoot(const sharedClique& subtree);
239 
241  void addClique(const sharedClique& clique, const sharedClique& parent_clique = sharedClique());
242 
245 
246  protected:
247 
249  void dot(std::ostream &s, sharedClique clique, const KeyFormatter& keyFormatter,
250  int parentnum = 0) const;
251 
254 
257 
259  void fillNodesIndex(const sharedClique& subtree);
260 
261  // Friend JunctionTree because it directly fills roots and nodes index.
262  template<class BAYESTREE, class GRAPH> friend class EliminatableClusterTree;
263 
264  private:
265 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
266 
267  friend class boost::serialization::access;
268  template<class ARCHIVE>
269  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
270  ar & BOOST_SERIALIZATION_NVP(nodes_);
271  ar & BOOST_SERIALIZATION_NVP(roots_);
272  }
273 #endif
274 
276 
277  }; // BayesTree
278 
279  /* ************************************************************************* */
280  template <class CLIQUE, typename = void>
281  class BayesTreeOrphanWrapper : public CLIQUE::ConditionalType {
282  public:
283  typedef CLIQUE CliqueType;
284  typedef typename CLIQUE::ConditionalType Base;
285 
286  std::shared_ptr<CliqueType> clique;
287 
298  BayesTreeOrphanWrapper(const std::shared_ptr<CliqueType>& clique)
299  : clique(clique) {
300  this->keys_.assign(clique->conditional()->beginParents(),
301  clique->conditional()->endParents());
302  }
303 
304  void print(
305  const std::string& s = "",
306  const KeyFormatter& formatter = DefaultKeyFormatter) const override {
307  clique->print(s + "stored clique", formatter);
308  }
309  };
310 
311 }
gtsam::BayesTree::empty
bool empty() const
Definition: BayesTree.h:141
gtsam::BayesTreeOrphanWrapper
Definition: BayesTree.h:281
gtsam::ConcurrentMap< Key, sharedClique >
gtsam::BayesTree::insertRoot
void insertRoot(const sharedClique &subtree)
Definition: BayesTree-inst.h:299
gtsam::BayesTree::FactorGraphType
CLIQUE::FactorGraphType FactorGraphType
Definition: BayesTree.h:83
gtsam::BayesTree::fillNodesIndex
void fillNodesIndex(const sharedClique &subtree)
Definition: BayesTree-inst.h:285
gtsam::BayesTree::Eliminate
FactorGraphType::Eliminate Eliminate
Definition: BayesTree.h:85
gtsam::BayesTree::~BayesTree
~BayesTree()
Definition: BayesTree-inst.h:190
gtsam::BayesTreeCliqueStats::maxSeparatorSize
std::size_t maxSeparatorSize
Definition: BayesTree.h:43
FastVector.h
A thin wrapper around std::vector that uses a custom allocator.
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::BayesTree::FactorType
CLIQUE::FactorType FactorType
Definition: BayesTree.h:81
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::BayesTreeOrphanWrapper::Base
CLIQUE::ConditionalType Base
Definition: BayesTree.h:284
gtsam::BayesTree::addFactorsToGraph
void addFactorsToGraph(FactorGraph< FactorType > *graph) const
Definition: BayesTree-inst.h:168
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::BayesTreeOrphanWrapper::clique
std::shared_ptr< CliqueType > clique
Definition: BayesTree.h:286
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
gtsam::BayesTree::roots_
Roots roots_
Definition: BayesTree.h:103
gtsam::BayesTree::ConditionalType
CLIQUE::ConditionalType ConditionalType
Definition: BayesTree.h:77
ConcurrentMap.h
gtsam::BayesTree::getCliqueData
BayesTreeCliqueData getCliqueData() const
Definition: BayesTree-inst.h:35
gtsam::BayesTree::Nodes
ConcurrentMap< Key, sharedClique > Nodes
Definition: BayesTree.h:92
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::BayesTreeOrphanWrapper::print
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
Definition: BayesTree.h:304
gtsam::BayesTree::nodes
const Nodes & nodes() const
Definition: BayesTree.h:146
gtsam::BayesTreeCliqueStats
Definition: BayesTree.h:39
gtsam::BayesTree::marginalFactor
sharedConditional marginalFactor(Key j, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Definition: BayesTree-inst.h:309
gtsam::BayesTree::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: BayesTree-inst.h:251
gtsam::BayesTreeCliqueStats::maxConditionalSize
std::size_t maxConditionalSize
Definition: BayesTree.h:41
gtsam::BayesTree::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: BayesTree.h:70
os
ofstream os("timeSchurFactors.csv")
gtsam::BayesTreeCliqueData::conditionalSizes
FastVector< std::size_t > conditionalSizes
Definition: BayesTree.h:49
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::BayesTree::addClique
void addClique(const sharedClique &clique, const sharedClique &parent_clique=sharedClique())
Definition: BayesTree-inst.h:142
gtsam::BayesTreeCliqueStats::avgConditionalSize
double avgConditionalSize
Definition: BayesTree.h:40
gtsam::BayesTree::removeTop
void removeTop(const KeyVector &keys, BayesNetType *bn, Cliques *orphans)
Definition: BayesTree-inst.h:516
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::FactorGraph
Definition: BayesTree.h:34
gtsam::BayesTree::dot
void dot(std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Output to graphviz format, stream version.
Definition: BayesTree-inst.h:64
gtsam::EliminatableClusterTree
Definition: BayesTree.h:35
Key.h
gtsam::BayesTree::nodes_
Nodes nodes_
Definition: BayesTree.h:100
gtsam::BayesTree::removeSubtree
Cliques removeSubtree(const sharedClique &subtree)
Definition: BayesTree-inst.h:537
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::BayesTree::sharedFactorGraph
std::shared_ptr< FactorGraphType > sharedFactorGraph
Definition: BayesTree.h:84
gtsam::BayesTree::removePath
void removePath(sharedClique clique, BayesNetType *bn, Cliques *orphans)
Definition: BayesTree-inst.h:489
gtsam::BayesTree::BayesTree
BayesTree()
Definition: BayesTree.h:109
gtsam::BayesTree::roots
const Roots & roots() const
Definition: BayesTree.h:152
gtsam::BayesTree::BayesNetType
CLIQUE::BayesNetType BayesNetType
Definition: BayesTree.h:79
gtsam::BayesTreeOrphanWrapper::BayesTreeOrphanWrapper
BayesTreeOrphanWrapper(const std::shared_ptr< CliqueType > &clique)
Construct a new Bayes Tree Orphan Wrapper object.
Definition: BayesTree.h:298
gtsam::HybridBayesTreeClique
A clique in a HybridBayesTree which is a HybridConditional internally.
Definition: HybridBayesTree.h:44
gtsam::BayesTree::sharedBayesNet
std::shared_ptr< BayesNetType > sharedBayesNet
Definition: BayesTree.h:80
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
stats
bool stats
Definition: SolverComparer.cpp:100
gtsam::BayesTree::operator[]
sharedClique operator[](Key j) const
Definition: BayesTree.h:149
relicense.filename
filename
Definition: relicense.py:57
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::BayesTree::clique
const sharedClique & clique(Key j) const
Definition: BayesTree.h:155
gtsam::BayesTreeCliqueData::separatorSizes
FastVector< std::size_t > separatorSizes
Definition: BayesTree.h:50
gtsam::BayesTree::Node
Clique Node
Synonym for Clique (TODO: remove)
Definition: BayesTree.h:75
gtsam::BayesTree::EliminationTraitsType
CLIQUE::EliminationTraitsType EliminationTraitsType
Definition: BayesTree.h:86
gtsam::BayesTree::operator=
This & operator=(const This &other)
Definition: BayesTree-inst.h:238
gtsam::BayesTreeCliqueStats::avgSeparatorSize
double avgSeparatorSize
Definition: BayesTree.h:42
gtsam::BayesTree::deleteCachedShortcuts
void deleteCachedShortcuts()
Definition: BayesTree-inst.h:457
gtsam::BayesTree::jointBayesNet
sharedBayesNet jointBayesNet(Key j1, Key j2, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Definition: BayesTree-inst.h:341
gtsam::BayesTree::findParentClique
Key findParentClique(const CONTAINER &parents) const
Definition: BayesTree-inst.h:277
gtsam::FastList
Definition: FastList.h:43
size_t
std::size_t size_t
Definition: wrap/pybind11/include/pybind11/detail/common.h:476
gtsam::BayesTree::removeClique
void removeClique(sharedClique clique)
Definition: BayesTree-inst.h:465
gtsam::BayesTree::Roots
FastVector< sharedClique > Roots
Definition: BayesTree.h:95
gtsam::BayesTreeCliqueData
Definition: BayesTree.h:48
gtsam::BayesTree::sharedFactor
std::shared_ptr< FactorType > sharedFactor
Definition: BayesTree.h:82
gtsam
traits
Definition: chartTesting.h:28
gtsam::BayesTree
Definition: BayesTree.h:66
gtsam::BayesTree::size
size_t size() const
Definition: BayesTree-inst.h:133
gtsam::BayesTree::sharedClique
std::shared_ptr< Clique > sharedClique
Shared pointer to a clique.
Definition: BayesTree.h:74
gtsam::BayesTree::sharedConditional
std::shared_ptr< ConditionalType > sharedConditional
Definition: BayesTree.h:78
gtsam::BayesTree::This
BayesTree< CLIQUE > This
Definition: BayesTree.h:69
gtsam::tol
const G double tol
Definition: Group.h:79
FastList.h
A thin wrapper around std::list that uses boost's fast_pool_allocator.
gtsam::BayesTree::sharedNode
sharedClique sharedNode
Synonym for sharedClique (TODO: remove)
Definition: BayesTree.h:76
gtsam::BayesTree::equals
bool equals(const This &other, double tol=1e-9) const
Definition: BayesTree-inst.h:269
gtsam::BayesTree::clear
void clear()
Definition: BayesTree-inst.h:449
gtsam::BayesTree::saveGraph
void saveGraph(const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
output to file with graphviz format.
Definition: BayesTree-inst.h:85
gtsam::BayesTree::joint
sharedFactorGraph joint(Key j1, Key j2, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Definition: BayesTree-inst.h:332
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::BayesTree::numCachedSeparatorMarginals
size_t numCachedSeparatorMarginals() const
Definition: BayesTree-inst.h:55
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
j1
double j1(double x)
Definition: j1.c:174
gtsam::BayesTree::Cliques
FastList< sharedClique > Cliques
Definition: BayesTree.h:89
gtsam::BayesTree::Clique
CLIQUE Clique
The clique type, normally BayesTreeClique.
Definition: BayesTree.h:73
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::BayesTreeOrphanWrapper::CliqueType
CLIQUE CliqueType
Definition: BayesTree.h:283


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:01:46