gtsam  4.0.0
gtsam
gtsam::noiseModel::Constrained Class Reference

Detailed Description

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.

+ Inheritance diagram for gtsam::noiseModel::Constrained:

Public Member Functions

virtual bool isConstrained () const
 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.
 
virtual double distance (const Vector &v) const
 The distance function for a constrained noisemodel, for non-constrained versions, uses sigmas, otherwise uses the penalty function with mu.
 
virtual void print (const std::string &name) const
 
virtual Vector whiten (const Vector &v) const
 Calculates error vector with weights applied.
 
virtual Matrix Whiten (const Matrix &H) const
 Whitening functions will perform partial whitening on rows with a non-zero sigma. More...
 
virtual void WhitenInPlace (Matrix &H) const
 In-place version.
 
virtual void WhitenInPlace (Eigen::Block< Matrix > H) const
 In-place version.
 
virtual Diagonal::shared_ptr QR (Matrix &Ab) const
 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). More...
 
shared_ptr unit () const
 Returns a Unit version of a constrained noisemodel in which constrained sigmas remain constrained and the rest are unit scaled.
 
- Public Member Functions inherited from gtsam::noiseModel::Diagonal
virtual Vector sigmas () const
 Calculate standard deviations.
 
virtual Vector unwhiten (const Vector &v) const
 Unwhiten an error vector.
 
double sigma (size_t i) const
 Return standard deviations (sqrt of diagonal)
 
const Vector & invsigmas () const
 Return sqrt precisions.
 
double invsigma (size_t i) const
 
const Vector & precisions () const
 Return precisions.
 
double precision (size_t i) const
 
virtual Matrix R () const
 Return R itself, but note that Whiten(H) is cheaper than R*H.
 
- Public Member Functions inherited from gtsam::noiseModel::Gaussian
virtual bool equals (const Base &expected, double tol=1e-9) const
 
virtual double Mahalanobis (const Vector &v) const
 Mahalanobis distance v'*R'*R*v = <R*v,R*v>
 
virtual void WhitenSystem (std::vector< Matrix > &A, Vector &b) const
 Whiten a system, in place as well.
 
virtual void WhitenSystem (Matrix &A, Vector &b) const
 
virtual void WhitenSystem (Matrix &A1, Matrix &A2, Vector &b) const
 
virtual void WhitenSystem (Matrix &A1, Matrix &A2, Matrix &A3, Vector &b) const
 
virtual Matrix information () const
 Compute information matrix.
 
virtual Matrix covariance () const
 Compute covariance matrix.
 
- Public Member Functions inherited from gtsam::noiseModel::Base
 Base (size_t dim=1)
 primary constructor More...
 
virtual bool isUnit () const
 true if a unit noise model, saves slow/clumsy dynamic casting
 
size_t dim () const
 Dimensionality.
 
virtual void whitenInPlace (Vector &v) const
 in-place whiten, override if can be done more efficiently
 
virtual void unwhitenInPlace (Vector &v) const
 in-place unwhiten, override if can be done more efficiently
 
virtual void whitenInPlace (Eigen::Block< Vector > &v) const
 in-place whiten, override if can be done more efficiently
 
virtual void unwhitenInPlace (Eigen::Block< Vector > &v) const
 in-place unwhiten, override if can be done more efficiently
 

Static Public Member Functions

static shared_ptr MixedSigmas (const Vector &mu, const Vector &sigmas)
 A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero.
 
static shared_ptr MixedSigmas (const Vector &sigmas)
 A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero.
 
static shared_ptr MixedSigmas (double m, const Vector &sigmas)
 A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero.
 
static shared_ptr MixedVariances (const Vector &mu, const Vector &variances)
 A diagonal noise model created by specifying a Vector of standard devations, some of which might be zero.
 
static shared_ptr MixedVariances (const Vector &variances)
 
static shared_ptr MixedPrecisions (const Vector &mu, const Vector &precisions)
 A diagonal noise model created by specifying a Vector of precisions, some of which might be inf.
 
static shared_ptr MixedPrecisions (const Vector &precisions)
 
static shared_ptr All (size_t dim)
 Fully constrained variations.
 
static shared_ptr All (size_t dim, const Vector &mu)
 Fully constrained variations.
 
static shared_ptr All (size_t dim, double mu)
 Fully constrained variations with a mu parameter.
 
- Static Public Member Functions inherited from gtsam::noiseModel::Diagonal
static shared_ptr Sigmas (const Vector &sigmas, bool smart=true)
 A diagonal noise model created by specifying a Vector of sigmas, i.e. More...
 
static shared_ptr Variances (const Vector &variances, bool smart=true)
 A diagonal noise model created by specifying a Vector of variances, i.e. More...
 
static shared_ptr Precisions (const Vector &precisions, bool smart=true)
 A diagonal noise model created by specifying a Vector of precisions, i.e. More...
 
- Static Public Member Functions inherited from gtsam::noiseModel::Gaussian
static shared_ptr SqrtInformation (const Matrix &R, bool smart=true)
 A Gaussian noise model created by specifying a square root information matrix. More...
 
static shared_ptr Information (const Matrix &M, bool smart=true)
 A Gaussian noise model created by specifying an information matrix. More...
 
static shared_ptr Covariance (const Matrix &covariance, bool smart=true)
 A Gaussian noise model created by specifying a covariance matrix. More...
 

Public Types

typedef boost::shared_ptr< Constrainedshared_ptr
 
- Public Types inherited from gtsam::noiseModel::Diagonal
typedef boost::shared_ptr< Diagonalshared_ptr
 
- Public Types inherited from gtsam::noiseModel::Gaussian
typedef boost::shared_ptr< Gaussianshared_ptr
 
- Public Types inherited from gtsam::noiseModel::Base
typedef boost::shared_ptr< Baseshared_ptr
 

Protected Member Functions

 Constrained (const Vector &sigmas=Z_1x1)
 protected constructor takes sigmas. More...
 
 Constrained (const Vector &mu, const Vector &sigmas)
 Constructor that prevents any inf values from appearing in invsigmas or precisions. More...
 
- Protected Member Functions inherited from gtsam::noiseModel::Diagonal
 Diagonal ()
 protected constructor - no initializations
 
 Diagonal (const Vector &sigmas)
 constructor to allow for disabling initialization of invsigmas
 
- Protected Member Functions inherited from gtsam::noiseModel::Gaussian
 Gaussian (size_t dim=1, const boost::optional< Matrix > &sqrt_information=boost::none)
 protected constructor takes square root information matrix
 

Protected Attributes

Vector mu_
 Penalty function weight - needs to be large enough to dominate soft constraints.
 
- Protected Attributes inherited from gtsam::noiseModel::Diagonal
Vector sigmas_
 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.
 
Vector invsigmas_
 
Vector precisions_
 
- Protected Attributes inherited from gtsam::noiseModel::Gaussian
boost::optional< Matrix > sqrt_information_
 Matrix square root of information matrix (R)
 
- Protected Attributes inherited from gtsam::noiseModel::Base
size_t dim_
 

Friends

class boost::serialization::access
 Serialization function.
 

Constructor & Destructor Documentation

◆ Constrained() [1/2]

gtsam::noiseModel::Constrained::Constrained ( const Vector &  sigmas = Z_1x1)
protected

protected constructor takes sigmas.

prevents any inf values from appearing in invsigmas or precisions. mu set to large default value (1000.0)

◆ Constrained() [2/2]

gtsam::noiseModel::Constrained::Constrained ( const Vector &  mu,
const Vector &  sigmas 
)
protected

Constructor that prevents any inf values from appearing in invsigmas or precisions.

Allows for specifying mu.

Member Function Documentation

◆ QR()

SharedDiagonal gtsam::noiseModel::Constrained::QR ( Matrix &  Ab) const
virtual

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.

Parameters
Abis the m*(n+1) augmented system matrix [A b]
Returns
diagonal noise model can be all zeros, mixed, or not-constrained

Reimplemented from gtsam::noiseModel::Gaussian.

◆ Whiten()

Matrix gtsam::noiseModel::Constrained::Whiten ( const Matrix &  H) const
virtual

Whitening functions will perform partial whitening on rows with a non-zero sigma.

Other rows remain untouched.

Reimplemented from gtsam::noiseModel::Diagonal.


The documentation for this class was generated from the following files: