gtsam 4.2
gtsam
Loading...
Searching...
No Matches
gtsam::noiseModel::Gaussian Class Reference

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.

Inheritance diagram for gtsam::noiseModel::Gaussian:

Public Member Functions

 Gaussian (size_t dim=1, const boost::optional< Matrix > &sqrt_information=boost::none)
 constructor takes square root information matrix
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
 Multiply a derivative with R (derivative of whiten) Equivalent to whitening each column of the input matrix.
virtual void WhitenInPlace (Matrix &H) const
 In-place version.
virtual void WhitenInPlace (Eigen::Block< Matrix > H) const
 In-place version.
void WhitenSystem (std::vector< Matrix > &A, Vector &b) const override
 Whiten a system, in place as well.
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 boost::shared_ptr< DiagonalQR (Matrix &Ab) const
 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).
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.
Public Member Functions inherited from gtsam::noiseModel::Base
 Base (size_t dim=1)
 primary constructor
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
 in-place whiten, override if can be done more efficiently
virtual void unwhitenInPlace (Vector &v) const
 in-place unwhiten, override if can be done more efficiently
virtual void whitenInPlace (Eigen::Block< Vector > &v) const
 in-place whiten, override if can be done more efficiently
virtual void unwhitenInPlace (Eigen::Block< Vector > &v) const
 in-place unwhiten, override if can be done more efficiently
virtual Vector unweightedWhiten (const Vector &v) const
 Useful function for robust noise models to get the unweighted but whitened error.
virtual double weight (const Vector &v) const
 get the weight from the effective loss function on residual vector v

Static Public Member Functions

static shared_ptr SqrtInformation (const Matrix &R, bool smart=true)
 A Gaussian noise model created by specifying a square root information matrix.
static shared_ptr Information (const Matrix &M, bool smart=true)
 A Gaussian noise model created by specifying an information matrix.
static shared_ptr Covariance (const Matrix &covariance, bool smart=true)
 A Gaussian noise model created by specifying a covariance matrix.

Public Types

typedef boost::shared_ptr< Gaussianshared_ptr
Public Types inherited from gtsam::noiseModel::Base
typedef boost::shared_ptr< Baseshared_ptr

Protected Attributes

boost::optional< Matrix > sqrt_information_
 Matrix square root of information matrix (R).
Protected Attributes inherited from gtsam::noiseModel::Base
size_t dim_

Friends

class boost::serialization::access
 Serialization function.

Member Function Documentation

◆ Covariance()

Gaussian::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

◆ equals()

bool gtsam::noiseModel::Gaussian::equals ( const Base & expected,
double tol = 1e-9 ) const
overridevirtual

◆ Information()

Gaussian::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

◆ print()

void gtsam::noiseModel::Gaussian::print ( const std::string & name) const
overridevirtual

◆ QR()

SharedDiagonal 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.

◆ R()

virtual Matrix gtsam::noiseModel::Gaussian::R ( ) const
inlinevirtual

Return R itself, but note that Whiten(H) is cheaper than R*H.

Reimplemented in gtsam::noiseModel::Diagonal.

◆ sigmas()

Vector gtsam::noiseModel::Gaussian::sigmas ( ) const
overridevirtual

Calculate standard deviations.

Reimplemented from gtsam::noiseModel::Base.

◆ SqrtInformation()

Gaussian::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

◆ unwhiten()

Vector gtsam::noiseModel::Gaussian::unwhiten ( const Vector & v) const
overridevirtual

Unwhiten an error vector.

Implements gtsam::noiseModel::Base.

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

◆ 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::Isotropic, and gtsam::noiseModel::Unit.

◆ whiten()

Vector gtsam::noiseModel::Gaussian::whiten ( const Vector & v) const
overridevirtual

Whiten an error vector.

Implements gtsam::noiseModel::Base.

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

◆ WhitenInPlace() [1/2]

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

◆ WhitenInPlace() [2/2]

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

◆ WhitenSystem() [1/4]

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

◆ WhitenSystem() [2/4]

void gtsam::noiseModel::Gaussian::WhitenSystem ( Matrix & A1,
Matrix & A2,
Matrix & A3,
Vector & b ) const
overridevirtual

◆ WhitenSystem() [3/4]

void gtsam::noiseModel::Gaussian::WhitenSystem ( Matrix & A1,
Matrix & A2,
Vector & b ) const
overridevirtual

◆ WhitenSystem() [4/4]

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

Whiten a system, in place as well.

Implements gtsam::noiseModel::Base.


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