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

#include <NoiseModel.h>

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

Public Types

typedef std::shared_ptr< Unitshared_ptr
 
- Public Types inherited from gtsam::noiseModel::Isotropic
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

bool isUnit () const override
 true if a unit noise model, saves slow/clumsy dynamic casting More...
 
void print (const std::string &name) const override
 
double squaredMahalanobisDistance (const Vector &v) const override
 Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v> More...
 
 Unit (size_t dim=1)
 
Vector unwhiten (const Vector &v) const override
 Unwhiten an error vector. More...
 
void unwhitenInPlace (Eigen::Block< Vector > &) const override
 
void unwhitenInPlace (Vector &) const override
 
Matrix Whiten (const Matrix &H) const override
 
Vector whiten (const Vector &v) const override
 Whiten an error vector. More...
 
void WhitenInPlace (Eigen::Block< Matrix >) const override
 
void whitenInPlace (Eigen::Block< Vector > &) const override
 
void WhitenInPlace (Matrix &) const override
 
void whitenInPlace (Vector &) const override
 
 ~Unit () override
 
- Public Member Functions inherited from gtsam::noiseModel::Isotropic
 Isotropic ()
 
double sigma () const
 
 ~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 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 double weight (const Vector &v) const
 
virtual ~Base ()
 

Static Public Member Functions

static shared_ptr Create (size_t dim)
 
- Static Public Member Functions inherited from gtsam::noiseModel::Isotropic
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

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

Additional Inherited Members

- Protected Attributes inherited from gtsam::noiseModel::Isotropic
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

Unit: i.i.d. unit-variance noise on all m dimensions.

Definition at line 614 of file NoiseModel.h.

Member Typedef Documentation

◆ shared_ptr

typedef std::shared_ptr<Unit> gtsam::noiseModel::Unit::shared_ptr

Definition at line 621 of file NoiseModel.h.

Constructor & Destructor Documentation

◆ Unit()

gtsam::noiseModel::Unit::Unit ( size_t  dim = 1)
inline

constructor for serialization

Definition at line 624 of file NoiseModel.h.

◆ ~Unit()

gtsam::noiseModel::Unit::~Unit ( )
inlineoverride

Definition at line 626 of file NoiseModel.h.

Member Function Documentation

◆ Create()

static shared_ptr gtsam::noiseModel::Unit::Create ( size_t  dim)
inlinestatic

Create a unit covariance noise model

Definition at line 631 of file NoiseModel.h.

◆ isUnit()

bool gtsam::noiseModel::Unit::isUnit ( ) const
inlineoverridevirtual

true if a unit noise model, saves slow/clumsy dynamic casting

Reimplemented from gtsam::noiseModel::Base.

Definition at line 636 of file NoiseModel.h.

◆ logDetR()

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

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

Reimplemented from gtsam::noiseModel::Isotropic.

Definition at line 692 of file NoiseModel.cpp.

◆ print()

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

Reimplemented from gtsam::noiseModel::Isotropic.

Definition at line 682 of file NoiseModel.cpp.

◆ squaredMahalanobisDistance()

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

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

Reimplemented from gtsam::noiseModel::Isotropic.

Definition at line 687 of file NoiseModel.cpp.

◆ unwhiten()

Vector gtsam::noiseModel::Unit::unwhiten ( const Vector v) const
inlineoverridevirtual

Unwhiten an error vector.

Reimplemented from gtsam::noiseModel::Isotropic.

Definition at line 641 of file NoiseModel.h.

◆ unwhitenInPlace() [1/2]

void gtsam::noiseModel::Unit::unwhitenInPlace ( Eigen::Block< Vector > &  v) const
inlineoverridevirtual

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

Reimplemented from gtsam::noiseModel::Base.

Definition at line 648 of file NoiseModel.h.

◆ unwhitenInPlace() [2/2]

void gtsam::noiseModel::Unit::unwhitenInPlace ( Vector v) const
inlineoverridevirtual

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

Reimplemented from gtsam::noiseModel::Base.

Definition at line 646 of file NoiseModel.h.

◆ Whiten()

Matrix gtsam::noiseModel::Unit::Whiten ( const Matrix H) const
inlineoverridevirtual

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

Reimplemented from gtsam::noiseModel::Isotropic.

Definition at line 642 of file NoiseModel.h.

◆ whiten()

Vector gtsam::noiseModel::Unit::whiten ( const Vector v) const
inlineoverridevirtual

Whiten an error vector.

Reimplemented from gtsam::noiseModel::Isotropic.

Definition at line 640 of file NoiseModel.h.

◆ WhitenInPlace() [1/2]

void gtsam::noiseModel::Unit::WhitenInPlace ( Eigen::Block< Matrix H) const
inlineoverridevirtual

In-place version

Reimplemented from gtsam::noiseModel::Isotropic.

Definition at line 644 of file NoiseModel.h.

◆ whitenInPlace() [1/2]

void gtsam::noiseModel::Unit::whitenInPlace ( Eigen::Block< Vector > &  v) const
inlineoverridevirtual

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

Reimplemented from gtsam::noiseModel::Base.

Definition at line 647 of file NoiseModel.h.

◆ WhitenInPlace() [2/2]

void gtsam::noiseModel::Unit::WhitenInPlace ( Matrix H) const
inlineoverridevirtual

In-place version

Reimplemented from gtsam::noiseModel::Isotropic.

Definition at line 643 of file NoiseModel.h.

◆ whitenInPlace() [2/2]

void gtsam::noiseModel::Unit::whitenInPlace ( Vector v) const
inlineoverridevirtual

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

Reimplemented from gtsam::noiseModel::Isotropic.

Definition at line 645 of file NoiseModel.h.


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


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:24:55