23#include <gtsam/dllexport.h>
24#include <gtsam/linear/LossFunctions.h>
26#include <boost/serialization/nvp.hpp>
27#include <boost/serialization/extended_type_info.hpp>
28#include <boost/serialization/singleton.hpp>
29#include <boost/serialization/shared_ptr.hpp>
30#include <boost/serialization/optional.hpp>
35 namespace noiseModel {
56 typedef boost::shared_ptr<Base> shared_ptr;
65 Base(
size_t dim = 1):dim_(dim) {}
72 virtual bool isUnit()
const {
return false; }
75 inline size_t dim()
const {
return dim_;}
77 virtual void print(
const std::string& name =
"")
const = 0;
79 virtual bool equals(
const Base& expected,
double tol=1e-9)
const = 0;
82 virtual Vector sigmas()
const;
85 virtual Vector
whiten(
const Vector& v)
const = 0;
88 virtual Matrix
Whiten(
const Matrix& H)
const = 0;
91 virtual Vector
unwhiten(
const Vector& v)
const = 0;
94 virtual double squaredMahalanobisDistance(
const Vector& v)
const;
98 return std::sqrt(squaredMahalanobisDistance(v));
102 virtual double loss(
const double squared_distance)
const {
103 return 0.5 * squared_distance;
106 virtual void WhitenSystem(std::vector<Matrix>& A, Vector& b)
const = 0;
107 virtual void WhitenSystem(Matrix& A, Vector& b)
const = 0;
108 virtual void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b)
const = 0;
109 virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b)
const = 0;
137 virtual double weight(
const Vector& v)
const {
return 1.0; }
141 friend class boost::serialization::access;
142 template<
class ARCHIVE>
143 void serialize(ARCHIVE & ar,
const unsigned int ) {
144 ar & BOOST_SERIALIZATION_NVP(dim_);
174 const Matrix& thisR()
const {
176 if (!sqrt_information_)
throw std::runtime_error(
"Gaussian: has no R matrix");
177 return *sqrt_information_;
183 typedef boost::shared_ptr<Gaussian> shared_ptr;
187 const boost::optional<Matrix>& sqrt_information = boost::none)
188 :
Base(dim), sqrt_information_(sqrt_information) {}
197 static shared_ptr SqrtInformation(
const Matrix& R,
bool smart =
true);
204 static shared_ptr Information(
const Matrix& M,
bool smart =
true);
211 static shared_ptr Covariance(
const Matrix& covariance,
bool smart =
true);
213 void print(
const std::string& name)
const override;
214 bool equals(
const Base& expected,
double tol=1e-9)
const override;
215 Vector sigmas()
const override;
216 Vector whiten(
const Vector& v)
const override;
217 Vector unwhiten(
const Vector& v)
const override;
223 Matrix Whiten(
const Matrix& H)
const override;
228 virtual void WhitenInPlace(Matrix& H)
const;
233 virtual void WhitenInPlace(Eigen::Block<Matrix> H)
const;
238 void WhitenSystem(std::vector<Matrix>& A, Vector& b)
const override;
239 void WhitenSystem(Matrix& A, Vector& b)
const override;
240 void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b)
const override;
241 void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b)
const override;
252 virtual boost::shared_ptr<Diagonal> QR(Matrix& Ab)
const;
255 virtual Matrix
R()
const {
return thisR();}
258 virtual Matrix
information()
const {
return R().transpose() * R(); }
261 virtual Matrix covariance()
const;
265 friend class boost::serialization::access;
266 template<
class ARCHIVE>
267 void serialize(ARCHIVE & ar,
const unsigned int ) {
268 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
269 ar & BOOST_SERIALIZATION_NVP(sqrt_information_);
300 typedef boost::shared_ptr<Diagonal> shared_ptr;
308 static shared_ptr Sigmas(
const Vector& sigmas,
bool smart =
true);
316 static shared_ptr Variances(
const Vector& variances,
bool smart =
true);
322 static shared_ptr
Precisions(
const Vector& precisions,
bool smart =
true) {
323 return Variances(precisions.array().inverse(), smart);
326 void print(
const std::string& name)
const override;
327 Vector
sigmas()
const override {
return sigmas_; }
328 Vector whiten(
const Vector& v)
const override;
329 Vector unwhiten(
const Vector& v)
const override;
330 Matrix Whiten(
const Matrix& H)
const override;
331 void WhitenInPlace(Matrix& H)
const override;
332 void WhitenInPlace(Eigen::Block<Matrix> H)
const override;
337 inline double sigma(
size_t i)
const {
return sigmas_(i); }
342 inline const Vector&
invsigmas()
const {
return invsigmas_; }
343 inline double invsigma(
size_t i)
const {
return invsigmas_(i);}
348 inline const Vector&
precisions()
const {
return precisions_; }
349 inline double precision(
size_t i)
const {
return precisions_(i);}
354 Matrix
R()
const override {
355 return invsigmas().asDiagonal();
360 friend class boost::serialization::access;
361 template<
class ARCHIVE>
362 void serialize(ARCHIVE & ar,
const unsigned int ) {
363 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Gaussian);
364 ar & BOOST_SERIALIZATION_NVP(sigmas_);
365 ar & BOOST_SERIALIZATION_NVP(invsigmas_);
394 Constrained(
const Vector& mu,
const Vector& sigmas);
398 typedef boost::shared_ptr<Constrained> shared_ptr;
414 bool constrained(
size_t i)
const;
417 const Vector&
mu()
const {
return mu_; }
423 static shared_ptr MixedSigmas(
const Vector& mu,
const Vector& sigmas);
430 return MixedSigmas(Vector::Constant(sigmas.size(), 1000.0), sigmas);
438 return MixedSigmas(Vector::Constant(sigmas.size(), m), sigmas);
446 return shared_ptr(
new Constrained(mu, variances.cwiseSqrt()));
448 static shared_ptr MixedVariances(
const Vector& variances) {
449 return shared_ptr(
new Constrained(variances.cwiseSqrt()));
457 return MixedVariances(mu, precisions.array().inverse());
459 static shared_ptr MixedPrecisions(
const Vector& precisions) {
460 return MixedVariances(precisions.array().inverse());
468 double squaredMahalanobisDistance(
const Vector& v)
const override;
471 static shared_ptr
All(
size_t dim) {
472 return shared_ptr(
new Constrained(Vector::Constant(dim, 1000.0), Vector::Constant(dim,0)));
476 static shared_ptr
All(
size_t dim,
const Vector& mu) {
477 return shared_ptr(
new Constrained(mu, Vector::Constant(dim,0)));
481 static shared_ptr
All(
size_t dim,
double mu) {
482 return shared_ptr(
new Constrained(Vector::Constant(dim, mu), Vector::Constant(dim,0)));
485 void print(
const std::string& name)
const override;
488 Vector whiten(
const Vector& v)
const override;
492 Matrix Whiten(
const Matrix& H)
const override;
493 void WhitenInPlace(Matrix& H)
const override;
494 void WhitenInPlace(Eigen::Block<Matrix> H)
const override;
505 Diagonal::shared_ptr QR(Matrix& Ab)
const override;
511 shared_ptr unit()
const;
515 friend class boost::serialization::access;
516 template<
class ARCHIVE>
517 void serialize(ARCHIVE & ar,
const unsigned int ) {
518 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Diagonal);
519 ar & BOOST_SERIALIZATION_NVP(mu_);
532 double sigma_, invsigma_;
536 Diagonal(Vector::Constant(dim, sigma)),sigma_(sigma),invsigma_(1.0/sigma) {}
543 ~Isotropic()
override {}
545 typedef boost::shared_ptr<Isotropic> shared_ptr;
550 static shared_ptr Sigma(
size_t dim,
double sigma,
bool smart =
true);
558 static shared_ptr Variance(
size_t dim,
double variance,
bool smart =
true);
563 static shared_ptr
Precision(
size_t dim,
double precision,
bool smart =
true) {
564 return Variance(dim, 1.0/precision, smart);
567 void print(
const std::string& name)
const override;
568 double squaredMahalanobisDistance(
const Vector& v)
const override;
569 Vector whiten(
const Vector& v)
const override;
570 Vector unwhiten(
const Vector& v)
const override;
571 Matrix Whiten(
const Matrix& H)
const override;
572 void WhitenInPlace(Matrix& H)
const override;
573 void whitenInPlace(Vector& v)
const override;
574 void WhitenInPlace(Eigen::Block<Matrix> H)
const override;
579 inline double sigma()
const {
return sigma_; }
583 friend class boost::serialization::access;
584 template<
class ARCHIVE>
585 void serialize(ARCHIVE & ar,
const unsigned int ) {
586 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Diagonal);
587 ar & BOOST_SERIALIZATION_NVP(sigma_);
588 ar & BOOST_SERIALIZATION_NVP(invsigma_);
601 typedef boost::shared_ptr<Unit> shared_ptr;
612 return shared_ptr(
new Unit(dim));
616 bool isUnit()
const override {
return true; }
618 void print(
const std::string& name)
const override;
620 Vector
whiten(
const Vector& v)
const override {
return v; }
621 Vector
unwhiten(
const Vector& v)
const override {
return v; }
622 Matrix
Whiten(
const Matrix& H)
const override {
return H; }
632 friend class boost::serialization::access;
633 template<
class ARCHIVE>
634 void serialize(ARCHIVE & ar,
const unsigned int ) {
635 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Isotropic);
658 typedef boost::shared_ptr<Robust> shared_ptr;
673 Robust(
const RobustModel::shared_ptr robust,
const NoiseModel::shared_ptr noise)
674 :
Base(noise->dim()), robust_(robust), noise_(noise) {}
679 void print(
const std::string& name)
const override;
680 bool equals(
const Base& expected,
double tol=1e-9)
const override;
683 const RobustModel::shared_ptr&
robust()
const {
return robust_; }
686 const NoiseModel::shared_ptr&
noise()
const {
return noise_; }
689 inline Vector
whiten(
const Vector& v)
const override
690 { Vector r = v; this->WhitenSystem(r);
return r; }
691 inline Matrix
Whiten(
const Matrix& A)
const override
692 { Vector b; Matrix B=A; this->WhitenSystem(B,b);
return B; }
693 inline Vector
unwhiten(
const Vector& )
const override
694 {
throw std::invalid_argument(
"unwhiten is not currently supported for robust noise models."); }
696 double loss(
const double squared_distance)
const override {
697 return robust_->loss(std::sqrt(squared_distance));
701 virtual void WhitenSystem(Vector& b)
const;
702 void WhitenSystem(std::vector<Matrix>& A, Vector& b)
const override;
703 void WhitenSystem(Matrix& A, Vector& b)
const override;
704 void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b)
const override;
705 void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b)
const override;
708 return noise_->unweightedWhiten(v);
710 double weight(
const Vector& v)
const override {
711 return robust_->weight(v.norm());
714 static shared_ptr Create(
715 const RobustModel::shared_ptr &robust,
const NoiseModel::shared_ptr noise);
719 friend class boost::serialization::access;
720 template<
class ARCHIVE>
721 void serialize(ARCHIVE & ar,
const unsigned int ) {
722 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
723 ar & boost::serialization::make_nvp(
"robust_",
const_cast<RobustModel::shared_ptr&
>(robust_));
724 ar & boost::serialization::make_nvp(
"noise_",
const_cast<NoiseModel::shared_ptr&
>(noise_));
729 GTSAM_EXPORT boost::optional<Vector> checkIfDiagonal(
const Matrix M);
737 typedef noiseModel::Gaussian::shared_ptr SharedGaussian;
738 typedef noiseModel::Diagonal::shared_ptr SharedDiagonal;
739 typedef noiseModel::Constrained::shared_ptr SharedConstrained;
740 typedef noiseModel::Isotropic::shared_ptr SharedIsotropic;
743 template<>
struct traits<noiseModel::Gaussian> :
public Testable<noiseModel::Gaussian> {};
744 template<>
struct traits<noiseModel::Diagonal> :
public Testable<noiseModel::Diagonal> {};
745 template<>
struct traits<noiseModel::Constrained> :
public Testable<noiseModel::Constrained> {};
746 template<>
struct traits<noiseModel::Isotropic> :
public Testable<noiseModel::Isotropic> {};
747 template<>
struct traits<noiseModel::Unit> :
public Testable<noiseModel::Unit> {};
typedef and functions to augment Eigen's MatrixXd
Concept check for values that can be used in unit tests.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:112
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:155
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Template to create a binary predicate.
Definition: Testable.h:111
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:151
Definition: LossFunctions.h:59
noiseModel::Base is the abstract base class for all noise models.
Definition: NoiseModel.h:53
virtual bool isConstrained() const
true if a constrained noise model, saves slow/clumsy dynamic casting
Definition: NoiseModel.h:69
virtual void whitenInPlace(Vector &v) const
in-place whiten, override if can be done more efficiently
Definition: NoiseModel.h:112
size_t dim() const
Dimensionality.
Definition: NoiseModel.h:75
virtual void unwhitenInPlace(Eigen::Block< Vector > &v) const
in-place unwhiten, override if can be done more efficiently
Definition: NoiseModel.h:127
virtual void whitenInPlace(Eigen::Block< Vector > &v) const
in-place whiten, override if can be done more efficiently
Definition: NoiseModel.h:122
virtual Vector whiten(const Vector &v) const =0
Whiten an error vector.
virtual double mahalanobisDistance(const Vector &v) const
Mahalanobis distance.
Definition: NoiseModel.h:97
virtual bool isUnit() const
true if a unit noise model, saves slow/clumsy dynamic casting
Definition: NoiseModel.h:72
virtual double weight(const Vector &v) const
get the weight from the effective loss function on residual vector v
Definition: NoiseModel.h:137
virtual Vector unweightedWhiten(const Vector &v) const
Useful function for robust noise models to get the unweighted but whitened error.
Definition: NoiseModel.h:132
virtual Vector unwhiten(const Vector &v) const =0
Unwhiten an error vector.
virtual double loss(const double squared_distance) const
loss function, input is Mahalanobis distance
Definition: NoiseModel.h:102
virtual void unwhitenInPlace(Vector &v) const
in-place unwhiten, override if can be done more efficiently
Definition: NoiseModel.h:117
virtual Matrix Whiten(const Matrix &H) const =0
Whiten a matrix.
Base(size_t dim=1)
primary constructor
Definition: NoiseModel.h:65
Gaussian implements the mathematical model |R*x|^2 = |y|^2 with R'*R=inv(Sigma) where y = whiten(x) =...
Definition: NoiseModel.h:162
virtual Matrix R() const
Return R itself, but note that Whiten(H) is cheaper than R*H.
Definition: NoiseModel.h:255
Gaussian(size_t dim=1, const boost::optional< Matrix > &sqrt_information=boost::none)
constructor takes square root information matrix
Definition: NoiseModel.h:186
boost::optional< Matrix > sqrt_information_
Matrix square root of information matrix (R)
Definition: NoiseModel.h:167
virtual Matrix information() const
Compute information matrix.
Definition: NoiseModel.h:258
A diagonal noise model implements a diagonal covariance matrix, with the elements of the diagonal spe...
Definition: NoiseModel.h:281
Matrix R() const override
Return R itself, but note that Whiten(H) is cheaper than R*H.
Definition: NoiseModel.h:354
Vector sigmas_
Standard deviations (sigmas), their inverse and inverse square (weights/precisions) These are all com...
Definition: NoiseModel.h:289
double sigma(size_t i) const
Return standard deviations (sqrt of diagonal)
Definition: NoiseModel.h:337
const Vector & invsigmas() const
Return sqrt precisions.
Definition: NoiseModel.h:342
Vector sigmas() const override
Calculate standard deviations.
Definition: NoiseModel.h:327
const Vector & precisions() const
Return precisions.
Definition: NoiseModel.h:348
static shared_ptr Precisions(const Vector &precisions, bool smart=true)
A diagonal noise model created by specifying a Vector of precisions, i.e.
Definition: NoiseModel.h:322
A Constrained constrained model is a specialization of Diagonal which allows some or all of the sigma...
Definition: NoiseModel.h:383
bool isConstrained() const override
true if a constrained noise mode, saves slow/clumsy dynamic casting
Definition: NoiseModel.h:411
static shared_ptr All(size_t dim, const Vector &mu)
Fully constrained variations.
Definition: NoiseModel.h:476
static shared_ptr All(size_t dim, double mu)
Fully constrained variations with a mu parameter.
Definition: NoiseModel.h:481
static shared_ptr All(size_t dim)
Fully constrained variations.
Definition: NoiseModel.h:471
static shared_ptr MixedPrecisions(const Vector &mu, const Vector &precisions)
A diagonal noise model created by specifying a Vector of precisions, some of which might be inf.
Definition: NoiseModel.h:456
static shared_ptr MixedSigmas(const Vector &sigmas)
A diagonal noise model created by specifying a Vector of standard devations, some of which might be z...
Definition: NoiseModel.h:429
const Vector & mu() const
Access mu as a vector.
Definition: NoiseModel.h:417
static shared_ptr MixedSigmas(double m, const Vector &sigmas)
A diagonal noise model created by specifying a Vector of standard devations, some of which might be z...
Definition: NoiseModel.h:437
Vector mu_
Penalty function weight - needs to be large enough to dominate soft constraints.
Definition: NoiseModel.h:387
static shared_ptr MixedVariances(const Vector &mu, const Vector &variances)
A diagonal noise model created by specifying a Vector of standard devations, some of which might be z...
Definition: NoiseModel.h:445
An isotropic noise model corresponds to a scaled diagonal covariance To construct,...
Definition: NoiseModel.h:530
double sigma() const
Return standard deviation.
Definition: NoiseModel.h:579
static shared_ptr Precision(size_t dim, double precision, bool smart=true)
An isotropic noise model created by specifying a precision.
Definition: NoiseModel.h:563
Isotropic(size_t dim, double sigma)
protected constructor takes sigma
Definition: NoiseModel.h:535
Unit: i.i.d.
Definition: NoiseModel.h:598
void WhitenInPlace(Eigen::Block< Matrix >) const override
In-place version.
Definition: NoiseModel.h:624
Vector unwhiten(const Vector &v) const override
Unwhiten an error vector.
Definition: NoiseModel.h:621
double squaredMahalanobisDistance(const Vector &v) const override
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
Definition: NoiseModel.h:619
void whitenInPlace(Eigen::Block< Vector > &) const override
in-place whiten, override if can be done more efficiently
Definition: NoiseModel.h:627
bool isUnit() const override
true if a unit noise model, saves slow/clumsy dynamic casting
Definition: NoiseModel.h:616
Unit(size_t dim=1)
constructor for serialization
Definition: NoiseModel.h:604
Vector whiten(const Vector &v) const override
Whiten an error vector.
Definition: NoiseModel.h:620
static shared_ptr Create(size_t dim)
Create a unit covariance noise model.
Definition: NoiseModel.h:611
void unwhitenInPlace(Vector &) const override
in-place unwhiten, override if can be done more efficiently
Definition: NoiseModel.h:626
void unwhitenInPlace(Eigen::Block< Vector > &) const override
in-place unwhiten, override if can be done more efficiently
Definition: NoiseModel.h:628
void whitenInPlace(Vector &) const override
in-place whiten, override if can be done more efficiently
Definition: NoiseModel.h:625
void WhitenInPlace(Matrix &) const override
In-place version.
Definition: NoiseModel.h:623
Matrix Whiten(const Matrix &H) const override
Multiply a derivative with R (derivative of whiten) Equivalent to whitening each column of the input ...
Definition: NoiseModel.h:622
Base class for robust error models The robust M-estimators above simply tell us how to re-weight the ...
Definition: NoiseModel.h:656
const RobustModel::shared_ptr & robust() const
Return the contained robust error function.
Definition: NoiseModel.h:683
Robust()
Default Constructor for serialization.
Definition: NoiseModel.h:670
Robust(const RobustModel::shared_ptr robust, const NoiseModel::shared_ptr noise)
Constructor.
Definition: NoiseModel.h:673
Vector unweightedWhiten(const Vector &v) const override
Useful function for robust noise models to get the unweighted but whitened error.
Definition: NoiseModel.h:707
double weight(const Vector &v) const override
get the weight from the effective loss function on residual vector v
Definition: NoiseModel.h:710
const NoiseModel::shared_ptr noise_
noise model used
Definition: NoiseModel.h:665
double loss(const double squared_distance) const override
Compute loss from the m-estimator using the Mahalanobis distance.
Definition: NoiseModel.h:696
Vector unwhiten(const Vector &) const override
Unwhiten an error vector.
Definition: NoiseModel.h:693
Matrix Whiten(const Matrix &A) const override
Whiten a matrix.
Definition: NoiseModel.h:691
const RobustModel::shared_ptr robust_
robust error function used
Definition: NoiseModel.h:664
~Robust() override
Destructor.
Definition: NoiseModel.h:677
const NoiseModel::shared_ptr & noise() const
Return the contained noise model.
Definition: NoiseModel.h:686
Vector whiten(const Vector &v) const override
Whiten an error vector.
Definition: NoiseModel.h:689