#include <NoiseModel.h>
Public Types | |
typedef boost::shared_ptr< Isotropic > | shared_ptr |
Public Types inherited from gtsam::noiseModel::Diagonal | |
typedef boost::shared_ptr< Diagonal > | shared_ptr |
Public Types inherited from gtsam::noiseModel::Gaussian | |
typedef boost::shared_ptr< Gaussian > | shared_ptr |
Public Types inherited from gtsam::noiseModel::Base | |
typedef boost::shared_ptr< Base > | shared_ptr |
Public Member Functions | |
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... | |
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 (Vector &v) const override |
void | WhitenInPlace (Eigen::Block< Matrix > H) const override |
~Isotropic () override | |
Public Member Functions inherited from gtsam::noiseModel::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... | |
~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< Diagonal > | QR (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 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 (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) | |
Isotropic () | |
Protected Member Functions inherited from gtsam::noiseModel::Diagonal | |
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 | |
double | invsigma_ |
double | sigma_ |
Protected Attributes inherited from gtsam::noiseModel::Diagonal | |
Vector | invsigmas_ |
Vector | precisions_ |
Vector | sigmas_ |
Protected Attributes inherited from gtsam::noiseModel::Gaussian | |
boost::optional< Matrix > | sqrt_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 |
An isotropic noise model corresponds to a scaled diagonal covariance To construct, use one of the static methods
Definition at line 526 of file NoiseModel.h.
typedef boost::shared_ptr<Isotropic> gtsam::noiseModel::Isotropic::shared_ptr |
Definition at line 541 of file NoiseModel.h.
|
inlineprotected |
protected constructor takes sigma
Definition at line 531 of file NoiseModel.h.
|
inlineprotected |
Definition at line 535 of file NoiseModel.h.
|
inlineoverride |
Definition at line 539 of file NoiseModel.h.
|
inlinestatic |
An isotropic noise model created by specifying a precision
Definition at line 559 of file NoiseModel.h.
|
overridevirtual |
Reimplemented from gtsam::noiseModel::Diagonal.
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 579 of file NoiseModel.cpp.
|
inlineprivate |
Definition at line 581 of file NoiseModel.h.
|
static |
An isotropic noise model created by specifying a standard devation sigma
Definition at line 567 of file NoiseModel.cpp.
|
inline |
Return standard deviation
Definition at line 575 of file NoiseModel.h.
|
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 584 of file NoiseModel.cpp.
Unwhiten an error vector.
Reimplemented from gtsam::noiseModel::Diagonal.
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 594 of file NoiseModel.cpp.
|
static |
An isotropic noise model created by specifying a variance = sigma^2.
dim | The dimension of this noise model |
variance | The variance of this noise model |
smart | check if can be simplified to derived class |
Definition at line 573 of file NoiseModel.cpp.
Whiten an error vector.
Reimplemented from gtsam::noiseModel::Diagonal.
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 589 of file NoiseModel.cpp.
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 599 of file NoiseModel.cpp.
|
overridevirtual |
In-place version
Reimplemented from gtsam::noiseModel::Diagonal.
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 604 of file NoiseModel.cpp.
|
overridevirtual |
in-place whiten, override if can be done more efficiently
Reimplemented from gtsam::noiseModel::Base.
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 609 of file NoiseModel.cpp.
|
overridevirtual |
In-place version
Reimplemented from gtsam::noiseModel::Diagonal.
Reimplemented in gtsam::noiseModel::Unit.
Definition at line 614 of file NoiseModel.cpp.
|
friend |
Serialization function
Definition at line 579 of file NoiseModel.h.
|
protected |
Definition at line 528 of file NoiseModel.h.
|
protected |
Definition at line 528 of file NoiseModel.h.