Public Types | Public Member Functions | Public Attributes | Protected Attributes | Private Types | List of all members
gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH > Class Template Reference

#include <BayesTreeCliqueBase.h>

Public Types

typedef EliminationTraitsType::BayesNetType BayesNetType
 
typedef BayesNetType::ConditionalType ConditionalType
 
typedef FactorGraphType::Eliminate Eliminate
 
typedef FACTORGRAPH FactorGraphType
 
typedef FactorGraphType::FactorType FactorType
 
typedef boost::shared_ptr< ConditionalTypesharedConditional
 

Public Member Functions

void setEliminationResult (const typename FactorGraphType::EliminationResult &eliminationResult)
 

Public Attributes

FastVector< derived_ptrchildren
 
sharedConditional conditional_
 
bool is_root = false
 
derived_weak_ptr parent_
 
int problemSize_
 

Protected Attributes

boost::optional< FactorGraphTypecachedSeparatorMarginal_
 This stores the Cached separator marginal P(S) More...
 
std::mutex cachedSeparatorMarginalMutex_
 

Private Types

typedef boost::shared_ptr< DerivedTypederived_ptr
 
typedef boost::weak_ptr< DerivedTypederived_weak_ptr
 
typedef DERIVED DerivedType
 
typedef EliminationTraits< FACTORGRAPH > EliminationTraitsType
 
typedef boost::shared_ptr< Thisshared_ptr
 
typedef BayesTreeCliqueBase< DERIVED, FACTORGRAPH > This
 
typedef boost::weak_ptr< Thisweak_ptr
 

Standard Constructors

 BayesTreeCliqueBase ()
 
 BayesTreeCliqueBase (const sharedConditional &conditional)
 
 BayesTreeCliqueBase (const BayesTreeCliqueBase &c)
 
BayesTreeCliqueBaseoperator= (const BayesTreeCliqueBase &c)
 

Testable

bool equals (const DERIVED &other, double tol=1e-9) const
 
virtual void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 

Standard Interface

const sharedConditionalconditional () const
 
bool isRoot () const
 
size_t treeSize () const
 
size_t numCachedSeparatorMarginals () const
 
derived_ptr parent () const
 
int problemSize () const
 

Advanced Interface

class BayesTree< DerivedType >
 
class boost::serialization::access
 
KeyVector separator_setminus_B (const derived_ptr &B) const
 Calculate set $ S \setminus B $ for shortcut calculations. More...
 
KeyVector shortcut_indices (const derived_ptr &B, const FactorGraphType &p_Cp_B) const
 
void deleteCachedShortcutsNonRecursive ()
 
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
 
void deleteCachedShortcuts ()
 
const boost::optional< FactorGraphType > & cachedSeparatorMarginal () const
 
template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Detailed Description

template<class DERIVED, class FACTORGRAPH>
class gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >

This is the base class for BayesTree cliques. The default and standard derived type is BayesTreeClique, but some algorithms, like iSAM2, use a different clique type in order to store extra data along with the clique.

This class is templated on the derived class (i.e. the curiously recursive template pattern). The advantage of this over using virtual classes is that it avoids the need for casting to get the derived type. This is possible because all cliques in a BayesTree are the same type - if they were not then we'd need a virtual class.

Template Parameters
DERIVEDThe derived clique type.
CONDITIONALThe conditional type.

Definition at line 49 of file BayesTreeCliqueBase.h.

Member Typedef Documentation

template<class DERIVED, class FACTORGRAPH>
typedef EliminationTraitsType::BayesNetType gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::BayesNetType

Definition at line 62 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef BayesNetType::ConditionalType gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::ConditionalType

Definition at line 63 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef boost::shared_ptr<DerivedType> gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::derived_ptr
private

Definition at line 57 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef boost::weak_ptr<DerivedType> gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::derived_weak_ptr
private

Definition at line 58 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef DERIVED gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::DerivedType
private

Definition at line 53 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef FactorGraphType::Eliminate gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::Eliminate

Definition at line 66 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef EliminationTraits<FACTORGRAPH> gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::EliminationTraitsType
private

Definition at line 54 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef FACTORGRAPH gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::FactorGraphType

Definition at line 61 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef FactorGraphType::FactorType gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::FactorType

Definition at line 65 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef boost::shared_ptr<This> gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::shared_ptr
private

Definition at line 55 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef boost::shared_ptr<ConditionalType> gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::sharedConditional

Definition at line 64 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef BayesTreeCliqueBase<DERIVED, FACTORGRAPH> gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::This
private

Definition at line 52 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
typedef boost::weak_ptr<This> gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::weak_ptr
private

Definition at line 56 of file BayesTreeCliqueBase.h.

Constructor & Destructor Documentation

template<class DERIVED, class FACTORGRAPH>
gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::BayesTreeCliqueBase ( )
inlineprotected

Default constructor

Definition at line 74 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::BayesTreeCliqueBase ( const sharedConditional conditional)
inlineprotected

Construct from a conditional, leaving parent and child pointers uninitialized

Definition at line 77 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::BayesTreeCliqueBase ( const BayesTreeCliqueBase< DERIVED, FACTORGRAPH > &  c)
inlineprotected

Shallow copy constructor

Definition at line 80 of file BayesTreeCliqueBase.h.

Member Function Documentation

template<class DERIVED, class FACTORGRAPH>
const boost::optional<FactorGraphType>& gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::cachedSeparatorMarginal ( ) const
inline

Definition at line 165 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
const sharedConditional& gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::conditional ( ) const
inline

Access the conditional

Definition at line 129 of file BayesTreeCliqueBase.h.

template<class DERIVED , class FACTORGRAPH >
void gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::deleteCachedShortcuts ( )

This deletes the cached shortcuts of all cliques (subtree) below this clique. This is performed when the bayes tree is modified.

Definition at line 206 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED, class FACTORGRAPH>
void gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::deleteCachedShortcutsNonRecursive ( )
inlineprotected

Non-recursive delete cached shortcuts and marginals - internal only.

Definition at line 183 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH >
bool gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::equals ( const DERIVED &  other,
double  tol = 1e-9 
) const

check equality

Definition at line 34 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED, class FACTORGRAPH>
bool gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::isRoot ( ) const
inline

is this the root of a Bayes tree ?

Definition at line 132 of file BayesTreeCliqueBase.h.

template<class DERIVED , class FACTORGRAPH >
BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::FactorGraphType gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::marginal2 ( Eliminate  function = EliminationTraitsType::DefaultEliminate) const

return the marginal P(C) of the clique, using marginal caching

Definition at line 194 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED , class FACTORGRAPH >
size_t gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::numCachedSeparatorMarginals ( ) const

Collect number of cliques with cached separator marginals

Definition at line 92 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED, class FACTORGRAPH>
BayesTreeCliqueBase& gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::operator= ( const BayesTreeCliqueBase< DERIVED, FACTORGRAPH > &  c)
inlineprotected

Shallow copy assignment constructor

Definition at line 83 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
derived_ptr gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::parent ( ) const
inline

return a shared_ptr to the parent clique

Definition at line 141 of file BayesTreeCliqueBase.h.

template<class DERIVED , class FACTORGRAPH >
void gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
virtual

print this node

Reimplemented in gtsam::ISAM2Clique.

Definition at line 75 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED, class FACTORGRAPH>
int gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::problemSize ( ) const
inline

Problem size (used for parallel traversal)

Definition at line 144 of file BayesTreeCliqueBase.h.

template<class DERIVED , class FACTORGRAPH >
KeyVector gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::separator_setminus_B ( const derived_ptr B) const
protected

Calculate set $ S \setminus B $ for shortcut calculations.

Definition at line 44 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED , class FACTORGRAPH >
BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::FactorGraphType gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::separatorMarginal ( Eliminate  function = EliminationTraitsType::DefaultEliminate) const

return the marginal P(S) on the separator

Definition at line 146 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED, class FACTORGRAPH>
template<class ARCHIVE >
void gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 193 of file BayesTreeCliqueBase.h.

template<class DERIVED , class FACTORGRAPH >
void gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::setEliminationResult ( const typename FactorGraphType::EliminationResult &  eliminationResult)

Fill the elimination result produced during elimination. Here this just stores the conditional and ignores the remaining factor, but this is overridden in ISAM2Clique to also cache the remaining factor.

Definition at line 26 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED , class FACTORGRAPH >
BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::BayesNetType gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::shortcut ( const derived_ptr root,
Eliminate  function = EliminationTraitsType::DefaultEliminate 
) const

return the conditional P(S|Root) on the separator given the root

Definition at line 112 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED , class FACTORGRAPH >
KeyVector gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::shortcut_indices ( const derived_ptr B,
const FactorGraphType p_Cp_B 
) const
protected

Determine variable indices to keep in recursive separator shortcut calculation The factor graph p_Cp_B has keys from the parent clique Cp and from B. But we only keep the variables not in S union B.

Definition at line 56 of file BayesTreeCliqueBase-inst.h.

template<class DERIVED , class FACTORGRAPH >
size_t gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::treeSize ( ) const

The size of subtree rooted at this clique, i.e., nr of Cliques

Definition at line 83 of file BayesTreeCliqueBase-inst.h.

Friends And Related Function Documentation

template<class DERIVED, class FACTORGRAPH>
friend class BayesTree< DerivedType >
friend

Definition at line 170 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
friend class boost::serialization::access
friend

Serialization function

Definition at line 191 of file BayesTreeCliqueBase.h.

Member Data Documentation

template<class DERIVED, class FACTORGRAPH>
boost::optional<FactorGraphType> gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::cachedSeparatorMarginal_
mutableprotected

This stores the Cached separator marginal P(S)

Definition at line 95 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
std::mutex gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::cachedSeparatorMarginalMutex_
mutableprotected

This protects Cached seperator marginal P(S) from concurrent read/writes as many the functions which access it are const (hence the mutable) leading to the false impression that these const functions are thread-safe which is not true due to these mutable values. This is fixed by applying this mutex.

Definition at line 100 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
FastVector<derived_ptr> gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::children

Definition at line 105 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
sharedConditional gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::conditional_

Definition at line 103 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
bool gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::is_root = false

Definition at line 108 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
derived_weak_ptr gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::parent_

Definition at line 104 of file BayesTreeCliqueBase.h.

template<class DERIVED, class FACTORGRAPH>
int gtsam::BayesTreeCliqueBase< DERIVED, FACTORGRAPH >::problemSize_

Definition at line 106 of file BayesTreeCliqueBase.h.


The documentation for this class was generated from the following files:


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