#include <NoiseModel.h>
Public Types | |
typedef std::shared_ptr< Base > | shared_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 (Eigen::Block< Vector > &v) const |
virtual void | unwhitenInPlace (Vector &v) const |
virtual double | weight (const Vector &v) const |
virtual Matrix | Whiten (const Matrix &H) const =0 |
Whiten a matrix. More... | |
virtual Vector | whiten (const Vector &v) const =0 |
Whiten an error vector. More... | |
virtual void | whitenInPlace (Eigen::Block< Vector > &v) const |
virtual void | whitenInPlace (Vector &v) const |
virtual void | WhitenSystem (Matrix &A, Vector &b) const =0 |
virtual void | WhitenSystem (Matrix &A1, Matrix &A2, Matrix &A3, Vector &b) const =0 |
virtual void | WhitenSystem (Matrix &A1, Matrix &A2, Vector &b) const =0 |
virtual void | WhitenSystem (std::vector< Matrix > &A, Vector &b) const =0 |
virtual | ~Base () |
Protected Attributes | |
size_t | dim_ |
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 57 of file NoiseModel.h.
typedef std::shared_ptr<Base> gtsam::noiseModel::Base::shared_ptr |
Definition at line 60 of file NoiseModel.h.
|
inline |
primary constructor
dim | is the dimension of the model |
Definition at line 69 of file NoiseModel.h.
|
inlinevirtual |
Definition at line 70 of file NoiseModel.h.
|
inline |
Dimensionality.
Definition at line 79 of file NoiseModel.h.
|
pure virtual |
Implemented in gtsam::noiseModel::Robust, and gtsam::noiseModel::Gaussian.
|
inlinevirtual |
true if a constrained noise model, saves slow/clumsy dynamic casting
Reimplemented in gtsam::noiseModel::Constrained.
Definition at line 73 of file NoiseModel.h.
|
inlinevirtual |
true if a unit noise model, saves slow/clumsy dynamic casting
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 76 of file NoiseModel.h.
|
inlinevirtual |
loss function, input is Mahalanobis distance
Reimplemented in gtsam::noiseModel::Robust.
Definition at line 106 of file NoiseModel.h.
|
inlinevirtual |
Mahalanobis distance.
Definition at line 101 of file NoiseModel.h.
|
pure virtual |
|
virtual |
Calculate standard deviations.
Reimplemented in gtsam::noiseModel::Diagonal, and gtsam::noiseModel::Gaussian.
Definition at line 72 of file NoiseModel.cpp.
|
virtual |
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
Reimplemented in gtsam::noiseModel::Robust, gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Constrained.
Definition at line 77 of file NoiseModel.cpp.
Useful function for robust noise models to get the unweighted but whitened error
Reimplemented in gtsam::noiseModel::Robust.
Definition at line 136 of file NoiseModel.h.
Unwhiten an error vector.
Implemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, gtsam::noiseModel::Diagonal, gtsam::noiseModel::Gaussian, and gtsam::noiseModel::Robust.
|
inlinevirtual |
in-place unwhiten, override if can be done more efficiently
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 131 of file NoiseModel.h.
|
inlinevirtual |
in-place unwhiten, override if can be done more efficiently
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 121 of file NoiseModel.h.
|
inlinevirtual |
get the weight from the effective loss function on residual vector v
Reimplemented in gtsam::noiseModel::Robust.
Definition at line 141 of file NoiseModel.h.
Whiten a matrix.
Implemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, gtsam::noiseModel::Constrained, gtsam::noiseModel::Diagonal, gtsam::noiseModel::Gaussian, and gtsam::noiseModel::Robust.
Whiten an error vector.
Implemented in gtsam::noiseModel::Robust, gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, gtsam::noiseModel::Constrained, gtsam::noiseModel::Diagonal, and gtsam::noiseModel::Gaussian.
|
inlinevirtual |
in-place whiten, override if can be done more efficiently
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 126 of file NoiseModel.h.
|
inlinevirtual |
in-place whiten, override if can be done more efficiently
Reimplemented in gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Unit.
Definition at line 116 of file NoiseModel.h.
Implemented in gtsam::noiseModel::Robust, and gtsam::noiseModel::Gaussian.
|
pure virtual |
Implemented in gtsam::noiseModel::Robust, and gtsam::noiseModel::Gaussian.
|
pure virtual |
Implemented in gtsam::noiseModel::Robust, and gtsam::noiseModel::Gaussian.
|
pure virtual |
Implemented in gtsam::noiseModel::Robust, and gtsam::noiseModel::Gaussian.
|
protected |
Definition at line 64 of file NoiseModel.h.