gtsam 4.1.1
gtsam
NoiseModel.h
Go to the documentation of this file.
1/* ----------------------------------------------------------------------------
2
3 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4 * Atlanta, Georgia 30332-0415
5 * All Rights Reserved
6 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7
8 * See LICENSE for the license information
9
10 * -------------------------------------------------------------------------- */
11
19#pragma once
20
21#include <gtsam/base/Testable.h>
22#include <gtsam/base/Matrix.h>
23#include <gtsam/dllexport.h>
24#include <gtsam/linear/LossFunctions.h>
25
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>
31
32namespace gtsam {
33
35 namespace noiseModel {
36
37 // Forward declaration
38 class Gaussian;
39 class Diagonal;
40 class Constrained;
41 class Isotropic;
42 class Unit;
43 class RobustModel;
44
45 //---------------------------------------------------------------------------------------
46
53 class GTSAM_EXPORT Base {
54
55 public:
56 typedef boost::shared_ptr<Base> shared_ptr;
57
58 protected:
59
60 size_t dim_;
61
62 public:
63
65 Base(size_t dim = 1):dim_(dim) {}
66 virtual ~Base() {}
67
69 virtual bool isConstrained() const { return false; } // default false
70
72 virtual bool isUnit() const { return false; } // default false
73
75 inline size_t dim() const { return dim_;}
76
77 virtual void print(const std::string& name = "") const = 0;
78
79 virtual bool equals(const Base& expected, double tol=1e-9) const = 0;
80
82 virtual Vector sigmas() const;
83
85 virtual Vector whiten(const Vector& v) const = 0;
86
88 virtual Matrix Whiten(const Matrix& H) const = 0;
89
91 virtual Vector unwhiten(const Vector& v) const = 0;
92
94 virtual double squaredMahalanobisDistance(const Vector& v) const;
95
97 virtual double mahalanobisDistance(const Vector& v) const {
98 return std::sqrt(squaredMahalanobisDistance(v));
99 }
100
102 virtual double loss(const double squared_distance) const {
103 return 0.5 * squared_distance;
104 }
105
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;
110
112 virtual void whitenInPlace(Vector& v) const {
113 v = whiten(v);
114 }
115
117 virtual void unwhitenInPlace(Vector& v) const {
118 v = unwhiten(v);
119 }
120
122 virtual void whitenInPlace(Eigen::Block<Vector>& v) const {
123 v = whiten(v);
124 }
125
127 virtual void unwhitenInPlace(Eigen::Block<Vector>& v) const {
128 v = unwhiten(v);
129 }
130
132 virtual Vector unweightedWhiten(const Vector& v) const {
133 return whiten(v);
134 }
135
137 virtual double weight(const Vector& v) const { return 1.0; }
138
139 private:
141 friend class boost::serialization::access;
142 template<class ARCHIVE>
143 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
144 ar & BOOST_SERIALIZATION_NVP(dim_);
145 }
146 };
147
148 //---------------------------------------------------------------------------------------
149
162 class GTSAM_EXPORT Gaussian: public Base {
163
164 protected:
165
167 boost::optional<Matrix> sqrt_information_;
168
169 private:
170
174 const Matrix& thisR() const {
175 // should never happen
176 if (!sqrt_information_) throw std::runtime_error("Gaussian: has no R matrix");
177 return *sqrt_information_;
178 }
179
180
181 public:
182
183 typedef boost::shared_ptr<Gaussian> shared_ptr;
184
186 Gaussian(size_t dim = 1,
187 const boost::optional<Matrix>& sqrt_information = boost::none)
188 : Base(dim), sqrt_information_(sqrt_information) {}
189
190 ~Gaussian() override {}
191
197 static shared_ptr SqrtInformation(const Matrix& R, bool smart = true);
198
204 static shared_ptr Information(const Matrix& M, bool smart = true);
205
211 static shared_ptr Covariance(const Matrix& covariance, bool smart = true);
212
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;
218
223 Matrix Whiten(const Matrix& H) const override;
224
228 virtual void WhitenInPlace(Matrix& H) const;
229
233 virtual void WhitenInPlace(Eigen::Block<Matrix> H) const;
234
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;
242
252 virtual boost::shared_ptr<Diagonal> QR(Matrix& Ab) const;
253
255 virtual Matrix R() const { return thisR();}
256
258 virtual Matrix information() const { return R().transpose() * R(); }
259
261 virtual Matrix covariance() const;
262
263 private:
265 friend class boost::serialization::access;
266 template<class ARCHIVE>
267 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
268 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
269 ar & BOOST_SERIALIZATION_NVP(sqrt_information_);
270 }
271
272 }; // Gaussian
273
274 //---------------------------------------------------------------------------------------
275
281 class GTSAM_EXPORT Diagonal : public Gaussian {
282 protected:
283
289 Vector sigmas_, invsigmas_, precisions_;
290
291 protected:
292
294 Diagonal(const Vector& sigmas);
295
296 public:
298 Diagonal();
299
300 typedef boost::shared_ptr<Diagonal> shared_ptr;
301
302 ~Diagonal() override {}
303
308 static shared_ptr Sigmas(const Vector& sigmas, bool smart = true);
309
316 static shared_ptr Variances(const Vector& variances, bool smart = true);
317
322 static shared_ptr Precisions(const Vector& precisions, bool smart = true) {
323 return Variances(precisions.array().inverse(), smart);
324 }
325
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;
333
337 inline double sigma(size_t i) const { return sigmas_(i); }
338
342 inline const Vector& invsigmas() const { return invsigmas_; }
343 inline double invsigma(size_t i) const {return invsigmas_(i);}
344
348 inline const Vector& precisions() const { return precisions_; }
349 inline double precision(size_t i) const {return precisions_(i);}
350
354 Matrix R() const override {
355 return invsigmas().asDiagonal();
356 }
357
358 private:
360 friend class boost::serialization::access;
361 template<class ARCHIVE>
362 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
363 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Gaussian);
364 ar & BOOST_SERIALIZATION_NVP(sigmas_);
365 ar & BOOST_SERIALIZATION_NVP(invsigmas_);
366 }
367 }; // Diagonal
368
369 //---------------------------------------------------------------------------------------
370
383 class GTSAM_EXPORT Constrained : public Diagonal {
384 protected:
385
386 // Sigmas are contained in the base class
387 Vector mu_;
388
394 Constrained(const Vector& mu, const Vector& sigmas);
395
396 public:
397
398 typedef boost::shared_ptr<Constrained> shared_ptr;
399
406 Constrained(const Vector& sigmas = Z_1x1);
407
408 ~Constrained() override {}
409
411 bool isConstrained() const override { return true; }
412
414 bool constrained(size_t i) const;
415
417 const Vector& mu() const { return mu_; }
418
423 static shared_ptr MixedSigmas(const Vector& mu, const Vector& sigmas);
424
429 static shared_ptr MixedSigmas(const Vector& sigmas) {
430 return MixedSigmas(Vector::Constant(sigmas.size(), 1000.0), sigmas);
431 }
432
437 static shared_ptr MixedSigmas(double m, const Vector& sigmas) {
438 return MixedSigmas(Vector::Constant(sigmas.size(), m), sigmas);
439 }
440
445 static shared_ptr MixedVariances(const Vector& mu, const Vector& variances) {
446 return shared_ptr(new Constrained(mu, variances.cwiseSqrt()));
447 }
448 static shared_ptr MixedVariances(const Vector& variances) {
449 return shared_ptr(new Constrained(variances.cwiseSqrt()));
450 }
451
456 static shared_ptr MixedPrecisions(const Vector& mu, const Vector& precisions) {
457 return MixedVariances(mu, precisions.array().inverse());
458 }
459 static shared_ptr MixedPrecisions(const Vector& precisions) {
460 return MixedVariances(precisions.array().inverse());
461 }
462
468 double squaredMahalanobisDistance(const Vector& v) const override;
469
471 static shared_ptr All(size_t dim) {
472 return shared_ptr(new Constrained(Vector::Constant(dim, 1000.0), Vector::Constant(dim,0)));
473 }
474
476 static shared_ptr All(size_t dim, const Vector& mu) {
477 return shared_ptr(new Constrained(mu, Vector::Constant(dim,0)));
478 }
479
481 static shared_ptr All(size_t dim, double mu) {
482 return shared_ptr(new Constrained(Vector::Constant(dim, mu), Vector::Constant(dim,0)));
483 }
484
485 void print(const std::string& name) const override;
486
488 Vector whiten(const Vector& v) const override;
489
492 Matrix Whiten(const Matrix& H) const override;
493 void WhitenInPlace(Matrix& H) const override;
494 void WhitenInPlace(Eigen::Block<Matrix> H) const override;
495
505 Diagonal::shared_ptr QR(Matrix& Ab) const override;
506
511 shared_ptr unit() const;
512
513 private:
515 friend class boost::serialization::access;
516 template<class ARCHIVE>
517 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
518 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal);
519 ar & BOOST_SERIALIZATION_NVP(mu_);
520 }
521
522 }; // Constrained
523
524 //---------------------------------------------------------------------------------------
525
530 class GTSAM_EXPORT Isotropic : public Diagonal {
531 protected:
532 double sigma_, invsigma_;
533
535 Isotropic(size_t dim, double sigma) :
536 Diagonal(Vector::Constant(dim, sigma)),sigma_(sigma),invsigma_(1.0/sigma) {}
537
538 public:
539
540 /* dummy constructor to allow for serialization */
541 Isotropic() : Diagonal(Vector1::Constant(1.0)),sigma_(1.0),invsigma_(1.0) {}
542
543 ~Isotropic() override {}
544
545 typedef boost::shared_ptr<Isotropic> shared_ptr;
546
550 static shared_ptr Sigma(size_t dim, double sigma, bool smart = true);
551
558 static shared_ptr Variance(size_t dim, double variance, bool smart = true);
559
563 static shared_ptr Precision(size_t dim, double precision, bool smart = true) {
564 return Variance(dim, 1.0/precision, smart);
565 }
566
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;
575
579 inline double sigma() const { return sigma_; }
580
581 private:
583 friend class boost::serialization::access;
584 template<class ARCHIVE>
585 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
586 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal);
587 ar & BOOST_SERIALIZATION_NVP(sigma_);
588 ar & BOOST_SERIALIZATION_NVP(invsigma_);
589 }
590
591 };
592
593 //---------------------------------------------------------------------------------------
594
598 class GTSAM_EXPORT Unit : public Isotropic {
599 public:
600
601 typedef boost::shared_ptr<Unit> shared_ptr;
602
604 Unit(size_t dim=1): Isotropic(dim,1.0) {}
605
606 ~Unit() override {}
607
611 static shared_ptr Create(size_t dim) {
612 return shared_ptr(new Unit(dim));
613 }
614
616 bool isUnit() const override { return true; }
617
618 void print(const std::string& name) const override;
619 double squaredMahalanobisDistance(const Vector& v) const override {return v.dot(v); }
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; }
623 void WhitenInPlace(Matrix& /*H*/) const override {}
624 void WhitenInPlace(Eigen::Block<Matrix> /*H*/) const override {}
625 void whitenInPlace(Vector& /*v*/) const override {}
626 void unwhitenInPlace(Vector& /*v*/) const override {}
627 void whitenInPlace(Eigen::Block<Vector>& /*v*/) const override {}
628 void unwhitenInPlace(Eigen::Block<Vector>& /*v*/) const override {}
629
630 private:
632 friend class boost::serialization::access;
633 template<class ARCHIVE>
634 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
635 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Isotropic);
636 }
637 };
638
656 class GTSAM_EXPORT Robust : public Base {
657 public:
658 typedef boost::shared_ptr<Robust> shared_ptr;
659
660 protected:
663
664 const RobustModel::shared_ptr robust_;
665 const NoiseModel::shared_ptr noise_;
666
667 public:
668
670 Robust() {};
671
673 Robust(const RobustModel::shared_ptr robust, const NoiseModel::shared_ptr noise)
674 : Base(noise->dim()), robust_(robust), noise_(noise) {}
675
677 ~Robust() override {}
678
679 void print(const std::string& name) const override;
680 bool equals(const Base& expected, double tol=1e-9) const override;
681
683 const RobustModel::shared_ptr& robust() const { return robust_; }
684
686 const NoiseModel::shared_ptr& noise() const { return noise_; }
687
688 // Functions below are dummy but necessary for the noiseModel::Base
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& /*v*/) 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));
698 }
699
700 // These are really robust iterated re-weighting support functions
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;
706
707 Vector unweightedWhiten(const Vector& v) const override {
708 return noise_->unweightedWhiten(v);
709 }
710 double weight(const Vector& v) const override {
711 return robust_->weight(v.norm());
712 }
713
714 static shared_ptr Create(
715 const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise);
716
717 private:
719 friend class boost::serialization::access;
720 template<class ARCHIVE>
721 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
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_));
725 }
726 };
727
728 // Helper function
729 GTSAM_EXPORT boost::optional<Vector> checkIfDiagonal(const Matrix M);
730
731 } // namespace noiseModel
732
736 typedef noiseModel::Base::shared_ptr SharedNoiseModel;
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;
741
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> {};
748
749} //\ namespace gtsam
750
751
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