Public Types | Public Member Functions | Private Types | List of all members
gtsam::GaussianBayesTree Class Reference

#include <GaussianBayesTree.h>

Inheritance diagram for gtsam::GaussianBayesTree:
Inheritance graph
[legend]

Public Types

typedef std::shared_ptr< Thisshared_ptr
 
typedef GaussianBayesTree This
 
- Public Types inherited from gtsam::BayesTree< GaussianBayesTreeClique >
typedef GaussianBayesTreeClique ::BayesNetType BayesNetType
 
typedef GaussianBayesTreeClique Clique
 The clique type, normally BayesTreeClique. More...
 
typedef FastList< sharedCliqueCliques
 
typedef GaussianBayesTreeClique ::ConditionalType ConditionalType
 
typedef FactorGraphType::Eliminate Eliminate
 
typedef GaussianBayesTreeClique ::EliminationTraitsType EliminationTraitsType
 
typedef GaussianBayesTreeClique ::FactorGraphType FactorGraphType
 
typedef GaussianBayesTreeClique ::FactorType FactorType
 
typedef Clique Node
 Synonym for Clique (TODO: remove) More...
 
typedef ConcurrentMap< Key, sharedCliqueNodes
 
typedef FastVector< sharedCliqueRoots
 
typedef std::shared_ptr< BayesNetTypesharedBayesNet
 
typedef std::shared_ptr< CliquesharedClique
 Shared pointer to a clique. More...
 
typedef std::shared_ptr< ConditionalTypesharedConditional
 
typedef std::shared_ptr< FactorTypesharedFactor
 
typedef std::shared_ptr< FactorGraphTypesharedFactorGraph
 
typedef sharedClique sharedNode
 Synonym for sharedClique (TODO: remove) More...
 

Public Member Functions

double determinant () const
 
bool equals (const This &other, double tol=1e-9) const
 
double error (const VectorValues &x) const
 
 GaussianBayesTree ()
 
VectorValues gradient (const VectorValues &x0) const
 
VectorValues gradientAtZero () const
 
double logDeterminant () const
 
Matrix marginalCovariance (Key key) const
 
VectorValues optimize () const
 
VectorValues optimizeGradientSearch () const
 
- Public Member Functions inherited from gtsam::BayesTree< GaussianBayesTreeClique >
size_t size () const
 
bool empty () const
 
const Nodesnodes () const
 
sharedClique operator[] (Key j) const
 
const Rootsroots () const
 
const sharedCliqueclique (Key j) const
 
BayesTreeCliqueData getCliqueData () const
 
size_t numCachedSeparatorMarginals () const
 
sharedConditional marginalFactor (Key j, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
 
sharedFactorGraph joint (Key j1, Key j2, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
 
sharedBayesNet jointBayesNet (Key j1, Key j2, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
 
void dot (std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 Output to graphviz format, stream version. More...
 
std::string dot (const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 Output to graphviz format string. More...
 
void saveGraph (const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 output to file with graphviz format. More...
 
Key findParentClique (const CONTAINER &parents) const
 
void clear ()
 
void deleteCachedShortcuts ()
 
void removePath (sharedClique clique, BayesNetType *bn, Cliques *orphans)
 
void removeTop (const KeyVector &keys, BayesNetType *bn, Cliques *orphans)
 
Cliques removeSubtree (const sharedClique &subtree)
 
void insertRoot (const sharedClique &subtree)
 
void addClique (const sharedClique &clique, const sharedClique &parent_clique=sharedClique())
 
void addFactorsToGraph (FactorGraph< FactorType > *graph) const
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 

Private Types

typedef BayesTree< GaussianBayesTreeCliqueBase
 

Additional Inherited Members

- Protected Types inherited from gtsam::BayesTree< GaussianBayesTreeClique >
typedef std::shared_ptr< Thisshared_ptr
 
typedef BayesTree< GaussianBayesTreeCliqueThis
 
- Protected Member Functions inherited from gtsam::BayesTree< GaussianBayesTreeClique >
Thisoperator= (const This &other)
 
 ~BayesTree ()
 
 BayesTree ()
 
 BayesTree (const This &other)
 
void getCliqueData (sharedClique clique, BayesTreeCliqueData *stats) const
 
void dot (std::ostream &s, sharedClique clique, const KeyFormatter &keyFormatter, int parentnum=0) const
 
void removeClique (sharedClique clique)
 
void fillNodesIndex (const sharedClique &subtree)
 
bool equals (const This &other, double tol=1e-9) const
 
- Protected Attributes inherited from gtsam::BayesTree< GaussianBayesTreeClique >
Nodes nodes_
 
Roots roots_
 

Detailed Description

A Bayes tree representing a Gaussian density

Definition at line 49 of file GaussianBayesTree.h.

Member Typedef Documentation

◆ Base

Definition at line 53 of file GaussianBayesTree.h.

◆ shared_ptr

typedef std::shared_ptr<This> gtsam::GaussianBayesTree::shared_ptr

Definition at line 57 of file GaussianBayesTree.h.

◆ This

Definition at line 56 of file GaussianBayesTree.h.

Constructor & Destructor Documentation

◆ GaussianBayesTree()

gtsam::GaussianBayesTree::GaussianBayesTree ( )
inline

Default constructor, creates an empty Bayes tree

Definition at line 60 of file GaussianBayesTree.h.

Member Function Documentation

◆ determinant()

double gtsam::GaussianBayesTree::determinant ( ) const

Computes the determinant of a GassianBayesTree, as if the Bayes tree is reorganized into a matrix. A GassianBayesTree is equivalent to an upper triangular matrix, and for an upper triangular matrix determinant is the product of the diagonal elements. Instead of actually multiplying we add the logarithms of the diagonal elements and take the exponent at the end because this is more numerically stable.

Definition at line 114 of file GaussianBayesTree.cpp.

◆ equals()

bool gtsam::GaussianBayesTree::equals ( const This other,
double  tol = 1e-9 
) const

Check equality

Definition at line 61 of file GaussianBayesTree.cpp.

◆ error()

double gtsam::GaussianBayesTree::error ( const VectorValues x) const

0.5 * sum of squared Mahalanobis distances.

Definition at line 90 of file GaussianBayesTree.cpp.

◆ gradient()

VectorValues gtsam::GaussianBayesTree::gradient ( const VectorValues x0) const

Compute the gradient of the energy function, $ \nabla_{x=x_0} \left\Vert \Sigma^{-1} R x - d \right\Vert^2 $, centered around $ x = x_0 $. The gradient is $ R^T(Rx-d) $.

Parameters
x0The center about which to compute the gradient
Returns
The gradient as a VectorValues

Definition at line 80 of file GaussianBayesTree.cpp.

◆ gradientAtZero()

VectorValues gtsam::GaussianBayesTree::gradientAtZero ( ) const

Compute the gradient of the energy function, $ \nabla_{x=0} \left\Vert \Sigma^{-1} R x - d \right\Vert^2 $, centered around zero. The gradient about zero is $ -R^T d $. See also gradient(const GaussianBayesNet&, const VectorValues&).

Returns
A VectorValues storing the gradient.

Definition at line 85 of file GaussianBayesTree.cpp.

◆ logDeterminant()

double gtsam::GaussianBayesTree::logDeterminant ( ) const

Computes the determinant of a GassianBayesTree, as if the Bayes tree is reorganized into a matrix. A GassianBayesTree is equivalent to an upper triangular matrix, and for an upper triangular matrix determinant is the product of the diagonal elements. Instead of actually multiplying we add the logarithms of the diagonal elements and take the exponent at the end because this is more numerically stable.

Definition at line 95 of file GaussianBayesTree.cpp.

◆ marginalCovariance()

Matrix gtsam::GaussianBayesTree::marginalCovariance ( Key  key) const

Return the marginal on the requested variable as a covariance matrix. See also marginalFactor().

Definition at line 120 of file GaussianBayesTree.cpp.

◆ optimize()

VectorValues gtsam::GaussianBayesTree::optimize ( ) const

Recursively optimize the BayesTree to produce a vector solution.

Definition at line 67 of file GaussianBayesTree.cpp.

◆ optimizeGradientSearch()

VectorValues gtsam::GaussianBayesTree::optimizeGradientSearch ( ) const

Optimize along the gradient direction, with a closed-form computation to perform the line search. The gradient is computed about $ \delta x=0 $.

This function returns $ \delta x $ that minimizes a reparametrized problem. The error function of a GaussianBayesNet is

\[ f(\delta x) = \frac{1}{2} |R \delta x - d|^2 = \frac{1}{2}d^T d - d^T R \delta x + \frac{1}{2} \delta x^T R^T R \delta x \]

with gradient and Hessian

\[ g(\delta x) = R^T(R\delta x - d), \qquad G(\delta x) = R^T R. \]

This function performs the line search in the direction of the gradient evaluated at $ g = g(\delta x = 0) $ with step size $ \alpha $ that minimizes $ f(\delta x = \alpha g) $:

\[ f(\alpha) = \frac{1}{2} d^T d + g^T \delta x + \frac{1}{2} \alpha^2 g^T G g \]

Optimizing by setting the derivative to zero yields $ \hat \alpha = (-g^T g) / (g^T G g) $. For efficiency, this function evaluates the denominator without computing the Hessian $ G $, returning

\[ \delta x = \hat\alpha g = \frac{-g^T g}{(R g)^T(R g)} \]

Definition at line 73 of file GaussianBayesTree.cpp.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:19