22 #include <boost/format.hpp> 23 #include <boost/make_shared.hpp> 34 namespace noiseModel {
42 template<
class MATRIX>
44 size_t n = Ab.cols()-1;
45 Ab.middleCols(j+1,n-j) -= a * rd.segment(j+1, n-j).transpose();
51 size_t m = M.rows(),
n = M.cols();
55 for (i = 0; i <
m; i++)
57 for (j = i + 1; j <
n; j++)
66 for (j = 0; j <
n; j++)
74 throw(
"Base::sigmas: sigmas() not implemented for this noise model");
78 double Base::squaredMahalanobisDistance(
const Vector&
v)
const {
86 size_t m = R.rows(),
n = R.cols();
88 throw invalid_argument(
"Gaussian::SqrtInformation: R not square");
92 return Diagonal::Sigmas(diagonal->array().inverse(),
true);
100 size_t m = information.rows(),
n = information.cols();
102 throw invalid_argument(
"Gaussian::Information: R not square");
103 boost::optional<Vector>
diagonal = boost::none;
107 return Diagonal::Precisions(*diagonal,
true);
118 size_t m = covariance.rows(),
n = covariance.cols();
120 throw invalid_argument(
"Gaussian::Covariance: covariance not square");
121 boost::optional<Vector> variances = boost::none;
125 return Diagonal::Variances(*variances,
true);
131 return Information(covariance.inverse(),
false);
143 if (p ==
nullptr)
return false;
144 if (
typeid(*
this) !=
typeid(*p))
return false;
152 Matrix I = Matrix::Identity(R.rows(), R.cols());
156 return Rinv * Rinv.transpose();
180 void Gaussian::WhitenInPlace(
Matrix&
H)
const {
193 gttic(Gaussian_noise_model_QR);
195 static const bool debug =
false;
199 size_t m = Ab.rows(),
n = Ab.cols()-1;
200 size_t maxRank =
min(m,
n);
215 return noiseModel::Unit::Create(maxRank);
218 void Gaussian::WhitenSystem(vector<Matrix>&
A,
Vector&
b)
const {
219 for(
Matrix& Aj: A) { WhitenInPlace(Aj); }
261 size_t n = variances.size();
262 for (
size_t j = 1;
j <
n;
j++)
263 if (variances(
j) != variances(0))
goto full;
272 size_t n = sigmas.size();
275 for (
size_t j=0;
j<
n; ++
j)
279 for (
size_t j = 1;
j <
n;
j++)
298 return v.cwiseProduct(
sigmas_);
370 assert (b.size()==a.size());
372 for(
size_t i = 0;
i <
n;
i++ ) {
373 const double&
ai =
a(
i), bi =
b(
i);
374 c(
i) = (bi==0.0) ? ai : ai/bi;
414 for (
size_t i=0;
i<
dim(); ++
i)
427 template <
typename VECTOR>
429 boost::optional<size_t> constraint_row;
432 double max_element = 1
e-9;
433 for (
size_t i = 0;
i <
m;
i++) {
437 if (abs_ai > max_element) {
438 max_element = abs_ai;
439 constraint_row.reset(i);
442 return constraint_row;
446 static const double kInfinity = std::numeric_limits<double>::infinity();
449 size_t m = Ab.rows();
450 const size_t n = Ab.cols() - 1;
451 const size_t maxRank =
min(m, n);
454 typedef boost::tuple<size_t, Matrix, double> Triple;
459 Vector weights = invsigmas.array().square();
465 for (
size_t j = 0;
j <
n; ++
j) {
472 if (constraint_row) {
477 rd = Ab.row(*constraint_row);
483 if (Rd.size() >= maxRank)
489 if (*constraint_row != m) {
490 Ab.row(*constraint_row) = Ab.row(m);
491 weights(*constraint_row) = weights(m);
497 a_reduced *= (1.0/rd(0,
j));
500 Ab.block(0,
j + 1, m, n -
j).noalias() -= a_reduced * rd.middleCols(
j + 1, n -
j);
509 for (
size_t i = 0;
i <
m;
i++) {
512 pseudo[
i] = weights[
i] *
ai;
513 precision += pseudo[
i] *
ai;
518 if (precision > 1
e-8) {
523 rd.block(0,
j + 1, 1, n -
j) = pseudo.transpose() * Ab.block(0,
j + 1, m, n -
j);
535 if (Rd.size() >= maxRank)
539 Ab.block(0,
j + 1, m, n -
j).noalias() -= a * rd.middleCols(
j + 1, n -
j);
550 for (
const Triple&
t: Rd) {
551 const size_t&
j =
t.get<0>();
556 Ab.block(i, j, 1, n + 1 - j) = rd.block(0, j, 1, n + 1 - j);
580 cout << boost::format(
"isotropic dim=%1% sigma=%2%") %
dim() % sigma_ << endl;
585 return v.dot(v) * invsigma_ * invsigma_;
590 return v * invsigma_;
600 return invsigma_ *
H;
622 cout << name <<
"unit (" <<
dim_ <<
") " << endl;
630 robust_->print(name);
636 if (p ==
nullptr)
return false;
641 noise_->whitenInPlace(b);
642 robust_->reweight(b);
646 noise_->WhitenSystem(A,b);
647 robust_->reweight(A,b);
651 noise_->WhitenSystem(A,b);
652 robust_->reweight(A,b);
656 noise_->WhitenSystem(A1,A2,b);
657 robust_->reweight(A1,A2,b);
661 noise_->WhitenSystem(A1,A2,A3,b);
662 robust_->reweight(A1,A2,A3,b);
void print(const Matrix &A, const string &s, ostream &stream)
void inplace_QR(Matrix &A)
Vector mu_
Penalty function weight - needs to be large enough to dominate soft constraints.
void print(const std::string &name) const override
Constrained(const Vector &sigmas=Z_1x1)
Matrix< RealScalar, Dynamic, Dynamic > M
const mpreal ai(const mpreal &x, mp_rnd_t r=mpreal::get_default_rnd())
void print(const std::string &name) const override
boost::shared_ptr< Robust > shared_ptr
void updateAb(MATRIX &Ab, int j, const Vector &a, const Vector &rd)
Traits::MatrixU matrixU() const
void vector_scale_inplace(const Vector &v, Matrix &A, bool inf_mask)
double squaredMahalanobisDistance(const Vector &v) const override
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
void diagonal(const MatrixType &m)
Rot2 R(Rot2::fromAngle(0.1))
Vector whiten(const Vector &v) const override
Calculates error vector with weights applied.
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
virtual Matrix R() const
Return R itself, but note that Whiten(H) is cheaper than R*H.
Matrix Whiten(const Matrix &H) const override
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
void WhitenInPlace(Matrix &H) const override
static shared_ptr Precisions(const Vector &precisions, bool smart=true)
static shared_ptr Create(const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise)
ptrdiff_t DenseIndex
The index type for Eigen objects.
Matrix vector_scale(const Vector &v, const Matrix &A, bool inf_mask)
static shared_ptr Create(size_t dim)
void WhitenInPlace(Matrix &H) const override
double squaredMahalanobisDistance(const Vector &v) const override
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
static shared_ptr Variance(size_t dim, double variance, bool smart=true)
void WhitenInPlace(Matrix &H) const override
static shared_ptr MixedSigmas(const Vector &mu, const Vector &sigmas)
const RobustModel::shared_ptr robust_
robust error function used
Tuple< Args... > make_tuple(Args...args)
Creates a tuple object, deducing the target type from the types of arguments.
void whitenInPlace(Vector &v) const override
boost::optional< size_t > check_if_constraint(VECTOR a, const Vector &invsigmas, size_t m)
static shared_ptr MixedPrecisions(const Vector &mu, const Vector &precisions)
Vector sigmas() const override
Calculate standard deviations.
const NoiseModel::shared_ptr noise_
noise model used
Standard Cholesky decomposition (LL^T) of a matrix and associated features.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::shared_ptr< Base > shared_ptr
Vector unwhiten(const Vector &v) const override
Unwhiten an error vector.
boost::shared_ptr< Diagonal > shared_ptr
Vector whiten(const Vector &v) const override
Whiten an error vector.
boost::shared_ptr< Constrained > shared_ptr
void print(const std::string &name) const override
boost::shared_ptr< Base > shared_ptr
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
noiseModel::Diagonal::shared_ptr SharedDiagonal
virtual void WhitenSystem(Vector &b) const
double sigma(size_t i) const
Matrix Whiten(const Matrix &H) const override
Matrix Whiten(const Matrix &H) const override
bool constrained(size_t i) const
Return true if a particular dimension is free or constrained.
size_t dim() const
Dimensionality.
Expression of a fixed-size or dynamic-size block.
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
void print(const std::string &name) const override
boost::optional< Vector > checkIfDiagonal(const Matrix M)
Vector backSubstituteUpper(const Matrix &U, const Vector &b, bool unit)
Diagonal::shared_ptr QR(Matrix &Ab) const override
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
const Vector & precisions() const
boost::shared_ptr< Isotropic > shared_ptr
bool equals(const Base &expected, double tol=1e-9) const override
boost::shared_ptr< Gaussian > shared_ptr
const Vector & mu() const
Access mu as a vector.
Annotation for function names.
const Vector & invsigmas() const
void print(const std::string &name) const override
double precision(size_t i) const
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Vector unwhiten(const Vector &v) const override
Unwhiten an error vector.
static shared_ptr Variances(const Vector &variances, bool smart=true)
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
Vector whiten(const Vector &v) const override
Whiten an error vector.
static void fix(const Vector &sigmas, Vector &precisions, Vector &invsigmas)
EIGEN_DEVICE_FUNC const SquareReturnType square() const
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)