Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gtsam::noiseModel::Isotropic Class Reference

#include <NoiseModel.h>

Inheritance diagram for gtsam::noiseModel::Isotropic:
Inheritance graph
[legend]

Public Types

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

Public Member Functions

 Isotropic ()
 
void print (const std::string &name) const override
 
double sigma () const
 
double squaredMahalanobisDistance (const Vector &v) const override
 Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v> More...
 
Vector unwhiten (const Vector &v) const override
 Unwhiten an error vector. More...
 
Matrix Whiten (const Matrix &H) const override
 
Vector whiten (const Vector &v) const override
 Whiten an error vector. More...
 
void WhitenInPlace (Eigen::Block< Matrix > H) const override
 
void WhitenInPlace (Matrix &H) const override
 
void whitenInPlace (Vector &v) const override
 
 ~Isotropic () override
 
- Public Member Functions inherited from gtsam::noiseModel::Diagonal
 Diagonal ()
 
double invsigma (size_t i) const
 
const Vectorinvsigmas () const
 
double precision (size_t i) const
 
const Vectorprecisions () const
 
Matrix R () const override
 
double sigma (size_t i) const
 
Vector sigmas () const override
 Calculate standard deviations. 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...
 
virtual std::shared_ptr< DiagonalQR (Matrix &Ab) const
 
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 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 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 ~Base ()
 

Static Public Member Functions

static shared_ptr Precision (size_t dim, double precision, bool smart=true)
 
static shared_ptr Sigma (size_t dim, double sigma, bool smart=true)
 
static shared_ptr Variance (size_t dim, double variance, bool smart=true)
 
- 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

 Isotropic (size_t dim, double sigma)
 
virtual double logDetR () const override
 Compute the log of |R|. Used for computing log(|Σ|) More...
 
- Protected Member Functions inherited from gtsam::noiseModel::Diagonal
 Diagonal (const Vector &sigmas)
 

Protected Attributes

double invsigma_
 
double sigma_
 
- Protected Attributes inherited from gtsam::noiseModel::Diagonal
Vector invsigmas_
 
Vector precisions_
 
Vector sigmas_
 
- Protected Attributes inherited from gtsam::noiseModel::Gaussian
std::optional< Matrixsqrt_information_
 
- Protected Attributes inherited from gtsam::noiseModel::Base
size_t dim_
 

Detailed Description

An isotropic noise model corresponds to a scaled diagonal covariance To construct, use one of the static methods

Definition at line 541 of file NoiseModel.h.

Member Typedef Documentation

◆ shared_ptr

Definition at line 559 of file NoiseModel.h.

Constructor & Destructor Documentation

◆ Isotropic() [1/2]

gtsam::noiseModel::Isotropic::Isotropic ( size_t  dim,
double  sigma 
)
inlineprotected

protected constructor takes sigma

Definition at line 546 of file NoiseModel.h.

◆ Isotropic() [2/2]

gtsam::noiseModel::Isotropic::Isotropic ( )
inline

Definition at line 555 of file NoiseModel.h.

◆ ~Isotropic()

gtsam::noiseModel::Isotropic::~Isotropic ( )
inlineoverride

Definition at line 557 of file NoiseModel.h.

Member Function Documentation

◆ logDetR()

double gtsam::noiseModel::Isotropic::logDetR ( ) const
overrideprotectedvirtual

Compute the log of |R|. Used for computing log(|Σ|)

Reimplemented from gtsam::noiseModel::Diagonal.

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 676 of file NoiseModel.cpp.

◆ Precision()

static shared_ptr gtsam::noiseModel::Isotropic::Precision ( size_t  dim,
double  precision,
bool  smart = true 
)
inlinestatic

An isotropic noise model created by specifying a precision

Definition at line 577 of file NoiseModel.h.

◆ print()

void gtsam::noiseModel::Isotropic::print ( const std::string &  name) const
overridevirtual

Reimplemented from gtsam::noiseModel::Diagonal.

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 636 of file NoiseModel.cpp.

◆ sigma()

double gtsam::noiseModel::Isotropic::sigma ( ) const
inline

Return standard deviation

Definition at line 593 of file NoiseModel.h.

◆ Sigma()

Isotropic::shared_ptr gtsam::noiseModel::Isotropic::Sigma ( size_t  dim,
double  sigma,
bool  smart = true 
)
static

An isotropic noise model created by specifying a standard devation sigma

Definition at line 624 of file NoiseModel.cpp.

◆ squaredMahalanobisDistance()

double gtsam::noiseModel::Isotropic::squaredMahalanobisDistance ( const Vector v) const
overridevirtual

Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>

Reimplemented from gtsam::noiseModel::Base.

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 641 of file NoiseModel.cpp.

◆ unwhiten()

Vector gtsam::noiseModel::Isotropic::unwhiten ( const Vector v) const
overridevirtual

Unwhiten an error vector.

Reimplemented from gtsam::noiseModel::Diagonal.

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 651 of file NoiseModel.cpp.

◆ Variance()

Isotropic::shared_ptr gtsam::noiseModel::Isotropic::Variance ( size_t  dim,
double  variance,
bool  smart = true 
)
static

An isotropic noise model created by specifying a variance = sigma^2.

Parameters
dimThe dimension of this noise model
varianceThe variance of this noise model
smartcheck if can be simplified to derived class

Definition at line 630 of file NoiseModel.cpp.

◆ Whiten()

Matrix gtsam::noiseModel::Isotropic::Whiten ( const Matrix H) const
overridevirtual

Multiply a derivative with R (derivative of whiten) Equivalent to whitening each column of the input matrix.

Reimplemented from gtsam::noiseModel::Diagonal.

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 656 of file NoiseModel.cpp.

◆ whiten()

Vector gtsam::noiseModel::Isotropic::whiten ( const Vector v) const
overridevirtual

Whiten an error vector.

Reimplemented from gtsam::noiseModel::Diagonal.

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 646 of file NoiseModel.cpp.

◆ WhitenInPlace() [1/2]

void gtsam::noiseModel::Isotropic::WhitenInPlace ( Eigen::Block< Matrix H) const
overridevirtual

In-place version

Reimplemented from gtsam::noiseModel::Diagonal.

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 671 of file NoiseModel.cpp.

◆ WhitenInPlace() [2/2]

void gtsam::noiseModel::Isotropic::WhitenInPlace ( Matrix H) const
overridevirtual

In-place version

Reimplemented from gtsam::noiseModel::Diagonal.

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 661 of file NoiseModel.cpp.

◆ whitenInPlace()

void gtsam::noiseModel::Isotropic::whitenInPlace ( Vector v) const
overridevirtual

in-place whiten, override if can be done more efficiently

Reimplemented from gtsam::noiseModel::Base.

Reimplemented in gtsam::noiseModel::Unit.

Definition at line 666 of file NoiseModel.cpp.

Member Data Documentation

◆ invsigma_

double gtsam::noiseModel::Isotropic::invsigma_
protected

Definition at line 543 of file NoiseModel.h.

◆ sigma_

double gtsam::noiseModel::Isotropic::sigma_
protected

Definition at line 543 of file NoiseModel.h.


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


gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:53:01