#include <NoiseModel.h>
Public Types | |
typedef std::shared_ptr< Robust > | shared_ptr |
Public Types inherited from gtsam::noiseModel::Base | |
typedef std::shared_ptr< Base > | shared_ptr |
Public Member Functions | |
bool | equals (const Base &expected, double tol=1e-9) const override |
double | loss (const double squared_distance) const override |
Compute loss from the m-estimator using the Mahalanobis distance. More... | |
const NoiseModel::shared_ptr & | noise () const |
Return the contained noise model. More... | |
void | print (const std::string &name) const override |
Robust () | |
Default Constructor for serialization. More... | |
const RobustModel::shared_ptr & | robust () const |
Return the contained robust error function. More... | |
Robust (const RobustModel::shared_ptr robust, const NoiseModel::shared_ptr noise) | |
Constructor. More... | |
double | squaredMahalanobisDistance (const Vector &v) const override |
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v> 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 |
Matrix | Whiten (const Matrix &A) const override |
Whiten a matrix. More... | |
Vector | whiten (const Vector &v) const override |
Whiten an error vector. More... | |
void | WhitenSystem (Matrix &A, Vector &b) const override |
void | WhitenSystem (Matrix &A1, Matrix &A2, Matrix &A3, Vector &b) const override |
void | WhitenSystem (Matrix &A1, Matrix &A2, Vector &b) const override |
void | WhitenSystem (std::vector< Matrix > &A, Vector &b) const override |
virtual void | WhitenSystem (Vector &b) const |
~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 void | unwhitenInPlace (Eigen::Block< Vector > &v) const |
virtual void | unwhitenInPlace (Vector &v) const |
virtual void | whitenInPlace (Eigen::Block< Vector > &v) const |
virtual void | whitenInPlace (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_ |
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".
Definition at line 678 of file NoiseModel.h.
|
protected |
Definition at line 684 of file NoiseModel.h.
|
protected |
Definition at line 683 of file NoiseModel.h.
typedef std::shared_ptr<Robust> gtsam::noiseModel::Robust::shared_ptr |
Definition at line 680 of file NoiseModel.h.
|
inline |
Default Constructor for serialization.
Definition at line 692 of file NoiseModel.h.
|
inline |
Constructor.
Definition at line 695 of file NoiseModel.h.
|
inlineoverride |
Destructor.
Definition at line 699 of file NoiseModel.h.
|
static |
Definition at line 741 of file NoiseModel.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
Definition at line 703 of file NoiseModel.cpp.
|
inlineoverridevirtual |
Compute loss from the m-estimator using the Mahalanobis distance.
Reimplemented from gtsam::noiseModel::Base.
Definition at line 718 of file NoiseModel.h.
|
inline |
Return the contained noise model.
Definition at line 708 of file NoiseModel.h.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
Definition at line 698 of file NoiseModel.cpp.
|
inline |
Return the contained robust error function.
Definition at line 705 of file NoiseModel.h.
|
inlineoverridevirtual |
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
Reimplemented from gtsam::noiseModel::Base.
Definition at line 724 of file NoiseModel.h.
Useful function for robust noise models to get the unweighted but whitened error
Reimplemented from gtsam::noiseModel::Base.
Definition at line 734 of file NoiseModel.cpp.
Unwhiten an error vector.
Implements gtsam::noiseModel::Base.
Definition at line 715 of file NoiseModel.h.
|
overridevirtual |
get the weight from the effective loss function on residual vector v
Reimplemented from gtsam::noiseModel::Base.
Definition at line 737 of file NoiseModel.cpp.
Whiten an error vector.
Implements gtsam::noiseModel::Base.
Definition at line 711 of file NoiseModel.h.
Implements gtsam::noiseModel::Base.
Definition at line 719 of file NoiseModel.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
Definition at line 729 of file NoiseModel.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
Definition at line 724 of file NoiseModel.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
Definition at line 714 of file NoiseModel.cpp.
|
virtual |
Definition at line 709 of file NoiseModel.cpp.
|
protected |
noise model used
Definition at line 687 of file NoiseModel.h.
|
protected |
robust error function used
Definition at line 686 of file NoiseModel.h.