BayesTreeCliqueBase.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 #pragma once
19 
20 #include <gtsam/inference/Key.h>
22 #include <gtsam/base/types.h>
23 #include <gtsam/base/FastVector.h>
24 
25 #include <string>
26 #include <mutex>
27 #include <optional>
28 
29 namespace gtsam {
30 
31  // Forward declarations
32  template<class CLIQUE> class BayesTree;
33  template<class GRAPH> struct EliminationTraits;
34 
48  template<class DERIVED, class FACTORGRAPH>
50  {
51  private:
53  typedef DERIVED DerivedType;
55  typedef std::shared_ptr<This> shared_ptr;
56  typedef std::weak_ptr<This> weak_ptr;
57  typedef std::shared_ptr<DerivedType> derived_ptr;
58  typedef std::weak_ptr<DerivedType> derived_weak_ptr;
59 
60  public:
61  typedef FACTORGRAPH FactorGraphType;
64  typedef std::shared_ptr<ConditionalType> sharedConditional;
67 
68  protected:
69 
72 
75 
78  BayesTreeCliqueBase(const sharedConditional& conditional)
79  : conditional_(conditional), problemSize_(1) {}
80 
84  parent_(c.parent_),
85  children(c.children),
87  is_root(c.is_root) {}
88 
92  parent_ = c.parent_;
93  children = c.children;
95  is_root = c.is_root;
96  return *this;
97  }
98 
99  // Virtual destructor.
100  virtual ~BayesTreeCliqueBase() {}
101 
103 
105  mutable std::optional<FactorGraphType> cachedSeparatorMarginal_;
110  mutable std::mutex cachedSeparatorMarginalMutex_;
111 
112  public:
113  sharedConditional conditional_;
114  derived_weak_ptr parent_;
117 
118  bool is_root = false;
119 
123  void setEliminationResult(const typename FactorGraphType::EliminationResult& eliminationResult);
124 
127 
129  bool equals(const DERIVED& other, double tol = 1e-9) const;
130 
132  virtual void print(
133  const std::string& s = "",
134  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
135 
139 
141  const sharedConditional& conditional() const { return conditional_; }
142 
144  inline bool isRoot() const { return parent_.expired(); }
145 
147  size_t treeSize() const;
148 
150  size_t numCachedSeparatorMarginals() const;
151 
153  derived_ptr parent() const { return parent_.lock(); }
154 
156  int problemSize() const { return problemSize_; }
157 
161 
163  BayesNetType shortcut(const derived_ptr& root, Eliminate function = EliminationTraitsType::DefaultEliminate) const;
164 
166  FactorGraphType separatorMarginal(Eliminate function = EliminationTraitsType::DefaultEliminate) const;
167 
169  FactorGraphType marginal2(Eliminate function = EliminationTraitsType::DefaultEliminate) const;
170 
175  void deleteCachedShortcuts();
176 
177  const std::optional<FactorGraphType>& cachedSeparatorMarginal() const {
178  std::lock_guard<std::mutex> marginalLock(cachedSeparatorMarginalMutex_);
179  return cachedSeparatorMarginal_;
180  }
181 
182  friend class BayesTree<DerivedType>;
183 
184  protected:
185 
187  KeyVector separator_setminus_B(const derived_ptr& B) const;
188 
192  KeyVector shortcut_indices(const derived_ptr& B, const FactorGraphType& p_Cp_B) const;
193 
196  std::lock_guard<std::mutex> marginalLock(cachedSeparatorMarginalMutex_);
197  cachedSeparatorMarginal_ = {};
198  }
199 
200  private:
201 
202 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
203 
204  friend class boost::serialization::access;
205  template<class ARCHIVE>
206  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
207  if(!parent_.lock()) {
208  is_root = true;
209  }
210  ar & BOOST_SERIALIZATION_NVP(is_root);
211  ar & BOOST_SERIALIZATION_NVP(conditional_);
212  if (!is_root) { // TODO(fan): Workaround for boost/serialization #119
213  ar & BOOST_SERIALIZATION_NVP(parent_);
214  }
215  ar & BOOST_SERIALIZATION_NVP(children);
216  }
217 #endif
218 
220 
221  };
222 
223 }
Typedefs for easier changing of types.
std::string serialize(const T &input)
serializes to a string
FactorGraphType::Eliminate Eliminate
BayesTreeCliqueBase(const BayesTreeCliqueBase &c)
Shallow copy constructor.
std::optional< FactorGraphType > cachedSeparatorMarginal_
This stores the Cached separator marginal P(S)
std::weak_ptr< This > weak_ptr
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
std::weak_ptr< DerivedType > derived_weak_ptr
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
EliminationTraitsType::BayesNetType BayesNetType
bool equals(const DERIVED &other, double tol=1e-9) const
BayesTreeCliqueBase(const sharedConditional &conditional)
std::shared_ptr< DerivedType > derived_ptr
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const std::optional< FactorGraphType > & cachedSeparatorMarginal() const
void setEliminationResult(const typename FactorGraphType::EliminationResult &eliminationResult)
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
std::function< EliminationResult(const FactorGraphType &, const Ordering &)> Eliminate
The function type that does a single dense elimination step on a subgraph.
std::pair< std::shared_ptr< ConditionalType >, std::shared_ptr< _FactorType > > EliminationResult
std::shared_ptr< ConditionalType > sharedConditional
std::shared_ptr< This > shared_ptr
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
FastVector< derived_ptr > children
EliminationTraits< FACTORGRAPH > EliminationTraitsType
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
A thin wrapper around std::vector that uses a custom allocator.
traits
Definition: chartTesting.h:28
BayesNetType shortcut(const derived_ptr &root, Eliminate function=EliminationTraitsType::DefaultEliminate) const
FactorGraphType separatorMarginal(Eliminate function=EliminationTraitsType::DefaultEliminate) const
FactorGraphType marginal2(Eliminate function=EliminationTraitsType::DefaultEliminate) const
BayesTreeCliqueBase()
Default constructor.
BayesTreeCliqueBase & operator=(const BayesTreeCliqueBase &c)
Shallow copy assignment constructor.
KeyVector shortcut_indices(const derived_ptr &B, const FactorGraphType &p_Cp_B) const
BayesTreeCliqueBase< DERIVED, FACTORGRAPH > This
KeyVector separator_setminus_B(const derived_ptr &B) const
Calculate set for shortcut calculations.
const G double tol
Definition: Group.h:86
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
const sharedConditional & conditional() const
BayesNetType::ConditionalType ConditionalType
FactorGraphType::FactorType FactorType


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:33:57