GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
gtsam::noiseModel::Gaussian Class Reference

#include <NoiseModel.h>

Inheritance diagram for gtsam::noiseModel::Gaussian:
Inheritance graph
[legend]
Collaboration diagram for gtsam::noiseModel::Gaussian:
Collaboration graph
[legend]

Public Types

typedef std::shared_ptr< Gaussianshared_ptr
 

Public Member Functions

 Gaussian (size_t dim=1, const std::optional< Matrix > &sqrt_information={})
 
void print (const std::string &name) const override
 
bool equals (const Base &expected, double tol=1e-9) const override
 
Vector sigmas () const override
 Calculate standard deviations.
 
Vector whiten (const Vector &v) const override
 Whiten an error vector.
 
Vector unwhiten (const Vector &v) const override
 Unwhiten an error vector.
 
Matrix Whiten (const Matrix &H) const override
 
virtual void WhitenInPlace (Matrix &H) const
 
virtual void WhitenInPlace (Eigen::Block< Matrix > H) const
 
void WhitenSystem (std::vector< Matrix > &A, Vector &b) const override
 
void WhitenSystem (Matrix &A, Vector &b) const override
 
void WhitenSystem (Matrix &A1, Matrix &A2, Vector &b) const override
 
void WhitenSystem (Matrix &A1, Matrix &A2, Matrix &A3, Vector &b) const override
 
virtual std::shared_ptr< DiagonalQR (Matrix &Ab) const
 
virtual Matrix R () const
 Return R itself, but note that Whiten(H) is cheaper than R*H.
 
virtual Matrix information () const
 Compute information matrix.
 
virtual Matrix covariance () const
 Compute covariance matrix.
 
virtual bool isConstrained () const
 true if a constrained noise model, saves slow/clumsy dynamic casting
 
virtual bool isUnit () const
 true if a unit noise model, saves slow/clumsy dynamic casting
 
size_t dim () const
 Dimensionality.
 
virtual double squaredMahalanobisDistance (const Vector &v) const
 Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
 
virtual double mahalanobisDistance (const Vector &v) const
 Mahalanobis distance.
 
virtual double loss (const double squared_distance) const
 loss function, input is Mahalanobis distance
 
virtual void whitenInPlace (Vector &v) const
 
virtual void whitenInPlace (Eigen::Block< Vector > &v) const
 
virtual void unwhitenInPlace (Vector &v) const
 
virtual void unwhitenInPlace (Eigen::Block< Vector > &v) const
 
virtual Vector unweightedWhiten (const Vector &v) const
 
virtual double weight (const Vector &v) const
 

Static Public Member Functions

static shared_ptr SqrtInformation (const Matrix &R, bool smart=true)
 
static shared_ptr Information (const Matrix &M, bool smart=true)
 
static shared_ptr Covariance (const Matrix &covariance, bool smart=true)
 

Protected Attributes

std::optional< Matrix > sqrt_information_
 
size_t dim_
 

Detailed Description

Gaussian implements the mathematical model |R*x|^2 = |y|^2 with R'*R=inv(Sigma) where y = whiten(x) = R*x x = unwhiten(x) = inv(R)*y as indeed |y|^2 = y'*y = x'*R'*R*x Various derived classes are available that are more efficient. The named constructors return a shared_ptr because, when the smart flag is true, the underlying object might be a derived class such as Diagonal.

Constructor & Destructor Documentation

◆ Gaussian()

gtsam::noiseModel::Gaussian::Gaussian ( size_t  dim = 1,
const std::optional< Matrix > &  sqrt_information = {} 
)
inline

constructor takes square root information matrix

Member Function Documentation

◆ Covariance()

static shared_ptr gtsam::noiseModel::Gaussian::Covariance ( const Matrix &  covariance,
bool  smart = true 
)
static

A Gaussian noise model created by specifying a covariance matrix.

Parameters
covarianceThe square covariance Matrix
smartcheck if can be simplified to derived class

◆ Information()

static shared_ptr gtsam::noiseModel::Gaussian::Information ( const Matrix &  M,
bool  smart = true 
)
static

A Gaussian noise model created by specifying an information matrix.

Parameters
MThe information matrix
smartcheck if can be simplified to derived class

◆ QR()

virtual std::shared_ptr<Diagonal> gtsam::noiseModel::Gaussian::QR ( Matrix &  Ab) const
virtual

Apply appropriately weighted QR factorization to the system [A b] Q' * [A b] = [R d] Dimensions: (r*m) * m*(n+1) = r*(n+1), where r = min(m,n). This routine performs an in-place factorization on Ab. Below-diagonal elements are set to zero by this routine.

Parameters
Abis the m*(n+1) augmented system matrix [A b]
Returns
Empty SharedDiagonal() noise model: R,d are whitened

Reimplemented in gtsam::noiseModel::Constrained.

◆ SqrtInformation()

static shared_ptr gtsam::noiseModel::Gaussian::SqrtInformation ( const Matrix &  R,
bool  smart = true 
)
static

A Gaussian noise model created by specifying a square root information matrix.

Parameters
RThe (upper-triangular) square root information matrix
smartcheck if can be simplified to derived class

◆ unweightedWhiten()

virtual Vector gtsam::noiseModel::Base::unweightedWhiten ( const Vector &  v) const
inlinevirtualinherited

Useful function for robust noise models to get the unweighted but whitened error

Reimplemented in gtsam::noiseModel::Robust.

◆ unwhitenInPlace() [1/2]

virtual void gtsam::noiseModel::Base::unwhitenInPlace ( Vector &  v) const
inlinevirtualinherited

in-place unwhiten, override if can be done more efficiently

Reimplemented in gtsam::noiseModel::Unit.

◆ unwhitenInPlace() [2/2]

virtual void gtsam::noiseModel::Base::unwhitenInPlace ( Eigen::Block< Vector > &  v) const
inlinevirtualinherited

in-place unwhiten, override if can be done more efficiently

Reimplemented in gtsam::noiseModel::Unit.

◆ weight()

virtual double gtsam::noiseModel::Base::weight ( const Vector &  v) const
inlinevirtualinherited

get the weight from the effective loss function on residual vector v

Reimplemented in gtsam::noiseModel::Robust.

◆ Whiten()

Matrix gtsam::noiseModel::Gaussian::Whiten ( const Matrix &  H) const
overridevirtual

Multiply a derivative with R (derivative of whiten) Equivalent to whitening each column of the input matrix.

Implements gtsam::noiseModel::Base.

Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, gtsam::noiseModel::Constrained, and gtsam::noiseModel::Diagonal.

◆ whitenInPlace() [1/2]

virtual void gtsam::noiseModel::Base::whitenInPlace ( Vector &  v) const
inlinevirtualinherited

in-place whiten, override if can be done more efficiently

Reimplemented in gtsam::noiseModel::Unit, and gtsam::noiseModel::Isotropic.

◆ whitenInPlace() [2/2]

virtual void gtsam::noiseModel::Base::whitenInPlace ( Eigen::Block< Vector > &  v) const
inlinevirtualinherited

in-place whiten, override if can be done more efficiently

Reimplemented in gtsam::noiseModel::Unit.

◆ WhitenInPlace() [1/2]

virtual void gtsam::noiseModel::Gaussian::WhitenInPlace ( Matrix &  H) const
virtual

◆ WhitenInPlace() [2/2]

virtual void gtsam::noiseModel::Gaussian::WhitenInPlace ( Eigen::Block< Matrix >  H) const
virtual

◆ WhitenSystem()

void gtsam::noiseModel::Gaussian::WhitenSystem ( std::vector< Matrix > &  A,
Vector &  b 
) const
overridevirtual

Whiten a system, in place as well

Implements gtsam::noiseModel::Base.

Member Data Documentation

◆ sqrt_information_

std::optional<Matrix> gtsam::noiseModel::Gaussian::sqrt_information_
protected

Matrix square root of information matrix (R)


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