Wrapped more useful noiseModel methods
parent
4b723107b3
commit
a7e60a08fe
20
gtsam.h
20
gtsam.h
|
@ -1230,9 +1230,19 @@ virtual class Base {
|
|||
virtual class Gaussian : gtsam::noiseModel::Base {
|
||||
static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R);
|
||||
static gtsam::noiseModel::Gaussian* Covariance(Matrix R);
|
||||
Matrix R() const;
|
||||
|
||||
bool equals(gtsam::noiseModel::Base& expected, double tol);
|
||||
|
||||
// access to noise model
|
||||
Matrix R() const;
|
||||
Matrix information() const;
|
||||
Matrix covariance() const;
|
||||
|
||||
// Whitening operations
|
||||
Vector whiten(Vector v) const;
|
||||
Vector unwhiten(Vector v) const;
|
||||
Matrix Whiten(Matrix H) const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serializable() const;
|
||||
};
|
||||
|
@ -1243,6 +1253,11 @@ virtual class Diagonal : gtsam::noiseModel::Gaussian {
|
|||
static gtsam::noiseModel::Diagonal* Precisions(Vector precisions);
|
||||
Matrix R() const;
|
||||
|
||||
// access to noise model
|
||||
Vector sigmas() const;
|
||||
Vector invsigmas() const;
|
||||
Vector precisions() const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serializable() const;
|
||||
};
|
||||
|
@ -1269,6 +1284,9 @@ virtual class Isotropic : gtsam::noiseModel::Diagonal {
|
|||
static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace);
|
||||
static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision);
|
||||
|
||||
// access to noise model
|
||||
double sigma() const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serializable() const;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue