gtsam 4.1.1
gtsam
gtsam::noiseModel::Robust Class Reference

Detailed Description

Base class for robust error models The robust M-estimators above simply tell us how to re-weight the residual, and are isotropic kernels, in that they do not allow for correlated noise.

They also have no way to scale the residual values, e.g., dividing by a single standard deviation. Hence, the actual robust noise model below does this scaling/whitening in sequence, by passing both a standard noise model and a robust estimator.

Taking as an example noise = Isotropic::Create(d, sigma), we first divide the residuals uw = |Ax-b| by sigma by "whitening" the system (A,b), obtaining r = |Ax-b|/sigma, and then we pass the now whitened residual 'r' through the robust M-estimator. This is currently done by multiplying with sqrt(w), because the residuals will be squared again in error, yielding 0.5 \sum w(r)*r^2.

In other words, while sigma is expressed in the native residual units, a parameter like k in the Huber norm is expressed in whitened units, i.e., "nr of sigmas".

+ Inheritance diagram for gtsam::noiseModel::Robust:

Public Member Functions

 Robust ()
 Default Constructor for serialization.
 
 Robust (const RobustModel::shared_ptr robust, const NoiseModel::shared_ptr noise)
 Constructor.
 
 ~Robust () override
 Destructor.
 
void print (const std::string &name) const override
 
bool equals (const Base &expected, double tol=1e-9) const override
 
const RobustModel::shared_ptr & robust () const
 Return the contained robust error function.
 
const NoiseModel::shared_ptr & noise () const
 Return the contained noise model.
 
Vector whiten (const Vector &v) const override
 Whiten an error vector. More...
 
Matrix Whiten (const Matrix &A) const override
 Whiten a matrix. More...
 
Vector unwhiten (const Vector &) const override
 Unwhiten an error vector. More...
 
double loss (const double squared_distance) const override
 Compute loss from the m-estimator using the Mahalanobis distance. More...
 
virtual void WhitenSystem (Vector &b) 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
 
Vector unweightedWhiten (const Vector &v) const override
 Useful function for robust noise models to get the unweighted but whitened error. More...
 
double weight (const Vector &v) const override
 get the weight from the effective loss function on residual vector v More...
 
- Public Member Functions inherited from gtsam::noiseModel::Base
 Base (size_t dim=1)
 primary constructor More...
 
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...
 
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. More...
 
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 Vector unwhiten (const Vector &v) const =0
 Unwhiten an error vector. More...
 
virtual double squaredMahalanobisDistance (const Vector &v) const
 Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v> More...
 
virtual double mahalanobisDistance (const Vector &v) const
 Mahalanobis distance.
 
virtual double loss (const double squared_distance) const
 loss function, input is Mahalanobis distance More...
 
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
 in-place whiten, override if can be done more efficiently More...
 
virtual void unwhitenInPlace (Vector &v) const
 in-place unwhiten, override if can be done more efficiently More...
 
virtual void whitenInPlace (Eigen::Block< Vector > &v) const
 in-place whiten, override if can be done more efficiently More...
 
virtual void unwhitenInPlace (Eigen::Block< Vector > &v) const
 in-place unwhiten, override if can be done more efficiently More...
 
virtual Vector unweightedWhiten (const Vector &v) const
 Useful function for robust noise models to get the unweighted but whitened error. More...
 
virtual double weight (const Vector &v) const
 get the weight from the effective loss function on residual vector v More...
 

Static Public Member Functions

static shared_ptr Create (const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise)
 

Public Types

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

Protected Types

typedef mEstimator::Base RobustModel
 
typedef noiseModel::Base NoiseModel
 

Protected Attributes

const RobustModel::shared_ptr robust_
 robust error function used
 
const NoiseModel::shared_ptr noise_
 noise model used
 
- Protected Attributes inherited from gtsam::noiseModel::Base
size_t dim_
 

Friends

class boost::serialization::access
 Serialization function.
 

Member Function Documentation

◆ equals()

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

◆ loss()

double gtsam::noiseModel::Robust::loss ( const double  squared_distance) const
inlineoverridevirtual

Compute loss from the m-estimator using the Mahalanobis distance.

Reimplemented from gtsam::noiseModel::Base.

◆ print()

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

◆ unweightedWhiten()

Vector gtsam::noiseModel::Robust::unweightedWhiten ( const Vector &  v) const
inlineoverridevirtual

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

Reimplemented from gtsam::noiseModel::Base.

◆ unwhiten()

Vector gtsam::noiseModel::Robust::unwhiten ( const Vector &  v) const
inlineoverridevirtual

Unwhiten an error vector.

Implements gtsam::noiseModel::Base.

◆ weight()

double gtsam::noiseModel::Robust::weight ( const Vector &  v) const
inlineoverridevirtual

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

Reimplemented from gtsam::noiseModel::Base.

◆ Whiten()

Matrix gtsam::noiseModel::Robust::Whiten ( const Matrix &  H) const
inlineoverridevirtual

Whiten a matrix.

Implements gtsam::noiseModel::Base.

◆ whiten()

Vector gtsam::noiseModel::Robust::whiten ( const Vector &  v) const
inlineoverridevirtual

Whiten an error vector.

Implements gtsam::noiseModel::Base.

◆ WhitenSystem() [1/4]

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

◆ WhitenSystem() [2/4]

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

◆ WhitenSystem() [3/4]

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

◆ WhitenSystem() [4/4]

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

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