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

#include <NoiseModel.h>

Inheritance diagram for gtsam::noiseModel::Base:
Inheritance graph
[legend]

Public Types

typedef std::shared_ptr< Baseshared_ptr
 

Public Member Functions

 Base (size_t dim=1)
 primary constructor More...
 
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 void print (const std::string &name="") const =0
 
virtual bool equals (const Base &expected, double tol=1e-9) const =0
 
virtual Vector sigmas () const
 Calculate standard deviations.
 
virtual Vector whiten (const Vector &v) const =0
 Whiten an error vector.
 
virtual Matrix Whiten (const Matrix &H) const =0
 Whiten a matrix.
 
virtual Vector unwhiten (const Vector &v) const =0
 Unwhiten an error vector.
 
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 WhitenSystem (std::vector< Matrix > &A, Vector &b) const =0
 
virtual void WhitenSystem (Matrix &A, Vector &b) const =0
 
virtual void WhitenSystem (Matrix &A1, Matrix &A2, Vector &b) const =0
 
virtual void WhitenSystem (Matrix &A1, Matrix &A2, Matrix &A3, Vector &b) const =0
 
virtual void whitenInPlace (Vector &v) const
 
virtual void unwhitenInPlace (Vector &v) const
 
virtual void whitenInPlace (Eigen::Block< 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
 

Protected Attributes

size_t dim_
 

Detailed Description

noiseModel::Base is the abstract base class for all noise models.

Noise models must implement a 'whiten' function to normalize an error vector, and an 'unwhiten' function to unnormalize an error vector.

Constructor & Destructor Documentation

◆ Base()

gtsam::noiseModel::Base::Base ( size_t  dim = 1)
inline

primary constructor

Parameters
dimis the dimension of the model

Member Function Documentation

◆ unweightedWhiten()

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

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
inlinevirtual

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
inlinevirtual

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
inlinevirtual

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

Reimplemented in gtsam::noiseModel::Robust.

◆ whitenInPlace() [1/2]

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

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
inlinevirtual

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

Reimplemented in gtsam::noiseModel::Unit.


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