|
GTSAM
4.0.2
C++ library for smoothing and mapping (SAM)
|
#include <NoiseModel.h>


Public Types | |
| typedef std::shared_ptr< Constrained > | shared_ptr |
Public Member Functions | |
| Constrained (const Vector &sigmas=Z_1x1) | |
| bool | isConstrained () const override |
| true if a constrained noise mode, saves slow/clumsy dynamic casting | |
| bool | constrained (size_t i) const |
| Return true if a particular dimension is free or constrained. | |
| const Vector & | mu () const |
| Access mu as a vector. | |
| double | squaredMahalanobisDistance (const Vector &v) const override |
| void | print (const std::string &name) const override |
| Vector | whiten (const Vector &v) const override |
| Calculates error vector with weights applied. | |
| Matrix | Whiten (const Matrix &H) const override |
| void | WhitenInPlace (Matrix &H) const override |
| void | WhitenInPlace (Eigen::Block< Matrix > H) const override |
| Diagonal::shared_ptr | QR (Matrix &Ab) const override |
| shared_ptr | unit () const |
| Vector | sigmas () const override |
| Calculate standard deviations. | |
| Vector | unwhiten (const Vector &v) const override |
| Unwhiten an error vector. | |
| double | sigma (size_t i) const |
| const Vector & | invsigmas () const |
| double | invsigma (size_t i) const |
| const Vector & | precisions () const |
| double | precision (size_t i) const |
| Matrix | R () const override |
| bool | equals (const Base &expected, double tol=1e-9) const override |
| 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 |
| virtual Matrix | information () const |
| Compute information matrix. | |
| virtual Matrix | covariance () const |
| Compute covariance matrix. | |
| virtual bool | isUnit () const |
| true if a unit noise model, saves slow/clumsy dynamic casting | |
| size_t | dim () const |
| Dimensionality. | |
| virtual double | mahalanobisDistance (const Vector &v) const |
| Mahalanobis distance. | |
| virtual double | loss (const double squared_distance) const |
| loss function, input is Mahalanobis distance | |
| virtual void | whitenInPlace (Vector &v) const |
| virtual void | whitenInPlace (Eigen::Block< Vector > &v) const |
| virtual void | unwhitenInPlace (Vector &v) const |
| virtual void | unwhitenInPlace (Eigen::Block< Vector > &v) const |
| virtual Vector | unweightedWhiten (const Vector &v) const |
| virtual double | weight (const Vector &v) const |
Static Public Member Functions | |
| static shared_ptr | MixedSigmas (const Vector &mu, const Vector &sigmas) |
| static shared_ptr | MixedSigmas (const Vector &sigmas) |
| static shared_ptr | MixedSigmas (double m, const Vector &sigmas) |
| static shared_ptr | MixedVariances (const Vector &mu, const Vector &variances) |
| static shared_ptr | MixedVariances (const Vector &variances) |
| static shared_ptr | MixedPrecisions (const Vector &mu, const Vector &precisions) |
| static shared_ptr | MixedPrecisions (const Vector &precisions) |
| static shared_ptr | All (size_t dim) |
| static shared_ptr | All (size_t dim, const Vector &mu) |
| static shared_ptr | All (size_t dim, double mu) |
| static shared_ptr | Sigmas (const Vector &sigmas, bool smart=true) |
| static shared_ptr | Variances (const Vector &variances, bool smart=true) |
| static shared_ptr | Precisions (const Vector &precisions, bool smart=true) |
| static shared_ptr | SqrtInformation (const Matrix &R, bool smart=true) |
| static shared_ptr | Information (const Matrix &M, bool smart=true) |
| static shared_ptr | Covariance (const Matrix &covariance, bool smart=true) |
Protected Member Functions | |
| Constrained (const Vector &mu, const Vector &sigmas) | |
Protected Attributes | |
| Vector | mu_ |
| Penalty function weight - needs to be large enough to dominate soft constraints. | |
| Vector | sigmas_ |
| Vector | invsigmas_ |
| Vector | precisions_ |
| std::optional< Matrix > | sqrt_information_ |
| size_t | dim_ |
A Constrained constrained model is a specialization of Diagonal which allows some or all of the sigmas to be zero, forcing the error to be zero there. All other Gaussian models are guaranteed to have a non-singular square-root information matrix, but this class is specifically equipped to deal with singular noise models, specifically: whiten will return zero on those components that have zero sigma and zero error, unchanged otherwise.
While a hard constraint may seem to be a case in which there is infinite error, we do not ever produce an error value of infinity to allow for constraints to actually be optimized rather than self-destructing if not initialized correctly.
|
protected |
Constructor that prevents any inf values from appearing in invsigmas or precisions. Allows for specifying mu.
| gtsam::noiseModel::Constrained::Constrained | ( | const Vector & | sigmas = Z_1x1 | ) |
protected constructor takes sigmas. prevents any inf values from appearing in invsigmas or precisions. mu set to large default value (1000.0)
|
inlinestatic |
Fully constrained variations
|
inlinestatic |
Fully constrained variations
|
inlinestatic |
Fully constrained variations with a mu parameter
|
staticinherited |
A Gaussian noise model created by specifying a covariance matrix.
| covariance | The square covariance Matrix |
| smart | check if can be simplified to derived class |
|
staticinherited |
A Gaussian noise model created by specifying an information matrix.
| M | The information matrix |
| smart | check if can be simplified to derived class |
|
inlineinherited |
Return sqrt precisions
|
static |
A diagonal noise model created by specifying a Vector of precisions, some of which might be inf
|
static |
A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero
|
static |
A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero
|
static |
A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero
|
static |
A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero
|
staticinherited |
A diagonal noise model created by specifying a Vector of precisions, i.e. i.e. the diagonal of the information matrix, i.e., weights
|
inlineinherited |
Return precisions
|
overridevirtual |
Apply QR factorization to the system [A b], taking into account constraints Q' * [A b] = [R d] Dimensions: (r*m) * m*(n+1) = r*(n+1), where r = min(m,n). This routine performs an in-place factorization on Ab. Below-diagonal elements are set to zero by this routine.
| Ab | is the m*(n+1) augmented system matrix [A b] |
Reimplemented from gtsam::noiseModel::Gaussian.
|
inlineoverridevirtualinherited |
Return R itself, but note that Whiten(H) is cheaper than R*H
Reimplemented from gtsam::noiseModel::Gaussian.
|
inlineinherited |
Return standard deviations (sqrt of diagonal)
|
staticinherited |
A diagonal noise model created by specifying a Vector of sigmas, i.e. standard deviations, the diagonal of the square root covariance matrix.
|
staticinherited |
A Gaussian noise model created by specifying a square root information matrix.
| R | The (upper-triangular) square root information matrix |
| smart | check if can be simplified to derived class |
|
overridevirtual |
The squaredMahalanobisDistance function for a constrained noisemodel, for non-constrained versions, uses sigmas, otherwise uses the penalty function with mu
Reimplemented from gtsam::noiseModel::Base.
| shared_ptr gtsam::noiseModel::Constrained::unit | ( | ) | const |
Returns a Unit version of a constrained noisemodel in which constrained sigmas remain constrained and the rest are unit scaled
|
inlinevirtualinherited |
Useful function for robust noise models to get the unweighted but whitened error
Reimplemented in gtsam::noiseModel::Robust.
|
inlinevirtualinherited |
in-place unwhiten, override if can be done more efficiently
Reimplemented in gtsam::noiseModel::Unit.
|
inlinevirtualinherited |
in-place unwhiten, override if can be done more efficiently
Reimplemented in gtsam::noiseModel::Unit.
|
staticinherited |
A diagonal noise model created by specifying a Vector of variances, i.e. i.e. the diagonal of the covariance matrix.
| variances | A vector containing the variances of this noise model |
| smart | check if can be simplified to derived class |
|
inlinevirtualinherited |
get the weight from the effective loss function on residual vector v
Reimplemented in gtsam::noiseModel::Robust.
|
overridevirtual |
Whitening functions will perform partial whitening on rows with a non-zero sigma. Other rows remain untouched.
Reimplemented from gtsam::noiseModel::Diagonal.
|
inlinevirtualinherited |
in-place whiten, override if can be done more efficiently
Reimplemented in gtsam::noiseModel::Unit, and gtsam::noiseModel::Isotropic.
|
inlinevirtualinherited |
in-place whiten, override if can be done more efficiently
Reimplemented in gtsam::noiseModel::Unit.
|
overridevirtual |
In-place version
Reimplemented from gtsam::noiseModel::Diagonal.
|
overridevirtual |
In-place version
Reimplemented from gtsam::noiseModel::Diagonal.
|
overridevirtualinherited |
Whiten a system, in place as well
Implements gtsam::noiseModel::Base.
|
protectedinherited |
Standard deviations (sigmas), their inverse and inverse square (weights/precisions) These are all computed at construction: the idea is to use one shared model where computation is done only once, the common use case in many problems.
|
protectedinherited |
Matrix square root of information matrix (R)
1.8.13