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

#include <NoiseModel.h>

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

Public Types

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
 

Public Member Functions

double invsigma (size_t i) const
 
const Vectorinvsigmas () const
 
double precision (size_t i) const
 
const Vectorprecisions () const
 
void print (const std::string &name) const override
 
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...
 
Vector whiten (const Vector &v) const override
 Whiten an error vector. More...
 
Matrix Whiten (const Matrix &H) const override
 
void WhitenInPlace (Matrix &H) const override
 
void WhitenInPlace (Eigen::Block< Matrix > H) const override
 
 ~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
 
virtual Matrix information () const
 Compute information matrix. More...
 
virtual boost::shared_ptr< DiagonalQR (Matrix &Ab) const
 
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
 
 ~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 double squaredMahalanobisDistance (const Vector &v) const
 Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v> More...
 
virtual Vector unweightedWhiten (const Vector &v) const
 
virtual void unwhitenInPlace (Vector &v) const
 
virtual void unwhitenInPlace (Eigen::Block< Vector > &v) const
 
virtual double weight (const Vector &v) const
 
virtual void whitenInPlace (Vector &v) const
 
virtual void whitenInPlace (Eigen::Block< Vector > &v) const
 
virtual ~Base ()
 

Static Public Member Functions

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

 Diagonal ()
 
 Diagonal (const Vector &sigmas)
 
- Protected Member Functions inherited from gtsam::noiseModel::Gaussian
 Gaussian (size_t dim=1, const boost::optional< Matrix > &sqrt_information=boost::none)
 

Protected Attributes

Vector invsigmas_
 
Vector precisions_
 
Vector sigmas_
 
- Protected Attributes inherited from gtsam::noiseModel::Gaussian
boost::optional< Matrixsqrt_information_
 
- Protected Attributes inherited from gtsam::noiseModel::Base
size_t dim_
 

Private Member Functions

template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Friends

class boost::serialization::access
 

Detailed Description

A diagonal noise model implements a diagonal covariance matrix, with the elements of the diagonal specified in a Vector. This class has no public constructors, instead, use the static constructor functions Sigmas etc...

Definition at line 282 of file NoiseModel.h.

Member Typedef Documentation

Definition at line 301 of file NoiseModel.h.

Constructor & Destructor Documentation

gtsam::noiseModel::Diagonal::Diagonal ( )
protected

protected constructor - no initializations

Definition at line 244 of file NoiseModel.cpp.

gtsam::noiseModel::Diagonal::Diagonal ( const Vector sigmas)
protected

constructor to allow for disabling initialization of invsigmas

Definition at line 250 of file NoiseModel.cpp.

gtsam::noiseModel::Diagonal::~Diagonal ( )
inlineoverride

Definition at line 303 of file NoiseModel.h.

Member Function Documentation

double gtsam::noiseModel::Diagonal::invsigma ( size_t  i) const
inline

Definition at line 344 of file NoiseModel.h.

const Vector& gtsam::noiseModel::Diagonal::invsigmas ( ) const
inline

Return sqrt precisions

Definition at line 343 of file NoiseModel.h.

double gtsam::noiseModel::Diagonal::precision ( size_t  i) const
inline

Definition at line 350 of file NoiseModel.h.

static shared_ptr gtsam::noiseModel::Diagonal::Precisions ( const Vector precisions,
bool  smart = true 
)
inlinestatic

A diagonal noise model created by specifying a Vector of precisions, i.e. i.e. the diagonal of the information matrix, i.e., weights

Definition at line 323 of file NoiseModel.h.

const Vector& gtsam::noiseModel::Diagonal::precisions ( ) const
inline

Return precisions

Definition at line 349 of file NoiseModel.h.

void gtsam::noiseModel::Diagonal::print ( const std::string &  name) const
overridevirtual
Matrix gtsam::noiseModel::Diagonal::R ( ) const
inlineoverridevirtual

Return R itself, but note that Whiten(H) is cheaper than R*H

Reimplemented from gtsam::noiseModel::Gaussian.

Definition at line 355 of file NoiseModel.h.

template<class ARCHIVE >
void gtsam::noiseModel::Diagonal::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 363 of file NoiseModel.h.

double gtsam::noiseModel::Diagonal::sigma ( size_t  i) const
inline

Return standard deviations (sqrt of diagonal)

Definition at line 338 of file NoiseModel.h.

Diagonal::shared_ptr gtsam::noiseModel::Diagonal::Sigmas ( const Vector sigmas,
bool  smart = true 
)
static

A diagonal noise model created by specifying a Vector of sigmas, i.e. standard deviations, the diagonal of the square root covariance matrix.

Definition at line 270 of file NoiseModel.cpp.

Vector gtsam::noiseModel::Diagonal::sigmas ( ) const
inlineoverridevirtual

Calculate standard deviations.

Reimplemented from gtsam::noiseModel::Gaussian.

Definition at line 328 of file NoiseModel.h.

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

Unwhiten an error vector.

Reimplemented from gtsam::noiseModel::Gaussian.

Reimplemented in gtsam::noiseModel::Unit, and gtsam::noiseModel::Isotropic.

Definition at line 297 of file NoiseModel.cpp.

Diagonal::shared_ptr gtsam::noiseModel::Diagonal::Variances ( const Vector variances,
bool  smart = true 
)
static

A diagonal noise model created by specifying a Vector of variances, i.e. i.e. the diagonal of the covariance matrix.

Parameters
variancesA vector containing the variances of this noise model
smartcheck if can be simplified to derived class

Definition at line 258 of file NoiseModel.cpp.

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

Whiten an error vector.

Reimplemented from gtsam::noiseModel::Gaussian.

Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Constrained.

Definition at line 292 of file NoiseModel.cpp.

Matrix gtsam::noiseModel::Diagonal::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::Gaussian.

Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Constrained.

Definition at line 302 of file NoiseModel.cpp.

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

In-place version

Reimplemented from gtsam::noiseModel::Gaussian.

Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Constrained.

Definition at line 307 of file NoiseModel.cpp.

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

In-place version

Reimplemented from gtsam::noiseModel::Gaussian.

Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Constrained.

Definition at line 312 of file NoiseModel.cpp.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 361 of file NoiseModel.h.

Member Data Documentation

Vector gtsam::noiseModel::Diagonal::invsigmas_
protected

Definition at line 290 of file NoiseModel.h.

Vector gtsam::noiseModel::Diagonal::precisions_
protected

Definition at line 290 of file NoiseModel.h.

Vector gtsam::noiseModel::Diagonal::sigmas_
protected

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.

Definition at line 290 of file NoiseModel.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:53