|
gtsam 4.2
gtsam
|
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.
Public Member Functions | |
| Gaussian (size_t dim=1, const boost::optional< Matrix > &sqrt_information=boost::none) | |
| constructor takes square root information matrix | |
| void | print (const std::string &name) const override |
| bool | equals (const Base &expected, double tol=1e-9) const override |
| Vector | sigmas () const override |
| Calculate standard deviations. | |
| Vector | whiten (const Vector &v) const override |
| Whiten an error vector. | |
| Vector | unwhiten (const Vector &v) const override |
| Unwhiten an error vector. | |
| Matrix | Whiten (const Matrix &H) const override |
| Multiply a derivative with R (derivative of whiten) Equivalent to whitening each column of the input matrix. | |
| virtual void | WhitenInPlace (Matrix &H) const |
| In-place version. | |
| virtual void | WhitenInPlace (Eigen::Block< Matrix > H) const |
| In-place version. | |
| void | WhitenSystem (std::vector< Matrix > &A, Vector &b) const override |
| Whiten a system, in place as well. | |
| 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 |
| virtual boost::shared_ptr< Diagonal > | QR (Matrix &Ab) const |
| 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). | |
| virtual Matrix | R () const |
| Return R itself, but note that Whiten(H) is cheaper than R*H. | |
| virtual Matrix | information () const |
| Compute information matrix. | |
| virtual Matrix | covariance () const |
| Compute covariance matrix. | |
| Public Member Functions inherited from gtsam::noiseModel::Base | |
| Base (size_t dim=1) | |
| primary constructor | |
| virtual bool | isConstrained () const |
| true if a constrained noise model, saves slow/clumsy dynamic casting | |
| virtual bool | isUnit () const |
| true if a unit noise model, saves slow/clumsy dynamic casting | |
| size_t | dim () const |
| Dimensionality. | |
| virtual double | squaredMahalanobisDistance (const Vector &v) const |
| Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>. | |
| virtual double | mahalanobisDistance (const Vector &v) const |
| Mahalanobis distance. | |
| virtual double | loss (const double squared_distance) const |
| loss function, input is Mahalanobis distance | |
| virtual void | whitenInPlace (Vector &v) const |
| in-place whiten, override if can be done more efficiently | |
| virtual void | unwhitenInPlace (Vector &v) const |
| in-place unwhiten, override if can be done more efficiently | |
| virtual void | whitenInPlace (Eigen::Block< Vector > &v) const |
| in-place whiten, override if can be done more efficiently | |
| virtual void | unwhitenInPlace (Eigen::Block< Vector > &v) const |
| in-place unwhiten, override if can be done more efficiently | |
| virtual Vector | unweightedWhiten (const Vector &v) const |
| Useful function for robust noise models to get the unweighted but whitened error. | |
| virtual double | weight (const Vector &v) const |
| get the weight from the effective loss function on residual vector v | |
Static Public Member Functions | |
| static shared_ptr | SqrtInformation (const Matrix &R, bool smart=true) |
| A Gaussian noise model created by specifying a square root information matrix. | |
| static shared_ptr | Information (const Matrix &M, bool smart=true) |
| A Gaussian noise model created by specifying an information matrix. | |
| static shared_ptr | Covariance (const Matrix &covariance, bool smart=true) |
| A Gaussian noise model created by specifying a covariance matrix. | |
Public Types | |
| typedef boost::shared_ptr< Gaussian > | shared_ptr |
| Public Types inherited from gtsam::noiseModel::Base | |
| typedef boost::shared_ptr< Base > | shared_ptr |
Protected Attributes | |
| boost::optional< Matrix > | sqrt_information_ |
| Matrix square root of information matrix (R). | |
| Protected Attributes inherited from gtsam::noiseModel::Base | |
| size_t | dim_ |
Friends | |
| class | boost::serialization::access |
| Serialization function. | |
|
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 |
|
overridevirtual |
Implements gtsam::noiseModel::Base.
|
static |
A Gaussian noise model created by specifying an information matrix.
| M | The information matrix |
| smart | check if can be simplified to derived class |
|
overridevirtual |
Implements gtsam::noiseModel::Base.
|
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.
|
inlinevirtual |
Return R itself, but note that Whiten(H) is cheaper than R*H.
Reimplemented in gtsam::noiseModel::Diagonal.
|
overridevirtual |
Calculate standard deviations.
Reimplemented from gtsam::noiseModel::Base.
|
static |
|
overridevirtual |
Unwhiten an error vector.
Implements gtsam::noiseModel::Base.
Reimplemented in gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Unit.
|
overridevirtual |
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::Isotropic, and gtsam::noiseModel::Unit.
|
overridevirtual |
Whiten an error vector.
Implements gtsam::noiseModel::Base.
Reimplemented in gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Unit.
|
virtual |
In-place version.
Reimplemented in gtsam::noiseModel::Constrained, gtsam::noiseModel::Diagonal, gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Unit.
|
virtual |
In-place version.
Reimplemented in gtsam::noiseModel::Constrained, gtsam::noiseModel::Diagonal, gtsam::noiseModel::Isotropic, and gtsam::noiseModel::Unit.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
|
overridevirtual |
Implements gtsam::noiseModel::Base.
|
overridevirtual |
Whiten a system, in place as well.
Implements gtsam::noiseModel::Base.