#include <Marginals.h>
Public Types | |
enum | Factorization { CHOLESKY, QR } |
Protected Member Functions | |
void | computeBayesTree () |
void | computeBayesTree (const Ordering &ordering) |
Protected Attributes | |
GaussianBayesTree | bayesTree_ |
Factorization | factorization_ |
GaussianFactorGraph | graph_ |
Values | values_ |
A class for computing Gaussian marginals of variables in a NonlinearFactorGraph
Definition at line 32 of file Marginals.h.
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.
|
inline |
Default constructor only for wrappers.
Definition at line 52 of file Marginals.h.
gtsam::Marginals::Marginals | ( | const NonlinearFactorGraph & | graph, |
const Values & | solution, | ||
Factorization | factorization = CHOLESKY |
||
) |
Construct a marginals class from a nonlinear factor graph.
graph | The factor graph defining the full joint density on all variables. |
solution | The linearization point about which to compute Gaussian marginals (usually the MLE as obtained from a NonlinearOptimizer). |
factorization | The 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.
gtsam::Marginals::Marginals | ( | const NonlinearFactorGraph & | graph, |
const Values & | solution, | ||
const Ordering & | ordering, | ||
Factorization | factorization = CHOLESKY |
||
) |
Construct a marginals class from a nonlinear factor graph.
graph | The factor graph defining the full joint density on all variables. |
solution | The linearization point about which to compute Gaussian marginals (usually the MLE as obtained from a NonlinearOptimizer). |
factorization | The linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems). |
ordering | The ordering for elimination. |
Definition at line 37 of file Marginals.cpp.
gtsam::Marginals::Marginals | ( | const GaussianFactorGraph & | graph, |
const Values & | solution, | ||
Factorization | factorization = CHOLESKY |
||
) |
Construct a marginals class from a linear factor graph.
graph | The factor graph defining the full joint density on all variables. |
solution | The solution point to compute Gaussian marginals. |
factorization | The 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.
gtsam::Marginals::Marginals | ( | const GaussianFactorGraph & | graph, |
const Values & | solution, | ||
const Ordering & | ordering, | ||
Factorization | factorization = CHOLESKY |
||
) |
Construct a marginals class from a linear factor graph.
graph | The factor graph defining the full joint density on all variables. |
solution | The solution point to compute Gaussian marginals. |
factorization | The linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems). |
ordering | The ordering for elimination. |
Definition at line 53 of file Marginals.cpp.
gtsam::Marginals::Marginals | ( | const GaussianFactorGraph & | graph, |
const VectorValues & | solution, | ||
Factorization | factorization = CHOLESKY |
||
) |
Construct a marginals class from a linear factor graph.
graph | The factor graph defining the full joint density on all variables. |
solution | The solution point to compute Gaussian marginals. |
factorization | The linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems). |
ordering | An optional variable ordering for elimination. |
Definition at line 61 of file Marginals.cpp.
gtsam::Marginals::Marginals | ( | const GaussianFactorGraph & | graph, |
const VectorValues & | solution, | ||
const Ordering & | ordering, | ||
Factorization | factorization = CHOLESKY |
||
) |
Construct a marginals class from a linear factor graph.
graph | The factor graph defining the full joint density on all variables. |
solution | The solution point to compute Gaussian marginals. |
factorization | The linear decomposition mode - either Marginals::CHOLESKY (faster and suitable for most problems) or Marginals::QR (slower but more numerically stable for poorly-conditioned problems). |
ordering | An optional variable ordering for elimination. |
Definition at line 71 of file Marginals.cpp.
|
protected |
Compute the Bayes Tree as a helper function to the constructor
Definition at line 82 of file Marginals.cpp.
|
protected |
Compute the Bayes Tree as a helper function to the constructor
Definition at line 95 of file Marginals.cpp.
JointMarginal gtsam::Marginals::jointMarginalCovariance | ( | const KeyVector & | variables | ) | const |
Compute the joint marginal covariance of several variables
Definition at line 138 of file Marginals.cpp.
JointMarginal gtsam::Marginals::jointMarginalInformation | ( | const KeyVector & | variables | ) | const |
Compute the joint marginal information of several variables
Definition at line 145 of file Marginals.cpp.
Compute the marginal covariance of a single variable
Definition at line 133 of file Marginals.cpp.
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.
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.
VectorValues gtsam::Marginals::optimize | ( | ) | const |
Optimize the bayes tree
Definition at line 192 of file Marginals.cpp.
void gtsam::Marginals::print | ( | const std::string & | str = "Marginals: " , |
const KeyFormatter & | keyFormatter = DefaultKeyFormatter |
||
) | const |
Definition at line 104 of file Marginals.cpp.
|
protected |
Definition at line 47 of file Marginals.h.
|
protected |
Definition at line 46 of file Marginals.h.
|
protected |
Definition at line 44 of file Marginals.h.
|
protected |
Definition at line 45 of file Marginals.h.