#include <NoiseModel.h>

Public Types | |
| typedef std::shared_ptr< Constrained > | shared_ptr |
Public Types inherited from gtsam::noiseModel::Diagonal | |
| typedef std::shared_ptr< Diagonal > | shared_ptr |
Public Types inherited from gtsam::noiseModel::Gaussian | |
| typedef std::shared_ptr< Gaussian > | shared_ptr |
Public Types inherited from gtsam::noiseModel::Base | |
| typedef std::shared_ptr< Base > | shared_ptr |
Public Member Functions | |
| Constrained (const Vector &sigmas=Z_1x1) | |
| bool | constrained (size_t i) const |
| Return true if a particular dimension is free or constrained. More... | |
| bool | isConstrained () const override |
| true if a constrained noise mode, saves slow/clumsy dynamic casting More... | |
| const Vector & | mu () const |
| Access mu as a vector. More... | |
| void | print (const std::string &name) const override |
| Diagonal::shared_ptr | QR (Matrix &Ab) const override |
| double | squaredMahalanobisDistance (const Vector &v) const override |
| shared_ptr | unit () const |
| Matrix | Whiten (const Matrix &H) const override |
| Vector | whiten (const Vector &v) const override |
| Calculates error vector with weights applied. More... | |
| void | WhitenInPlace (Eigen::Block< Matrix > H) const override |
| void | WhitenInPlace (Matrix &H) const override |
| ~Constrained () override | |
Public Member Functions inherited from gtsam::noiseModel::Diagonal | |
| Diagonal () | |
| double | invsigma (size_t i) const |
| const Vector & | invsigmas () const |
| double | precision (size_t i) const |
| const Vector & | precisions () const |
| Matrix | R () const override |
| double | sigma (size_t i) const |
| Vector | sigmas () const override |
| Calculate standard deviations. More... | |
| Vector | unwhiten (const Vector &v) const override |
| Unwhiten an error vector. More... | |
| ~Diagonal () override | |
Public Member Functions inherited from gtsam::noiseModel::Gaussian | |
| virtual Matrix | covariance () const |
| Compute covariance matrix. More... | |
| bool | equals (const Base &expected, double tol=1e-9) const override |
| Gaussian (size_t dim=1, const std::optional< Matrix > &sqrt_information={}) | |
| virtual Matrix | information () const |
| Compute information matrix. More... | |
| double | logDeterminant () const |
| Compute the log of |Σ|. More... | |
| double | negLogConstant () const |
| Compute the negative log of the normalization constant for a Gaussian noise model k = 1/\sqrt(|2πΣ|). 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 |
| ~Gaussian () override | |
Public Member Functions inherited from gtsam::noiseModel::Base | |
| Base (size_t dim=1) | |
| primary constructor More... | |
| size_t | dim () const |
| Dimensionality. 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 Vector | unweightedWhiten (const Vector &v) const |
| virtual void | unwhitenInPlace (Eigen::Block< Vector > &v) const |
| virtual void | unwhitenInPlace (Vector &v) const |
| virtual double | weight (const 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 | 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 | MixedPrecisions (const Vector &mu, const Vector &precisions) |
| static shared_ptr | MixedPrecisions (const Vector &precisions) |
| 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 Public Member Functions inherited from gtsam::noiseModel::Diagonal | |
| static shared_ptr | Precisions (const Vector &precisions, bool smart=true) |
| static shared_ptr | Sigmas (const Vector &sigmas, bool smart=true) |
| static shared_ptr | Variances (const Vector &variances, bool smart=true) |
Static Public Member Functions inherited from gtsam::noiseModel::Gaussian | |
| static shared_ptr | Covariance (const Matrix &covariance, bool smart=true) |
| static shared_ptr | Information (const Matrix &M, bool smart=true) |
| static shared_ptr | SqrtInformation (const Matrix &R, bool smart=true) |
Protected Member Functions | |
| Constrained (const Vector &mu, const Vector &sigmas) | |
Protected Member Functions inherited from gtsam::noiseModel::Diagonal | |
| Diagonal (const Vector &sigmas) | |
| virtual double | logDetR () const override |
| Compute the log of |R|. Used for computing log(|Σ|) More... | |
Protected Attributes | |
| Vector | mu_ |
| Penalty function weight - needs to be large enough to dominate soft constraints. More... | |
Protected Attributes inherited from gtsam::noiseModel::Diagonal | |
| Vector | invsigmas_ |
| Vector | precisions_ |
| Vector | sigmas_ |
Protected Attributes inherited from gtsam::noiseModel::Gaussian | |
| std::optional< Matrix > | sqrt_information_ |
Protected Attributes inherited from gtsam::noiseModel::Base | |
| 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.
Definition at line 404 of file NoiseModel.h.
| typedef std::shared_ptr<Constrained> gtsam::noiseModel::Constrained::shared_ptr |
Definition at line 419 of file NoiseModel.h.
Constructor that prevents any inf values from appearing in invsigmas or precisions. Allows for specifying mu.
Definition at line 362 of file NoiseModel.cpp.
| 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)
Definition at line 356 of file NoiseModel.cpp.
|
inlineoverride |
Definition at line 429 of file NoiseModel.h.
|
inlinestatic |
Fully constrained variations
Definition at line 480 of file NoiseModel.h.
|
inlinestatic |
Fully constrained variations
Definition at line 485 of file NoiseModel.h.
|
inlinestatic |
Fully constrained variations with a mu parameter
Definition at line 490 of file NoiseModel.h.
| bool gtsam::noiseModel::Constrained::constrained | ( | size_t | i | ) | const |
Return true if a particular dimension is free or constrained.
Definition at line 374 of file NoiseModel.cpp.
|
inlineoverridevirtual |
true if a constrained noise mode, saves slow/clumsy dynamic casting
Reimplemented from gtsam::noiseModel::Base.
Definition at line 432 of file NoiseModel.h.
|
static |
A diagonal noise model created by specifying a Vector of precisions, some of which might be inf
Definition at line 420 of file NoiseModel.cpp.
|
static |
Definition at line 424 of file NoiseModel.cpp.
|
static |
A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero
Definition at line 368 of file NoiseModel.cpp.
|
static |
A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero
Definition at line 403 of file NoiseModel.cpp.
|
static |
A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero
Definition at line 407 of file NoiseModel.cpp.
|
static |
A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero
Definition at line 412 of file NoiseModel.cpp.
|
static |
Definition at line 416 of file NoiseModel.cpp.
|
inline |
Access mu as a vector.
Definition at line 438 of file NoiseModel.h.
|
overridevirtual |
Reimplemented from gtsam::noiseModel::Diagonal.
Definition at line 380 of file NoiseModel.cpp.
|
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.
Definition at line 494 of file NoiseModel.cpp.
|
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.
Definition at line 429 of file NoiseModel.cpp.
| Constrained::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
Definition at line 461 of file NoiseModel.cpp.
Whitening functions will perform partial whitening on rows with a non-zero sigma. Other rows remain untouched.
Reimplemented from gtsam::noiseModel::Diagonal.
Definition at line 438 of file NoiseModel.cpp.
Calculates error vector with weights applied.
Reimplemented from gtsam::noiseModel::Diagonal.
Definition at line 386 of file NoiseModel.cpp.
|
overridevirtual |
In-place version
Reimplemented from gtsam::noiseModel::Diagonal.
Definition at line 454 of file NoiseModel.cpp.
|
overridevirtual |
In-place version
Reimplemented from gtsam::noiseModel::Diagonal.
Definition at line 447 of file NoiseModel.cpp.
|
protected |
Penalty function weight - needs to be large enough to dominate soft constraints.
Definition at line 408 of file NoiseModel.h.