gtsam
4.0.0
gtsam
|
A class for computing Gaussian marginals of variables in a NonlinearFactorGraph.
Public Member Functions | |
Marginals () | |
Default constructor only for Cython wrapper. | |
Marginals (const NonlinearFactorGraph &graph, const Values &solution, Factorization factorization=CHOLESKY, EliminateableFactorGraph< GaussianFactorGraph >::OptionalOrdering ordering=boost::none) | |
Construct a marginals class. More... | |
void | print (const std::string &str="Marginals: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const |
print | |
GaussianFactor::shared_ptr | marginalFactor (Key variable) const |
Compute the marginal factor of a single variable. | |
Matrix | marginalInformation (Key variable) const |
Compute the marginal information matrix of a single variable. More... | |
Matrix | marginalCovariance (Key variable) const |
Compute the marginal covariance of a single variable. | |
JointMarginal | jointMarginalCovariance (const KeyVector &variables) const |
Compute the joint marginal covariance of several variables. | |
JointMarginal | jointMarginalInformation (const KeyVector &variables) const |
Compute the joint marginal information of several variables. | |
VectorValues | optimize () const |
Optimize the bayes tree. | |
Public Types | |
enum | Factorization { CHOLESKY, QR } |
The linear factorization mode - either CHOLESKY (faster and suitable for most problems) or QR (slower but more numerically stable for poorly-conditioned problems). More... | |
Protected Attributes | |
GaussianFactorGraph | graph_ |
Values | values_ |
Factorization | factorization_ |
GaussianBayesTree | bayesTree_ |
The linear factorization mode - either CHOLESKY (faster and suitable for most problems) or QR (slower but more numerically stable for poorly-conditioned problems).
gtsam::Marginals::Marginals | ( | const NonlinearFactorGraph & | graph, |
const Values & | solution, | ||
Factorization | factorization = CHOLESKY , |
||
EliminateableFactorGraph< GaussianFactorGraph >::OptionalOrdering | ordering = boost::none |
||
) |
Construct a marginals class.
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 | An optional variable ordering for elimination. |
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.