Public Types | Public Member Functions | Static Public Member Functions | Protected Types | Protected Attributes | Private Member Functions | Friends | List of all members
gtsam::noiseModel::Robust Class Reference

#include <NoiseModel.h>

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

Public Types

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

Public Member Functions

bool equals (const Base &expected, double tol=1e-9) const override
 
double loss (const double squared_distance) const override
 loss function, input is Mahalanobis distance More...
 
const NoiseModel::shared_ptrnoise () const
 Return the contained noise model. More...
 
void print (const std::string &name) const override
 
 Robust ()
 Default Constructor for serialization. More...
 
 Robust (const RobustModel::shared_ptr robust, const NoiseModel::shared_ptr noise)
 Constructor. More...
 
const RobustModel::shared_ptrrobust () const
 Return the contained robust error function. More...
 
Vector unweightedWhiten (const Vector &v) const override
 
Vector unwhiten (const Vector &) const override
 Unwhiten an error vector. More...
 
double weight (const Vector &v) const override
 
Vector whiten (const Vector &v) const override
 Whiten an error vector. More...
 
Matrix Whiten (const Matrix &A) const override
 Whiten a matrix. 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
 
 ~Robust () override
 Destructor. More...
 
- Public Member Functions inherited from gtsam::noiseModel::Base
 Base (size_t dim=1)
 primary constructor More...
 
size_t dim () const
 Dimensionality. 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...
 
virtual double mahalanobisDistance (const Vector &v) const
 Mahalanobis distance. More...
 
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 void unwhitenInPlace (Vector &v) const
 
virtual void unwhitenInPlace (Eigen::Block< Vector > &v) const
 
virtual void whitenInPlace (Vector &v) const
 
virtual void whitenInPlace (Eigen::Block< Vector > &v) const
 
virtual ~Base ()
 

Static Public Member Functions

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

Protected Types

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

Protected Attributes

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

Private Member Functions

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

Friends

class boost::serialization::access
 

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

Definition at line 653 of file NoiseModel.h.

Member Typedef Documentation

Definition at line 659 of file NoiseModel.h.

Definition at line 658 of file NoiseModel.h.

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

Definition at line 655 of file NoiseModel.h.

Constructor & Destructor Documentation

gtsam::noiseModel::Robust::Robust ( )
inline

Default Constructor for serialization.

Definition at line 667 of file NoiseModel.h.

gtsam::noiseModel::Robust::Robust ( const RobustModel::shared_ptr  robust,
const NoiseModel::shared_ptr  noise 
)
inline

Constructor.

Definition at line 670 of file NoiseModel.h.

gtsam::noiseModel::Robust::~Robust ( )
inlineoverride

Destructor.

Definition at line 674 of file NoiseModel.h.

Member Function Documentation

Robust::shared_ptr gtsam::noiseModel::Robust::Create ( const RobustModel::shared_ptr robust,
const NoiseModel::shared_ptr  noise 
)
static

Definition at line 665 of file NoiseModel.cpp.

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

Implements gtsam::noiseModel::Base.

Definition at line 634 of file NoiseModel.cpp.

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

loss function, input is Mahalanobis distance

Reimplemented from gtsam::noiseModel::Base.

Definition at line 693 of file NoiseModel.h.

const NoiseModel::shared_ptr& gtsam::noiseModel::Robust::noise ( ) const
inline

Return the contained noise model.

Definition at line 683 of file NoiseModel.h.

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

Implements gtsam::noiseModel::Base.

Definition at line 629 of file NoiseModel.cpp.

const RobustModel::shared_ptr& gtsam::noiseModel::Robust::robust ( ) const
inline

Return the contained robust error function.

Definition at line 680 of file NoiseModel.h.

template<class ARCHIVE >
void gtsam::noiseModel::Robust::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 719 of file NoiseModel.h.

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.

Definition at line 704 of file NoiseModel.h.

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

Unwhiten an error vector.

Implements gtsam::noiseModel::Base.

Definition at line 690 of file NoiseModel.h.

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.

Definition at line 707 of file NoiseModel.h.

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

Whiten an error vector.

Implements gtsam::noiseModel::Base.

Definition at line 686 of file NoiseModel.h.

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

Whiten a matrix.

Implements gtsam::noiseModel::Base.

Definition at line 688 of file NoiseModel.h.

void gtsam::noiseModel::Robust::WhitenSystem ( Vector b) const
virtual

Definition at line 640 of file NoiseModel.cpp.

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

Implements gtsam::noiseModel::Base.

Definition at line 645 of file NoiseModel.cpp.

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

Implements gtsam::noiseModel::Base.

Definition at line 650 of file NoiseModel.cpp.

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

Implements gtsam::noiseModel::Base.

Definition at line 655 of file NoiseModel.cpp.

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

Implements gtsam::noiseModel::Base.

Definition at line 660 of file NoiseModel.cpp.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 717 of file NoiseModel.h.

Member Data Documentation

const NoiseModel::shared_ptr gtsam::noiseModel::Robust::noise_
protected

noise model used

Definition at line 662 of file NoiseModel.h.

const RobustModel::shared_ptr gtsam::noiseModel::Robust::robust_
protected

robust error function used

Definition at line 661 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