23 #include <gtsam/dllexport.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 {
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;
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;
141 friend class boost::serialization::access;
142 template<
class ARCHIVE>
144 ar & BOOST_SERIALIZATION_NVP(dim_);
176 if (!sqrt_information_)
throw std::runtime_error(
"Gaussian: has no R matrix");
177 return *sqrt_information_;
183 Gaussian(
size_t dim = 1,
const boost::optional<Matrix>& sqrt_information = boost::none) :
184 Base(
dim), sqrt_information_(sqrt_information) {
198 static shared_ptr SqrtInformation(
const Matrix&
R,
bool smart =
true);
205 static shared_ptr Information(
const Matrix&
M,
bool smart =
true);
212 static shared_ptr Covariance(
const Matrix& covariance,
bool smart =
true);
214 void print(
const std::string&
name)
const override;
229 virtual void WhitenInPlace(
Matrix& H)
const;
239 void WhitenSystem(std::vector<Matrix>&
A,
Vector&
b)
const override;
253 virtual boost::shared_ptr<Diagonal> QR(
Matrix&
Ab)
const;
262 virtual Matrix covariance()
const;
266 friend class boost::serialization::access;
267 template<
class ARCHIVE>
269 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
270 ar & BOOST_SERIALIZATION_NVP(sqrt_information_);
309 static shared_ptr Sigmas(
const Vector&
sigmas,
bool smart =
true);
317 static shared_ptr Variances(
const Vector& variances,
bool smart =
true);
324 return Variances(precisions.array().inverse(), smart);
327 void print(
const std::string&
name)
const override;
332 void WhitenInPlace(
Matrix& H)
const override;
338 inline double sigma(
size_t i)
const {
return sigmas_(i); }
344 inline double invsigma(
size_t i)
const {
return invsigmas_(i);}
350 inline double precision(
size_t i)
const {
return precisions_(i);}
356 return invsigmas().asDiagonal();
361 friend class boost::serialization::access;
362 template<
class ARCHIVE>
364 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Gaussian);
365 ar & BOOST_SERIALIZATION_NVP(sigmas_);
366 ar & BOOST_SERIALIZATION_NVP(invsigmas_);
415 bool constrained(
size_t i)
const;
431 return MixedSigmas(Vector::Constant(sigmas.size(), 1000.0),
sigmas);
439 return MixedSigmas(Vector::Constant(sigmas.size(),
m), sigmas);
447 return shared_ptr(
new Constrained(mu, variances.cwiseSqrt()));
450 return shared_ptr(
new Constrained(variances.cwiseSqrt()));
458 return MixedVariances(mu, precisions.array().inverse());
461 return MixedVariances(precisions.array().inverse());
464 double squaredMahalanobisDistance(
const Vector&
v)
const override;
468 return shared_ptr(
new Constrained(Vector::Constant(dim, 1000.0), Vector::Constant(dim,0)));
473 return shared_ptr(
new Constrained(mu, Vector::Constant(dim,0)));
477 static shared_ptr
All(
size_t dim,
double mu) {
478 return shared_ptr(
new Constrained(Vector::Constant(dim, mu), Vector::Constant(dim,0)));
481 void print(
const std::string&
name)
const override;
489 void WhitenInPlace(
Matrix& H)
const override;
507 shared_ptr unit()
const;
511 friend class boost::serialization::access;
512 template<
class ARCHIVE>
514 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Diagonal);
515 ar & BOOST_SERIALIZATION_NVP(mu_);
532 Diagonal(
Vector::Constant(dim, sigma)),sigma_(sigma),invsigma_(1.0/sigma) {}
546 static shared_ptr Sigma(
size_t dim,
double sigma,
bool smart =
true);
554 static shared_ptr Variance(
size_t dim,
double variance,
bool smart =
true);
560 return Variance(dim, 1.0/precision, smart);
563 void print(
const std::string&
name)
const override;
564 double squaredMahalanobisDistance(
const Vector&
v)
const override;
568 void WhitenInPlace(
Matrix& H)
const override;
569 void whitenInPlace(
Vector& v)
const override;
575 inline double sigma()
const {
return sigma_; }
579 friend class boost::serialization::access;
580 template<
class ARCHIVE>
582 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Diagonal);
583 ar & BOOST_SERIALIZATION_NVP(sigma_);
584 ar & BOOST_SERIALIZATION_NVP(invsigma_);
609 return shared_ptr(
new Unit(dim));
613 bool isUnit()
const override {
return true; }
615 void print(
const std::string&
name)
const override;
629 friend class boost::serialization::access;
630 template<
class ARCHIVE>
632 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Isotropic);
671 :
Base(noise->
dim()), robust_(robust), noise_(noise) {}
676 void print(
const std::string&
name)
const override;
687 {
Vector r =
v; this->WhitenSystem(r);
return r; }
691 {
throw std::invalid_argument(
"unwhiten is not currently supported for robust noise models."); }
693 double loss(
const double squared_distance)
const override {
694 return robust_->loss(
std::sqrt(squared_distance));
698 virtual void WhitenSystem(
Vector&
b)
const;
699 void WhitenSystem(std::vector<Matrix>&
A,
Vector& b)
const override;
705 return noise_->unweightedWhiten(v);
709 return robust_->weight(v.norm());
712 static shared_ptr Create(
717 friend class boost::serialization::access;
718 template<
class ARCHIVE>
720 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
721 ar & boost::serialization::make_nvp(
"robust_", const_cast<RobustModel::shared_ptr&>(robust_));
722 ar & boost::serialization::make_nvp(
"noise_", const_cast<NoiseModel::shared_ptr&>(noise_));
741 template<>
struct traits<noiseModel::Gaussian> :
public Testable<noiseModel::Gaussian> {};
743 template<>
struct traits<noiseModel::Constrained> :
public Testable<noiseModel::Constrained> {};
744 template<>
struct traits<noiseModel::Isotropic> :
public Testable<noiseModel::Isotropic> {};
745 template<>
struct traits<noiseModel::Unit> :
public Testable<noiseModel::Unit> {};
void print(const Matrix &A, const string &s, ostream &stream)
Vector unweightedWhiten(const Vector &v) const override
Matrix Whiten(const Matrix &H) const override
static shared_ptr All(size_t dim, const Vector &mu)
Vector mu_
Penalty function weight - needs to be large enough to dominate soft constraints.
boost::shared_ptr< Unit > shared_ptr
Matrix< RealScalar, Dynamic, Dynamic > M
void serialize(ARCHIVE &ar, const unsigned int)
static shared_ptr MixedSigmas(const Vector &sigmas)
Concept check for values that can be used in unit tests.
void serialize(ARCHIVE &ar, const unsigned int)
void serialize(ARCHIVE &ar, const unsigned int)
const RobustModel::shared_ptr & robust() const
Return the contained robust error function.
virtual double weight(const Vector &v) const
boost::shared_ptr< Robust > shared_ptr
static shared_ptr MixedPrecisions(const Vector &precisions)
static const double sigma
Rot2 R(Rot2::fromAngle(0.1))
void unwhitenInPlace(Eigen::Block< Vector > &) const override
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
virtual Matrix R() const
Return R itself, but note that Whiten(H) is cheaper than R*H.
noiseModel::Isotropic::shared_ptr SharedIsotropic
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
virtual void whitenInPlace(Eigen::Block< Vector > &v) const
void serialize(ARCHIVE &ar, const unsigned int)
static shared_ptr Precisions(const Vector &precisions, bool smart=true)
void WhitenInPlace(Eigen::Block< Matrix >) const override
double invsigma(size_t i) const
static shared_ptr Create(size_t dim)
bool isConstrained() const override
true if a constrained noise mode, saves slow/clumsy dynamic casting
const Matrix & thisR() const
static shared_ptr All(size_t dim, double mu)
virtual bool isConstrained() const
true if a constrained noise model, saves slow/clumsy dynamic casting
const RobustModel::shared_ptr robust_
robust error function used
Vector whiten(const Vector &v) const override
Whiten an error vector.
Robust()
Default Constructor for serialization.
mEstimator::Base RobustModel
static shared_ptr MixedPrecisions(const Vector &mu, const Vector &precisions)
Vector sigmas() const override
Calculate standard deviations.
virtual void unwhitenInPlace(Vector &v) const
static shared_ptr MixedVariances(const Vector &mu, const Vector &variances)
boost::optional< Matrix > sqrt_information_
void serialize(ARCHIVE &ar, const unsigned int)
const NoiseModel::shared_ptr noise_
noise model used
void WhitenInPlace(Matrix &) const override
void serialize(ARCHIVE &ar, const unsigned int)
void unwhitenInPlace(Vector &) const override
virtual double loss(const double squared_distance) const
loss function, input is Mahalanobis distance
double weight(const Vector &v) const override
double loss(const double squared_distance) const override
loss function, input is Mahalanobis distance
Array< double, 1, 3 > e(1./3., 0.5, 2.)
~Robust() override
Destructor.
boost::shared_ptr< Base > shared_ptr
virtual Matrix information() const
Compute information matrix.
boost::shared_ptr< Diagonal > shared_ptr
boost::shared_ptr< Constrained > shared_ptr
void whitenInPlace(Eigen::Block< Vector > &) const override
virtual void unwhitenInPlace(Eigen::Block< Vector > &v) const
boost::shared_ptr< Base > shared_ptr
Base(size_t dim=1)
primary constructor
Vector whiten(const Vector &v) const override
Whiten an error vector.
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
noiseModel::Diagonal::shared_ptr SharedDiagonal
noiseModel::Constrained::shared_ptr SharedConstrained
double sigma(size_t i) const
void serialize(ARCHIVE &ar, const unsigned int)
size_t dim() const
Dimensionality.
Expression of a fixed-size or dynamic-size block.
noiseModel::Base NoiseModel
boost::optional< Vector > checkIfDiagonal(const Matrix M)
Gaussian(size_t dim=1, const boost::optional< Matrix > &sqrt_information=boost::none)
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
const Vector & precisions() const
Matrix R() const override
boost::shared_ptr< Isotropic > shared_ptr
boost::shared_ptr< Gaussian > shared_ptr
const Vector & mu() const
Access mu as a vector.
Annotation for function names.
virtual bool isUnit() const
true if a unit noise model, saves slow/clumsy dynamic casting
Robust(const RobustModel::shared_ptr robust, const NoiseModel::shared_ptr noise)
Constructor.
const Vector & invsigmas() const
void whitenInPlace(Vector &) const override
The matrix class, also used for vectors and row-vectors.
Vector unwhiten(const Vector &) const override
Unwhiten an error vector.
Vector unwhiten(const Vector &v) const override
Unwhiten an error vector.
virtual double mahalanobisDistance(const Vector &v) const
Mahalanobis distance.
static shared_ptr MixedVariances(const Vector &variances)
double squaredMahalanobisDistance(const Vector &v) const override
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
double precision(size_t i) const
static shared_ptr Precision(size_t dim, double precision, bool smart=true)
const NoiseModel::shared_ptr & noise() const
Return the contained noise model.
Matrix Whiten(const Matrix &A) const override
Whiten a matrix.
static shared_ptr MixedSigmas(double m, const Vector &sigmas)
virtual void whitenInPlace(Vector &v) const
noiseModel::Gaussian::shared_ptr SharedGaussian
noiseModel::Base::shared_ptr SharedNoiseModel
virtual Vector unweightedWhiten(const Vector &v) const
Isotropic(size_t dim, double sigma)
static shared_ptr All(size_t dim)
bool isUnit() const override
true if a unit noise model, saves slow/clumsy dynamic casting