#include <NoiseModel.h>
Public Types | |
typedef std::shared_ptr< Gaussian > | shared_ptr |
Public Types inherited from gtsam::noiseModel::Base | |
typedef std::shared_ptr< Base > | shared_ptr |
Public Member Functions | |
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... | |
void | print (const std::string &name) const override |
virtual std::shared_ptr< Diagonal > | QR (Matrix &Ab) const |
virtual Matrix | R () const |
Return R itself, but note that Whiten(H) is cheaper than R*H. More... | |
Vector | sigmas () const override |
Calculate standard deviations. 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... | |
virtual void | WhitenInPlace (Eigen::Block< Matrix > H) const |
virtual void | WhitenInPlace (Matrix &H) 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 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 (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 void | whitenInPlace (Vector &v) const |
virtual | ~Base () |
Static Public Member Functions | |
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 Attributes | |
std::optional< Matrix > | sqrt_information_ |
Protected Attributes inherited from gtsam::noiseModel::Base | |
size_t | dim_ |
Private Member Functions | |
virtual double | logDetR () const |
Compute the log of |R|. Used for computing log(|Σ|) More... | |
const Matrix & | thisR () const |
Gaussian implements the mathematical model |R*x|^2 = |y|^2 with R'*R=inv(Sigma) where y = whiten(x) = R*x x = unwhiten(x) = inv(R)*y as indeed |y|^2 = y'*y = x'*R'*R*x Various derived classes are available that are more efficient. The named constructors return a shared_ptr because, when the smart flag is true, the underlying object might be a derived class such as Diagonal.
Definition at line 168 of file NoiseModel.h.
typedef std::shared_ptr<Gaussian> gtsam::noiseModel::Gaussian::shared_ptr |
Definition at line 191 of file NoiseModel.h.
|
inline |
constructor takes square root information matrix
Definition at line 194 of file NoiseModel.h.
|
inlineoverride |
Definition at line 198 of file NoiseModel.h.
|
virtual |
Compute covariance matrix.
Definition at line 148 of file NoiseModel.cpp.
|
static |
A Gaussian noise model created by specifying a covariance matrix.
covariance | The square covariance Matrix |
smart | check if can be simplified to derived class |
Definition at line 115 of file NoiseModel.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
Definition at line 140 of file NoiseModel.cpp.
|
virtual |
Compute information matrix.
Definition at line 240 of file NoiseModel.cpp.
|
static |
A Gaussian noise model created by specifying an information matrix.
M | The information matrix |
smart | check if can be simplified to derived class |
Definition at line 98 of file NoiseModel.cpp.
double gtsam::noiseModel::Gaussian::logDeterminant | ( | ) | const |
Compute the log of |Σ|.
Definition at line 250 of file NoiseModel.cpp.
|
privatevirtual |
Compute the log of |R|. Used for computing log(|Σ|)
Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Diagonal.
Definition at line 243 of file NoiseModel.cpp.
double gtsam::noiseModel::Gaussian::negLogConstant | ( | ) | const |
Compute the negative log of the normalization constant for a Gaussian noise model k = 1/\sqrt(|2πΣ|).
Definition at line 259 of file NoiseModel.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, gtsam::noiseModel::Constrained, and gtsam::noiseModel::Diagonal.
Definition at line 135 of file NoiseModel.cpp.
|
virtual |
Apply appropriately weighted QR factorization to the system [A b] 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.
Ab | is the m*(n+1) augmented system matrix [A b] |
Reimplemented in gtsam::noiseModel::Constrained.
Definition at line 190 of file NoiseModel.cpp.
|
inlinevirtual |
Return R itself, but note that Whiten(H) is cheaper than R*H.
Reimplemented in gtsam::noiseModel::Diagonal.
Definition at line 263 of file NoiseModel.h.
|
overridevirtual |
Calculate standard deviations.
Reimplemented from gtsam::noiseModel::Base.
Reimplemented in gtsam::noiseModel::Diagonal.
Definition at line 159 of file NoiseModel.cpp.
|
static |
A Gaussian noise model created by specifying a square root information matrix.
R | The (upper-triangular) square root information matrix |
smart | check if can be simplified to derived class |
Definition at line 84 of file NoiseModel.cpp.
|
inlineprivate |
Return R itself, but note that Whiten(H) is cheaper than R*H
Definition at line 180 of file NoiseModel.h.
Unwhiten an error vector.
Implements gtsam::noiseModel::Base.
Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Diagonal.
Definition at line 169 of file NoiseModel.cpp.
Multiply a derivative with R (derivative of whiten) Equivalent to whitening each column of the input matrix.
Implements gtsam::noiseModel::Base.
Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, gtsam::noiseModel::Constrained, and gtsam::noiseModel::Diagonal.
Definition at line 174 of file NoiseModel.cpp.
Whiten an error vector.
Implements gtsam::noiseModel::Base.
Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, gtsam::noiseModel::Constrained, and gtsam::noiseModel::Diagonal.
Definition at line 164 of file NoiseModel.cpp.
|
virtual |
In-place version
Reimplemented in gtsam::noiseModel::Unit, gtsam::noiseModel::Isotropic, gtsam::noiseModel::Constrained, and gtsam::noiseModel::Diagonal.
Definition at line 184 of file NoiseModel.cpp.
|
virtual |
In-place version
Reimplemented in gtsam::noiseModel::Isotropic, gtsam::noiseModel::Constrained, gtsam::noiseModel::Diagonal, and gtsam::noiseModel::Unit.
Definition at line 179 of file NoiseModel.cpp.
Implements gtsam::noiseModel::Base.
Definition at line 222 of file NoiseModel.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
Definition at line 233 of file NoiseModel.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
Definition at line 227 of file NoiseModel.cpp.
|
overridevirtual |
Whiten a system, in place as well
Implements gtsam::noiseModel::Base.
Definition at line 217 of file NoiseModel.cpp.
|
protected |
Matrix square root of information matrix (R)
Definition at line 173 of file NoiseModel.h.