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 <gtsam/inference/Key.h>
23 #include <gtsam/base/FastList.h>
25 #include <gtsam/base/FastVector.h>
26 
27 #include <string>
28 
29 namespace gtsam {
30 
31  // Forward declarations
32  template<class FACTOR> class FactorGraph;
33  template<class BAYESTREE, class GRAPH> class EliminatableClusterTree;
34 
35  /* ************************************************************************* */
37  struct GTSAM_EXPORT BayesTreeCliqueStats {
42  void print(const std::string& s = "") const ;
43  };
44 
46  struct GTSAM_EXPORT BayesTreeCliqueData {
49  BayesTreeCliqueStats getStats() const;
50  };
51 
52  /* ************************************************************************* */
63  template<class CLIQUE>
64  class BayesTree
65  {
66  protected:
68  typedef boost::shared_ptr<This> shared_ptr;
69 
70  public:
71  typedef CLIQUE Clique;
72  typedef boost::shared_ptr<Clique> sharedClique;
73  typedef Clique Node;
74  typedef sharedClique sharedNode;
75  typedef typename CLIQUE::ConditionalType ConditionalType;
76  typedef boost::shared_ptr<ConditionalType> sharedConditional;
77  typedef typename CLIQUE::BayesNetType BayesNetType;
78  typedef boost::shared_ptr<BayesNetType> sharedBayesNet;
79  typedef typename CLIQUE::FactorType FactorType;
80  typedef boost::shared_ptr<FactorType> sharedFactor;
81  typedef typename CLIQUE::FactorGraphType FactorGraphType;
82  typedef boost::shared_ptr<FactorGraphType> sharedFactorGraph;
84  typedef typename CLIQUE::EliminationTraitsType EliminationTraitsType;
85 
88 
91 
94 
95  protected:
96 
98  Nodes nodes_;
99 
101  Roots roots_;
102 
105 
108 
110  BayesTree(const This& other);
111 
113 
115  This& operator=(const This& other);
116 
119 
121  bool equals(const This& other, double tol = 1e-9) const;
122 
123  public:
125  void print(const std::string& s = "",
126  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
128 
131 
133  size_t size() const;
134 
136  inline bool empty() const {
137  return nodes_.empty();
138  }
139 
141  const Nodes& nodes() const { return nodes_; }
142 
144  const sharedNode operator[](Key j) const { return nodes_.at(j); }
145 
147  const Roots& roots() const { return roots_; }
148 
150  const sharedClique& clique(Key j) const {
151  typename Nodes::const_iterator c = nodes_.find(j);
152  if(c == nodes_.end())
153  throw std::out_of_range("Requested the BayesTree clique for a key that is not in the BayesTree");
154  else
155  return c->second;
156  }
157 
159  BayesTreeCliqueData getCliqueData() const;
160 
162  size_t numCachedSeparatorMarginals() const;
163 
169  sharedConditional marginalFactor(Key j, const Eliminate& function = EliminationTraitsType::DefaultEliminate) const;
170 
175  sharedFactorGraph joint(Key j1, Key j2, const Eliminate& function = EliminationTraitsType::DefaultEliminate) const;
176 
181  sharedBayesNet jointBayesNet(Key j1, Key j2, const Eliminate& function = EliminationTraitsType::DefaultEliminate) const;
182 
188  void saveGraph(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
189 
193 
198  template<class CONTAINER>
199  Key findParentClique(const CONTAINER& parents) const;
200 
202  void clear();
203 
205  void deleteCachedShortcuts();
206 
211  void removePath(sharedClique clique, BayesNetType* bn, Cliques* orphans);
212 
217  void removeTop(const KeyVector& keys, BayesNetType* bn, Cliques* orphans);
218 
221  Cliques removeSubtree(const sharedClique& subtree);
222 
226  void insertRoot(const sharedClique& subtree);
227 
229  void addClique(const sharedClique& clique, const sharedClique& parent_clique = sharedClique());
230 
232  void addFactorsToGraph(FactorGraph<FactorType>* graph) const;
233 
234  protected:
235 
237  void saveGraph(std::ostream &s, sharedClique clique, const KeyFormatter& keyFormatter,
238  int parentnum = 0) const;
239 
241  void getCliqueData(sharedClique clique, BayesTreeCliqueData* stats) const;
242 
244  void removeClique(sharedClique clique);
245 
247  void fillNodesIndex(const sharedClique& subtree);
248 
249  // Friend JunctionTree because it directly fills roots and nodes index.
250  template<class BAYESRTEE, class GRAPH> friend class EliminatableClusterTree;
251 
252  private:
254  friend class boost::serialization::access;
255  template<class ARCHIVE>
256  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
257  ar & BOOST_SERIALIZATION_NVP(nodes_);
258  ar & BOOST_SERIALIZATION_NVP(roots_);
259  }
260 
262 
263  }; // BayesTree
264 
265  /* ************************************************************************* */
266  template<class CLIQUE>
267  class BayesTreeOrphanWrapper : public CLIQUE::ConditionalType
268  {
269  public:
270  typedef CLIQUE CliqueType;
271  typedef typename CLIQUE::ConditionalType Base;
272 
273  boost::shared_ptr<CliqueType> clique;
274 
275  BayesTreeOrphanWrapper(const boost::shared_ptr<CliqueType>& clique) :
276  clique(clique)
277  {
278  // Store parent keys in our base type factor so that eliminating those parent keys will pull
279  // this subtree into the elimination.
280  this->keys_.assign(clique->conditional()->beginParents(), clique->conditional()->endParents());
281  }
282 
283  void print(const std::string& s="", const KeyFormatter& formatter = DefaultKeyFormatter) const override {
284  clique->print(s + "stored clique", formatter);
285  }
286  };
287 
288 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const sharedNode operator[](Key j) const
Definition: BayesTree.h:144
BayesTree< CLIQUE > This
Definition: BayesTree.h:67
boost::shared_ptr< Clique > sharedClique
Shared pointer to a clique.
Definition: BayesTree.h:72
FactorGraphType::Eliminate Eliminate
Definition: BayesTree.h:83
sharedClique sharedNode
Synonym for sharedClique (TODO: remove)
Definition: BayesTree.h:74
A thin wrapper around std::list that uses boost&#39;s fast_pool_allocator.
std::size_t maxSeparatorSize
Definition: BayesTree.h:41
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
Definition: BayesTree.h:283
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
const Nodes & nodes() const
Definition: BayesTree.h:141
CLIQUE::ConditionalType Base
Definition: BayesTree.h:271
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
Clique Node
Synonym for Clique (TODO: remove)
Definition: BayesTree.h:73
bool stats
const KeyFormatter & formatter
CLIQUE::EliminationTraitsType EliminationTraitsType
Definition: BayesTree.h:84
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
const sharedClique & clique(Key j) const
Definition: BayesTree.h:150
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
FastVector< std::size_t > conditionalSizes
Definition: BayesTree.h:47
CLIQUE Clique
The clique type, normally BayesTreeClique.
Definition: BayesTree.h:71
CLIQUE::ConditionalType ConditionalType
Definition: BayesTree.h:75
FastVector< std::size_t > separatorSizes
Definition: BayesTree.h:48
bool empty() const
Definition: BayesTree.h:136
BayesTreeOrphanWrapper(const boost::shared_ptr< CliqueType > &clique)
Definition: BayesTree.h:275
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
ConcurrentMap< Key, sharedClique > Nodes
Definition: BayesTree.h:90
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
boost::shared_ptr< FactorType > sharedFactor
Definition: BayesTree.h:80
boost::shared_ptr< CliqueType > clique
Definition: BayesTree.h:273
CLIQUE::FactorGraphType FactorGraphType
Definition: BayesTree.h:81
A thin wrapper around std::vector that uses a custom allocator.
traits
Definition: chartTesting.h:28
boost::shared_ptr< This > shared_ptr
Definition: BayesTree.h:68
boost::shared_ptr< FactorGraphType > sharedFactorGraph
Definition: BayesTree.h:82
boost::shared_ptr< BayesNetType > sharedBayesNet
Definition: BayesTree.h:78
void serialize(ARCHIVE &ar, const unsigned int)
Definition: BayesTree.h:256
boost::function< EliminationResult(const FactorGraphType &, const Ordering &)> Eliminate
The function type that does a single dense elimination step on a subgraph.
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
FastList< sharedClique > Cliques
Definition: BayesTree.h:87
FastVector< sharedClique > Roots
Definition: BayesTree.h:93
CLIQUE::BayesNetType BayesNetType
Definition: BayesTree.h:77
boost::shared_ptr< ConditionalType > sharedConditional
Definition: BayesTree.h:76
const G double tol
Definition: Group.h:83
const KeyVector keys
std::size_t maxConditionalSize
Definition: BayesTree.h:39
const Roots & roots() const
Definition: BayesTree.h:147
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
CLIQUE::FactorType FactorType
Definition: BayesTree.h:79


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