Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gtsam::Marginals Class Reference

#include <Marginals.h>

Public Types

enum  Factorization { CHOLESKY, QR }
 

Public Member Functions

JointMarginal jointMarginalCovariance (const KeyVector &variables) const
 
JointMarginal jointMarginalInformation (const KeyVector &variables) const
 
Matrix marginalCovariance (Key variable) const
 
GaussianFactor::shared_ptr marginalFactor (Key variable) const
 
Matrix marginalInformation (Key variable) const
 
 Marginals ()
 Default constructor only for wrappers. More...
 
 Marginals (const NonlinearFactorGraph &graph, const Values &solution, Factorization factorization=CHOLESKY)
 
 Marginals (const NonlinearFactorGraph &graph, const Values &solution, const Ordering &ordering, Factorization factorization=CHOLESKY)
 
 Marginals (const GaussianFactorGraph &graph, const Values &solution, Factorization factorization=CHOLESKY)
 
 Marginals (const GaussianFactorGraph &graph, const Values &solution, const Ordering &ordering, Factorization factorization=CHOLESKY)
 
 Marginals (const GaussianFactorGraph &graph, const VectorValues &solution, Factorization factorization=CHOLESKY)
 
 Marginals (const GaussianFactorGraph &graph, const VectorValues &solution, const Ordering &ordering, Factorization factorization=CHOLESKY)
 
VectorValues optimize () const
 
void print (const std::string &str="Marginals: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 

Protected Member Functions

void computeBayesTree ()
 
void computeBayesTree (const Ordering &ordering)
 

Protected Attributes

GaussianBayesTree bayesTree_
 
Factorization factorization_
 
GaussianFactorGraph graph_
 
Values values_
 

Detailed Description

A class for computing Gaussian marginals of variables in a NonlinearFactorGraph

Definition at line 32 of file Marginals.h.

Member Enumeration Documentation

◆ Factorization

The linear factorization mode - either CHOLESKY (faster and suitable for most problems) or QR (slower but more numerically stable for poorly-conditioned problems).

Enumerator
CHOLESKY 
QR 

Definition at line 37 of file Marginals.h.

Constructor & Destructor Documentation

◆ Marginals() [1/7]

gtsam::Marginals::Marginals ( )
inline

Default constructor only for wrappers.

Definition at line 52 of file Marginals.h.

◆ Marginals() [2/7]

gtsam::Marginals::Marginals ( const NonlinearFactorGraph graph,
const Values solution,
Factorization  factorization = CHOLESKY 
)

Construct a marginals class from a nonlinear factor graph.

Parameters
graphThe factor graph defining the full joint density on all variables.
solutionThe linearization point about which to compute Gaussian marginals (usually the MLE as obtained from a NonlinearOptimizer).
factorizationThe linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems).

Definition at line 29 of file Marginals.cpp.

◆ Marginals() [3/7]

gtsam::Marginals::Marginals ( const NonlinearFactorGraph graph,
const Values solution,
const Ordering ordering,
Factorization  factorization = CHOLESKY 
)

Construct a marginals class from a nonlinear factor graph.

Parameters
graphThe factor graph defining the full joint density on all variables.
solutionThe linearization point about which to compute Gaussian marginals (usually the MLE as obtained from a NonlinearOptimizer).
factorizationThe linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems).
orderingThe ordering for elimination.

Definition at line 37 of file Marginals.cpp.

◆ Marginals() [4/7]

gtsam::Marginals::Marginals ( const GaussianFactorGraph graph,
const Values solution,
Factorization  factorization = CHOLESKY 
)

Construct a marginals class from a linear factor graph.

Parameters
graphThe factor graph defining the full joint density on all variables.
solutionThe solution point to compute Gaussian marginals.
factorizationThe linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems).

Definition at line 46 of file Marginals.cpp.

◆ Marginals() [5/7]

gtsam::Marginals::Marginals ( const GaussianFactorGraph graph,
const Values solution,
const Ordering ordering,
Factorization  factorization = CHOLESKY 
)

Construct a marginals class from a linear factor graph.

Parameters
graphThe factor graph defining the full joint density on all variables.
solutionThe solution point to compute Gaussian marginals.
factorizationThe linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems).
orderingThe ordering for elimination.

Definition at line 53 of file Marginals.cpp.

◆ Marginals() [6/7]

gtsam::Marginals::Marginals ( const GaussianFactorGraph graph,
const VectorValues solution,
Factorization  factorization = CHOLESKY 
)

Construct a marginals class from a linear factor graph.

Parameters
graphThe factor graph defining the full joint density on all variables.
solutionThe solution point to compute Gaussian marginals.
factorizationThe linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems).
orderingAn optional variable ordering for elimination.

Definition at line 61 of file Marginals.cpp.

◆ Marginals() [7/7]

gtsam::Marginals::Marginals ( const GaussianFactorGraph graph,
const VectorValues solution,
const Ordering ordering,
Factorization  factorization = CHOLESKY 
)

Construct a marginals class from a linear factor graph.

Parameters
graphThe factor graph defining the full joint density on all variables.
solutionThe solution point to compute Gaussian marginals.
factorizationThe linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems).
orderingAn optional variable ordering for elimination.

Definition at line 71 of file Marginals.cpp.

Member Function Documentation

◆ computeBayesTree() [1/2]

void gtsam::Marginals::computeBayesTree ( )
protected

Compute the Bayes Tree as a helper function to the constructor

Definition at line 82 of file Marginals.cpp.

◆ computeBayesTree() [2/2]

void gtsam::Marginals::computeBayesTree ( const Ordering ordering)
protected

Compute the Bayes Tree as a helper function to the constructor

Definition at line 95 of file Marginals.cpp.

◆ jointMarginalCovariance()

JointMarginal gtsam::Marginals::jointMarginalCovariance ( const KeyVector variables) const

Compute the joint marginal covariance of several variables

Definition at line 138 of file Marginals.cpp.

◆ jointMarginalInformation()

JointMarginal gtsam::Marginals::jointMarginalInformation ( const KeyVector variables) const

Compute the joint marginal information of several variables

Definition at line 145 of file Marginals.cpp.

◆ marginalCovariance()

Matrix gtsam::Marginals::marginalCovariance ( Key  variable) const

Compute the marginal covariance of a single variable

Definition at line 133 of file Marginals.cpp.

◆ marginalFactor()

GaussianFactor::shared_ptr gtsam::Marginals::marginalFactor ( Key  variable) const

Compute the marginal factor of a single variable

Definition at line 112 of file Marginals.cpp.

◆ marginalInformation()

Matrix gtsam::Marginals::marginalInformation ( Key  variable) const

Compute the marginal information matrix of a single variable. Use LLt(const Matrix&) or RtR(const Matrix&) to obtain the square-root information matrix.

Definition at line 125 of file Marginals.cpp.

◆ optimize()

VectorValues gtsam::Marginals::optimize ( ) const

Optimize the bayes tree

Definition at line 192 of file Marginals.cpp.

◆ print()

void gtsam::Marginals::print ( const std::string &  str = "Marginals: ",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const

print

Definition at line 104 of file Marginals.cpp.

Member Data Documentation

◆ bayesTree_

GaussianBayesTree gtsam::Marginals::bayesTree_
protected

Definition at line 47 of file Marginals.h.

◆ factorization_

Factorization gtsam::Marginals::factorization_
protected

Definition at line 46 of file Marginals.h.

◆ graph_

GaussianFactorGraph gtsam::Marginals::graph_
protected

Definition at line 44 of file Marginals.h.

◆ values_

Values gtsam::Marginals::values_
protected

Definition at line 45 of file Marginals.h.


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


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