Public Types | Public Member Functions | Protected Attributes | Private Member Functions | Friends | List of all members
gtsam::noiseModel::Base Class Referenceabstract

#include <NoiseModel.h>

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

Public Types

typedef boost::shared_ptr< Baseshared_ptr
 

Public Member Functions

 Base (size_t dim=1)
 primary constructor More...
 
size_t dim () const
 Dimensionality. More...
 
virtual bool equals (const Base &expected, double tol=1e-9) const =0
 
virtual bool isConstrained () const
 true if a constrained noise model, saves slow/clumsy dynamic casting More...
 
virtual bool isUnit () const
 true if a unit noise model, saves slow/clumsy dynamic casting More...
 
virtual double loss (const double squared_distance) const
 loss function, input is Mahalanobis distance More...
 
virtual double mahalanobisDistance (const Vector &v) const
 Mahalanobis distance. More...
 
virtual void print (const std::string &name="") const =0
 
virtual Vector sigmas () const
 Calculate standard deviations. More...
 
virtual double squaredMahalanobisDistance (const Vector &v) const
 Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v> More...
 
virtual Vector unweightedWhiten (const Vector &v) const
 
virtual Vector unwhiten (const Vector &v) const =0
 Unwhiten an error vector. More...
 
virtual void unwhitenInPlace (Vector &v) const
 
virtual void unwhitenInPlace (Eigen::Block< Vector > &v) const
 
virtual double weight (const Vector &v) const
 
virtual Vector whiten (const Vector &v) const =0
 Whiten an error vector. More...
 
virtual Matrix Whiten (const Matrix &H) const =0
 Whiten a matrix. More...
 
virtual void whitenInPlace (Vector &v) const
 
virtual void whitenInPlace (Eigen::Block< Vector > &v) const
 
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 ~Base ()
 

Protected Attributes

size_t dim_
 

Private Member Functions

template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Friends

class boost::serialization::access
 

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.

Definition at line 53 of file NoiseModel.h.

Member Typedef Documentation

typedef boost::shared_ptr<Base> gtsam::noiseModel::Base::shared_ptr

Definition at line 56 of file NoiseModel.h.

Constructor & Destructor Documentation

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

primary constructor

Parameters
dimis the dimension of the model

Definition at line 65 of file NoiseModel.h.

virtual gtsam::noiseModel::Base::~Base ( )
inlinevirtual

Definition at line 66 of file NoiseModel.h.

Member Function Documentation

size_t gtsam::noiseModel::Base::dim ( ) const
inline

Dimensionality.

Definition at line 75 of file NoiseModel.h.

virtual bool gtsam::noiseModel::Base::equals ( const Base expected,
double  tol = 1e-9 
) const
pure virtual
virtual bool gtsam::noiseModel::Base::isConstrained ( ) const
inlinevirtual

true if a constrained noise model, saves slow/clumsy dynamic casting

Reimplemented in gtsam::noiseModel::Constrained.

Definition at line 69 of file NoiseModel.h.

virtual bool gtsam::noiseModel::Base::isUnit ( ) const
inlinevirtual

true if a unit noise model, saves slow/clumsy dynamic casting

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 72 of file NoiseModel.h.

virtual double gtsam::noiseModel::Base::loss ( const double  squared_distance) const
inlinevirtual

loss function, input is Mahalanobis distance

Reimplemented in gtsam::noiseModel::Robust.

Definition at line 102 of file NoiseModel.h.

virtual double gtsam::noiseModel::Base::mahalanobisDistance ( const Vector v) const
inlinevirtual

Mahalanobis distance.

Definition at line 97 of file NoiseModel.h.

virtual void gtsam::noiseModel::Base::print ( const std::string &  name = "") const
pure virtual
template<class ARCHIVE >
void gtsam::noiseModel::Base::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 143 of file NoiseModel.h.

Vector Base::sigmas ( ) const
virtual

Calculate standard deviations.

Reimplemented in gtsam::noiseModel::Diagonal, and gtsam::noiseModel::Gaussian.

Definition at line 73 of file NoiseModel.cpp.

double Base::squaredMahalanobisDistance ( const Vector v) const
virtual

Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>

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

Definition at line 78 of file NoiseModel.cpp.

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.

Definition at line 132 of file NoiseModel.h.

virtual Vector gtsam::noiseModel::Base::unwhiten ( const Vector v) const
pure virtual
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.

Definition at line 117 of file NoiseModel.h.

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.

Definition at line 127 of file NoiseModel.h.

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.

Definition at line 137 of file NoiseModel.h.

virtual Vector gtsam::noiseModel::Base::whiten ( const Vector v) const
pure virtual
virtual Matrix gtsam::noiseModel::Base::Whiten ( const Matrix H) const
pure virtual
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.

Definition at line 112 of file NoiseModel.h.

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.

Definition at line 122 of file NoiseModel.h.

virtual void gtsam::noiseModel::Base::WhitenSystem ( std::vector< Matrix > &  A,
Vector b 
) const
pure virtual
virtual void gtsam::noiseModel::Base::WhitenSystem ( Matrix A,
Vector b 
) const
pure virtual
virtual void gtsam::noiseModel::Base::WhitenSystem ( Matrix A1,
Matrix A2,
Vector b 
) const
pure virtual
virtual void gtsam::noiseModel::Base::WhitenSystem ( Matrix A1,
Matrix A2,
Matrix A3,
Vector b 
) const
pure virtual

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 141 of file NoiseModel.h.

Member Data Documentation

size_t gtsam::noiseModel::Base::dim_
protected

Definition at line 60 of file NoiseModel.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:53