NoiseModel.cpp
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 
20 #include <gtsam/base/timing.h>
21 
22 #include <cmath>
23 #include <cassert>
24 #include <iostream>
25 #include <limits>
26 #include <stdexcept>
27 #include <typeinfo>
28 
29 using namespace std;
30 
31 namespace gtsam {
32 namespace noiseModel {
33 
34 /* ************************************************************************* */
35 // update A, b
36 // A' \define A_{S}-ar and b'\define b-ad
37 // Linear algebra: takes away projection on latest orthogonal
38 // Graph: make a new factor on the separator S
39 // __attribute__ ((noinline)) // uncomment to prevent inlining when profiling
40 template<class MATRIX>
41 void updateAb(MATRIX& Ab, int j, const Vector& a, const Vector& rd) {
42  size_t n = Ab.cols()-1;
43  Ab.middleCols(j+1,n-j) -= a * rd.segment(j+1, n-j).transpose();
44 }
45 
46 /* ************************************************************************* */
47 // check *above the diagonal* for non-zero entries
48 std::optional<Vector> checkIfDiagonal(const Matrix& M) {
49  size_t m = M.rows(), n = M.cols();
50  assert(m > 0);
51  // check all non-diagonal entries
52  bool full = false;
53  size_t i, j;
54  for (i = 0; i < m; i++)
55  if (!full)
56  for (j = i + 1; j < n; j++)
57  if (std::abs(M(i, j)) > 1e-9) {
58  full = true;
59  break;
60  }
61  if (full) {
62  return {};
63  } else {
64  Vector diagonal(n);
65  for (j = 0; j < n; j++)
66  diagonal(j) = M(j, j);
67  return diagonal;
68  }
69 }
70 
71 /* ************************************************************************* */
73  throw("Base::sigmas: sigmas() not implemented for this noise model");
74 }
75 
76 /* ************************************************************************* */
77 double Base::squaredMahalanobisDistance(const Vector& v) const {
78  // Note: for Diagonal, which does ediv_, will be correct for constraints
79  Vector w = whiten(v);
80  return w.dot(w);
81 }
82 
83 /* ************************************************************************* */
84 Gaussian::shared_ptr Gaussian::SqrtInformation(const Matrix& R, bool smart) {
85  size_t m = R.rows(), n = R.cols();
86  if (m != n)
87  throw invalid_argument("Gaussian::SqrtInformation: R not square");
88  if (smart) {
89  std::optional<Vector> diagonal = checkIfDiagonal(R);
90  if (diagonal)
91  return Diagonal::Sigmas(diagonal->array().inverse(), true);
92  }
93  // NOTE(frank): only reaches here if !(smart && diagonal)
94  return std::make_shared<Gaussian>(R.rows(), R);
95 }
96 
97 /* ************************************************************************* */
98 Gaussian::shared_ptr Gaussian::Information(const Matrix& information, bool smart) {
99  size_t m = information.rows(), n = information.cols();
100  if (m != n)
101  throw invalid_argument("Gaussian::Information: R not square");
102  std::optional<Vector> diagonal = {};
103  if (smart)
104  diagonal = checkIfDiagonal(information);
105  if (diagonal)
106  return Diagonal::Precisions(*diagonal, true);
107  else {
108  Eigen::LLT<Matrix> llt(information);
109  Matrix R = llt.matrixU();
110  return std::make_shared<Gaussian>(n, R);
111  }
112 }
113 
114 /* ************************************************************************* */
115 Gaussian::shared_ptr Gaussian::Covariance(const Matrix& covariance,
116  bool smart) {
117  size_t m = covariance.rows(), n = covariance.cols();
118  if (m != n)
119  throw invalid_argument("Gaussian::Covariance: covariance not square");
120  std::optional<Vector> variances = {};
121  if (smart)
122  variances = checkIfDiagonal(covariance);
123  if (variances)
124  return Diagonal::Variances(*variances, true);
125  else {
126  // NOTE: if cov = L'*L, then the square root information R can be found by
127  // QR, as L.inverse() = Q*R, with Q some rotation matrix. However, R has
128  // annoying sign flips with respect the simpler Information(inv(cov)),
129  // hence we choose the simpler path here:
130  return Information(covariance.inverse(), false);
131  }
132 }
133 
134 /* ************************************************************************* */
135 void Gaussian::print(const string& name) const {
136  gtsam::print(thisR(), name + "Gaussian ");
137 }
138 
139 /* ************************************************************************* */
140 bool Gaussian::equals(const Base& expected, double tol) const {
141  const Gaussian* p = dynamic_cast<const Gaussian*> (&expected);
142  if (p == nullptr) return false;
143  if (typeid(*this) != typeid(*p)) return false;
144  return equal_with_abs_tol(R(), p->R(), sqrt(tol));
145 }
146 
147 /* ************************************************************************* */
148 Matrix Gaussian::covariance() const {
149  // Uses a fast version of `covariance = information().inverse();`
150  const Matrix& R = this->R();
151  Matrix I = Matrix::Identity(R.rows(), R.cols());
152  // Fast inverse of upper-triangular matrix R using forward-substitution
153  Matrix Rinv = R.triangularView<Eigen::Upper>().solve(I);
154  // (R' * R)^{-1} = R^{-1} * R^{-1}'
155  return Rinv * Rinv.transpose();
156 }
157 
158 /* ************************************************************************* */
160  return Vector(covariance().diagonal()).cwiseSqrt();
161 }
162 
163 /* ************************************************************************* */
164 Vector Gaussian::whiten(const Vector& v) const {
165  return thisR() * v;
166 }
167 
168 /* ************************************************************************* */
169 Vector Gaussian::unwhiten(const Vector& v) const {
170  return backSubstituteUpper(thisR(), v);
171 }
172 
173 /* ************************************************************************* */
174 Matrix Gaussian::Whiten(const Matrix& H) const {
175  return thisR() * H;
176 }
177 
178 /* ************************************************************************* */
179 void Gaussian::WhitenInPlace(Matrix& H) const {
180  H = thisR() * H;
181 }
182 
183 /* ************************************************************************* */
184 void Gaussian::WhitenInPlace(Eigen::Block<Matrix> H) const {
185  H = thisR() * H;
186 }
187 
188 /* ************************************************************************* */
189 // General QR, see also special version in Constrained
190 SharedDiagonal Gaussian::QR(Matrix& Ab) const {
191 
192  gttic(Gaussian_noise_model_QR);
193 
194  // get size(A) and maxRank
195  // TODO: really no rank problems ?
196  size_t m = Ab.rows(), n = Ab.cols()-1;
197  size_t maxRank = min(m,n);
198 
199  // pre-whiten everything (cheaply if possible)
200  WhitenInPlace(Ab);
201 
202  // Eigen QR - much faster than older householder approach
203  inplace_QR(Ab);
204 
205  return noiseModel::Unit::Create(maxRank);
206 }
207 
208 void Gaussian::WhitenSystem(vector<Matrix>& A, Vector& b) const {
209  for(Matrix& Aj: A) { WhitenInPlace(Aj); }
210  whitenInPlace(b);
211 }
212 
213 void Gaussian::WhitenSystem(Matrix& A, Vector& b) const {
214  WhitenInPlace(A);
215  whitenInPlace(b);
216 }
217 
218 void Gaussian::WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const {
219  WhitenInPlace(A1);
220  WhitenInPlace(A2);
221  whitenInPlace(b);
222 }
223 
224 void Gaussian::WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const{
225  WhitenInPlace(A1);
226  WhitenInPlace(A2);
227  WhitenInPlace(A3);
228  whitenInPlace(b);
229 }
230 
231 Matrix Gaussian::information() const { return R().transpose() * R(); }
232 
233 /* *******************************************************************************/
234 double Gaussian::logDetR() const {
235  double logDetR =
236  R().diagonal().unaryExpr([](double x) { return log(x); }).sum();
237  return logDetR;
238 }
239 
240 /* *******************************************************************************/
241 double Gaussian::logDeterminant() const {
242  // Since noise models are Gaussian, we can get the logDeterminant easily
243  // Sigma = (R'R)^{-1}, det(Sigma) = det((R'R)^{-1}) = det(R'R)^{-1}
244  // log det(Sigma) = -log(det(R'R)) = -2*log(det(R))
245  // Hence, log det(Sigma)) = -2.0 * logDetR()
246  return -2.0 * logDetR();
247 }
248 
249 /* *******************************************************************************/
250 double Gaussian::negLogConstant() const {
251  // log(det(Sigma)) = -2.0 * logDetR
252  // which gives neg-log = 0.5*n*log(2*pi) + 0.5*(-2.0 * logDetR())
253  // = 0.5*n*log(2*pi) - (0.5*2.0 * logDetR())
254  // = 0.5*n*log(2*pi) - logDetR()
255  size_t n = dim();
256  constexpr double log2pi = 1.8378770664093454835606594728112;
257  // Get -log(1/\sqrt(|2pi Sigma|)) = 0.5*log(|2pi Sigma|)
258  return 0.5 * n * log2pi - logDetR();
259 }
260 
261 /* ************************************************************************* */
262 // Diagonal
263 /* ************************************************************************* */
265 
266 /* ************************************************************************* */
268  : Gaussian(sigmas.size()),
269  sigmas_(sigmas),
270  invsigmas_(sigmas.array().inverse()),
271  precisions_(invsigmas_.array().square()) {
272 }
273 
274 /* ************************************************************************* */
275 Diagonal::shared_ptr Diagonal::Variances(const Vector& variances, bool smart) {
276  // check whether all the same entry
277  return (smart && (variances.array() == variances(0)).all())
278  ? Isotropic::Variance(variances.size(), variances(0), true)
279  : shared_ptr(new Diagonal(variances.cwiseSqrt()));
280 }
281 
282 /* ************************************************************************* */
284  if (smart) {
285  size_t n = sigmas.size();
286  if (n == 0) goto full;
287 
288  // look for zeros to make a constraint
289  if ((sigmas.array() < 1e-8).any()) {
291  }
292 
293  // check whether all the same entry
294  if ((sigmas.array() == sigmas(0)).all()) {
295  return Isotropic::Sigma(n, sigmas(0), true);
296  }
297  }
298 full:
299  return Diagonal::shared_ptr(new Diagonal(sigmas));
300 }
301 
302 /* ************************************************************************* */
304  bool smart) {
305  return Variances(precisions.array().inverse(), smart);
306 }
307 
308 /* ************************************************************************* */
309 void Diagonal::print(const string& name) const {
310  gtsam::print(sigmas_, name + "diagonal sigmas ");
311 }
312 
313 /* ************************************************************************* */
315  return v.cwiseProduct(invsigmas_);
316 }
317 
319  return v.cwiseProduct(sigmas_);
320 }
321 
323  return vector_scale(invsigmas(), H);
324 }
325 
328 }
329 
331  H = invsigmas().asDiagonal() * H;
332 }
333 
334 /* *******************************************************************************/
335 double Diagonal::logDetR() const {
336  return invsigmas_.unaryExpr([](double x) { return log(x); }).sum();
337 }
338 
339 /* ************************************************************************* */
340 // Constrained
341 /* ************************************************************************* */
342 
343 namespace internal {
344 // switch precisions and invsigmas to finite value
345 // TODO: why?? And, why not just ask s==0.0 below ?
346 static void fix(const Vector& sigmas, Vector& precisions, Vector& invsigmas) {
347  for (Vector::Index i = 0; i < sigmas.size(); ++i)
348  if (!std::isfinite(1. / sigmas[i])) {
349  precisions[i] = 0.0;
350  invsigmas[i] = 0.0;
351  }
352 }
353 }
354 
355 /* ************************************************************************* */
357  : Diagonal(sigmas), mu_(Vector::Constant(sigmas.size(), 1000.0)) {
359 }
360 
361 /* ************************************************************************* */
363  : Diagonal(sigmas), mu_(mu) {
365 }
366 
367 /* ************************************************************************* */
369  const Vector& sigmas) {
370  return shared_ptr(new Constrained(mu, sigmas));
371 }
372 
373 /* ************************************************************************* */
374 bool Constrained::constrained(size_t i) const {
375  // TODO why not just check sigmas_[i]==0.0 ?
376  return !std::isfinite(1./sigmas_[i]);
377 }
378 
379 /* ************************************************************************* */
380 void Constrained::print(const std::string& name) const {
381  gtsam::print(sigmas_, name + "constrained sigmas ");
382  gtsam::print(mu_, name + "constrained mu ");
383 }
384 
385 /* ************************************************************************* */
387  // If sigmas[i] is not 0 then divide v[i] by sigmas[i], as usually done in
388  // other normal Gaussian noise model. Otherwise, sigmas[i] = 0 indicating
389  // a hard constraint, we don't do anything.
390  const Vector& a = v;
391  const Vector& b = sigmas_;
392  size_t n = a.size();
393  assert (b.size()==a.size());
394  Vector c(n);
395  for( size_t i = 0; i < n; i++ ) {
396  const double& ai = a(i), bi = b(i);
397  c(i) = (bi==0.0) ? ai : ai/bi; // NOTE: not ediv_()
398  }
399  return c;
400 }
401 
402 /* ************************************************************************* */
404  return MixedSigmas(Vector::Constant(sigmas.size(), 1000.0), sigmas);
405 }
406 
408  const Vector& sigmas) {
409  return MixedSigmas(Vector::Constant(sigmas.size(), m), sigmas);
410 }
411 
413  const Vector& variances) {
414  return shared_ptr(new Constrained(mu, variances.cwiseSqrt()));
415 }
417  return shared_ptr(new Constrained(variances.cwiseSqrt()));
418 }
419 
421  const Vector& precisions) {
422  return MixedVariances(mu, precisions.array().inverse());
423 }
425  return MixedVariances(precisions.array().inverse());
426 }
427 
428 /* ************************************************************************* */
430  Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements
431  for (size_t i=0; i<dim_; ++i) // add mu weights on constrained variables
432  if (constrained(i)) // whiten makes constrained variables zero
433  w[i] = v[i] * sqrt(mu_[i]); // TODO: may want to store sqrt rather than rebuild
434  return w.dot(w);
435 }
436 
437 /* ************************************************************************* */
439  Matrix A = H;
440  for (DenseIndex i=0; i<(DenseIndex)dim_; ++i)
441  if (!constrained(i)) // if constrained, leave row of A as is
442  A.row(i) *= invsigmas_(i);
443  return A;
444 }
445 
446 /* ************************************************************************* */
448  for (DenseIndex i=0; i<(DenseIndex)dim_; ++i)
449  if (!constrained(i)) // if constrained, leave row of H as is
450  H.row(i) *= invsigmas_(i);
451 }
452 
453 /* ************************************************************************* */
455  for (DenseIndex i=0; i<(DenseIndex)dim_; ++i)
456  if (!constrained(i)) // if constrained, leave row of H as is
457  H.row(i) *= invsigmas_(i);
458 }
459 
460 /* ************************************************************************* */
462  Vector sigmas = Vector::Ones(dim());
463  for (size_t i=0; i<dim(); ++i)
464  if (constrained(i))
465  sigmas(i) = 0.0;
466  return MixedSigmas(mu_, sigmas);
467 }
468 
469 /* ************************************************************************* */
470 // Special version of QR for Constrained calls slower but smarter code
471 // that deals with possibly zero sigmas
472 // It is Gram-Schmidt orthogonalization rather than Householder
473 
474 // Check whether column a triggers a constraint and corresponding variable is deterministic
475 // Return constraint_row with maximum element in case variable plays in multiple constraints
476 template <typename VECTOR>
477 std::optional<size_t> check_if_constraint(VECTOR a, const Vector& invsigmas, size_t m) {
478  std::optional<size_t> constraint_row;
479  // not zero, so roundoff errors will not be counted
480  // TODO(frank): that's a fairly crude way of dealing with roundoff errors :-(
481  double max_element = 1e-9;
482  for (size_t i = 0; i < m; i++) {
483  if (!std::isinf(invsigmas[i]))
484  continue;
485  double abs_ai = std::abs(a(i,0));
486  if (abs_ai > max_element) {
487  max_element = abs_ai;
488  constraint_row = i;
489  }
490  }
491  return constraint_row;
492 }
493 
495  static const double kInfinity = std::numeric_limits<double>::infinity();
496 
497  // get size(A) and maxRank
498  size_t m = Ab.rows();
499  const size_t n = Ab.cols() - 1;
500  const size_t maxRank = min(m, n);
501 
502  // create storage for [R d]
503  typedef std::tuple<size_t, Matrix, double> Triple;
504  list<Triple> Rd;
505 
506  Matrix rd(1, n + 1); // and for row of R
507  Vector invsigmas = sigmas_.array().inverse();
508  Vector weights = invsigmas.array().square(); // calculate weights once
509 
510  // We loop over all columns, because the columns that can be eliminated
511  // are not necessarily contiguous. For each one, estimate the corresponding
512  // scalar variable x as d-rS, with S the separator (remaining columns).
513  // Then update A and b by substituting x with d-rS, zero-ing out x's column.
514  for (size_t j = 0; j < n; ++j) {
515  // extract the first column of A
516  Eigen::Block<Matrix> a = Ab.block(0, j, m, 1);
517 
518  // Check whether we need to handle as a constraint
519  std::optional<size_t> constraint_row = check_if_constraint(a, invsigmas, m);
520 
521  if (constraint_row) {
522  // Handle this as a constraint, as the i^th row has zero sigma with non-zero entry A(i,j)
523 
524  // In this case, the row in [R|d] is simply the row in [A|b]
525  // NOTE(frank): we used to divide by a[i] but there is no need with a constraint
526  rd = Ab.row(*constraint_row);
527 
528  // Construct solution (r, d, sigma)
529  Rd.push_back(std::make_tuple(j, rd, kInfinity));
530 
531  // exit after rank exhausted
532  if (Rd.size() >= maxRank)
533  break;
534 
535  // The constraint row will be zeroed out, so we can save work by swapping in the
536  // last valid row and decreasing m. This will save work on subsequent down-dates, too.
537  m -= 1;
538  if (*constraint_row != m) {
539  Ab.row(*constraint_row) = Ab.row(m);
540  weights(*constraint_row) = weights(m);
541  invsigmas(*constraint_row) = invsigmas(m);
542  }
543 
544  // get a reduced a-column which is now shorter
545  Eigen::Block<Matrix> a_reduced = Ab.block(0, j, m, 1);
546  a_reduced *= (1.0/rd(0, j)); // NOTE(frank): this is the 1/a[i] = 1/rd(0,j) factor we need!
547 
548  // Rank-1 down-date of Ab, expensive, using outer product
549  Ab.block(0, j + 1, m, n - j).noalias() -= a_reduced * rd.middleCols(j + 1, n - j);
550  } else {
551  // Treat in normal Gram-Schmidt way
552  // Calculate weighted pseudo-inverse and corresponding precision
553 
554  // Form psuedo-inverse inv(a'inv(Sigma)a)a'inv(Sigma)
555  // For diagonal Sigma, inv(Sigma) = diag(precisions)
556  double precision = 0;
557  Vector pseudo(m); // allocate storage for pseudo-inverse
558  for (size_t i = 0; i < m; i++) {
559  double ai = a(i, 0);
560  if (std::abs(ai) > 1e-9) { // also catches remaining sigma==0 rows
561  pseudo[i] = weights[i] * ai;
562  precision += pseudo[i] * ai;
563  } else
564  pseudo[i] = 0;
565  }
566 
567  if (precision > 1e-8) {
568  pseudo /= precision;
569 
570  // create solution [r d], rhs is automatically r(n)
571  rd(0, j) = 1.0; // put 1 on diagonal
572  rd.block(0, j + 1, 1, n - j) = pseudo.transpose() * Ab.block(0, j + 1, m, n - j);
573 
574  // construct solution (r, d, sigma)
575  Rd.push_back(std::make_tuple(j, rd, precision));
576  } else {
577  // If precision is zero, no information on this column
578  // This is actually not limited to constraints, could happen in Gaussian::QR
579  // In that case, we're probably hosed. TODO: make sure Householder is rank-revealing
580  continue; // but even if not, no need to update if a==zeros
581  }
582 
583  // exit after rank exhausted
584  if (Rd.size() >= maxRank)
585  break;
586 
587  // Rank-1 down-date of Ab, expensive, using outer product
588  Ab.block(0, j + 1, m, n - j).noalias() -= a * rd.middleCols(j + 1, n - j);
589  }
590  }
591 
592  // Create storage for precisions
593  Vector precisions(Rd.size());
594 
595  // Write back result in Ab, imperative as we are
596  size_t i = 0; // start with first row
597  bool mixed = false;
598  Ab.setZero(); // make sure we don't look below
599  for (const Triple& t: Rd) {
600  const size_t& j = std::get<0>(t);
601  const Matrix& rd = std::get<1>(t);
602  precisions(i) = std::get<2>(t);
603  if (std::isinf(precisions(i)))
604  mixed = true;
605  Ab.block(i, j, 1, n + 1 - j) = rd.block(0, j, 1, n + 1 - j);
606  i += 1;
607  }
608 
609  // Must include mu, as the defaults might be higher, resulting in non-convergence
611 }
612 
613 /* ************************************************************************* */
614 // Isotropic
615 /* ************************************************************************* */
616 Isotropic::shared_ptr Isotropic::Sigma(size_t dim, double sigma, bool smart) {
617  if (smart && std::abs(sigma-1.0)<1e-9) return Unit::Create(dim);
618  return shared_ptr(new Isotropic(dim, sigma));
619 }
620 
621 /* ************************************************************************* */
622 Isotropic::shared_ptr Isotropic::Variance(size_t dim, double variance, bool smart) {
623  if (smart && std::abs(variance-1.0)<1e-9) return Unit::Create(dim);
624  return shared_ptr(new Isotropic(dim, sqrt(variance)));
625 }
626 
627 /* ************************************************************************* */
628 void Isotropic::print(const string& name) const {
629  cout << "isotropic dim=" << dim() << " sigma=" << sigma_ << endl;
630 }
631 
632 /* ************************************************************************* */
634  return v.dot(v) * invsigma_ * invsigma_;
635 }
636 
637 /* ************************************************************************* */
639  return v * invsigma_;
640 }
641 
642 /* ************************************************************************* */
644  return v * sigma_;
645 }
646 
647 /* ************************************************************************* */
649  return invsigma_ * H;
650 }
651 
652 /* ************************************************************************* */
654  H *= invsigma_;
655 }
656 
657 /* ************************************************************************* */
659  v *= invsigma_;
660 }
661 
662 /* ************************************************************************* */
664  H *= invsigma_;
665 }
666 
667 /* *******************************************************************************/
668 double Isotropic::logDetR() const { return log(invsigma_) * dim(); }
669 
670 /* ************************************************************************* */
671 // Unit
672 /* ************************************************************************* */
673 void Unit::print(const std::string& name) const {
674  cout << name << "unit (" << dim_ << ") " << endl;
675 }
676 
677 /* ************************************************************************* */
679  return v.dot(v);
680 }
681 
682 /* *******************************************************************************/
683 double Unit::logDetR() const { return 0.0; }
684 
685 /* ************************************************************************* */
686 // Robust
687 /* ************************************************************************* */
688 
689 void Robust::print(const std::string& name) const {
690  robust_->print(name);
691  noise_->print(name);
692 }
693 
694 bool Robust::equals(const Base& expected, double tol) const {
695  const Robust* p = dynamic_cast<const Robust*> (&expected);
696  if (p == nullptr) return false;
697  return noise_->equals(*p->noise_,tol) && robust_->equals(*p->robust_,tol);
698 }
699 
701  noise_->whitenInPlace(b);
702  robust_->reweight(b);
703 }
704 
705 void Robust::WhitenSystem(vector<Matrix>& A, Vector& b) const {
706  noise_->WhitenSystem(A,b);
707  robust_->reweight(A,b);
708 }
709 
711  noise_->WhitenSystem(A,b);
712  robust_->reweight(A,b);
713 }
714 
716  noise_->WhitenSystem(A1,A2,b);
717  robust_->reweight(A1,A2,b);
718 }
719 
721  noise_->WhitenSystem(A1,A2,A3,b);
722  robust_->reweight(A1,A2,A3,b);
723 }
724 
726  return noise_->unweightedWhiten(v);
727 }
728 double Robust::weight(const Vector& v) const {
729  return robust_->weight(v.norm());
730 }
731 
733 const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){
734  return shared_ptr(new Robust(robust,noise));
735 }
736 
737 /* ************************************************************************* */
738 } // namespace noiseModel
739 } // gtsam
gtsam::noiseModel::Isotropic::Isotropic
Isotropic()
Definition: NoiseModel.h:555
timing.h
Timing utilities.
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
gtsam::noiseModel::Constrained::MixedVariances
static shared_ptr MixedVariances(const Vector &mu, const Vector &variances)
Definition: NoiseModel.cpp:412
gtsam::noiseModel::Diagonal::unwhiten
Vector unwhiten(const Vector &v) const override
Unwhiten an error vector.
Definition: NoiseModel.cpp:318
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::noiseModel::internal::fix
static void fix(const Vector &sigmas, Vector &precisions, Vector &invsigmas)
Definition: NoiseModel.cpp:346
gtsam::noiseModel::Diagonal::whiten
Vector whiten(const Vector &v) const override
Whiten an error vector.
Definition: NoiseModel.cpp:314
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
name
Annotation for function names.
Definition: attr.h:51
llt
EIGEN_DONT_INLINE void llt(const Mat &A, const Mat &B, Mat &C)
Definition: llt.cpp:5
Eigen::Block
Expression of a fixed-size or dynamic-size block.
Definition: Block.h:103
A3
static const double A3[]
Definition: expn.h:8
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
gtsam::noiseModel::Robust::robust
const RobustModel::shared_ptr & robust() const
Return the contained robust error function.
Definition: NoiseModel.h:705
gtsam::noiseModel::Diagonal::Whiten
Matrix Whiten(const Matrix &H) const override
Definition: NoiseModel.cpp:322
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::noiseModel::Base
Definition: NoiseModel.h:57
gtsam::noiseModel::Constrained::MixedSigmas
static shared_ptr MixedSigmas(const Vector &mu, const Vector &sigmas)
Definition: NoiseModel.cpp:368
gtsam::noiseModel::Base::shared_ptr
std::shared_ptr< Base > shared_ptr
Definition: NoiseModel.h:60
test_constructor::sigmas
Vector1 sigmas
Definition: testHybridNonlinearFactor.cpp:52
gtsam::noiseModel::Constrained::unit
shared_ptr unit() const
Definition: NoiseModel.cpp:461
gtsam::noiseModel::Robust::unweightedWhiten
Vector unweightedWhiten(const Vector &v) const override
Definition: NoiseModel.cpp:725
gtsam::noiseModel::Diagonal::Precisions
static shared_ptr Precisions(const Vector &precisions, bool smart=true)
Definition: NoiseModel.cpp:303
gtsam::noiseModel::check_if_constraint
std::optional< size_t > check_if_constraint(VECTOR a, const Vector &invsigmas, size_t m)
Definition: NoiseModel.cpp:477
mu
double mu
Definition: testBoundingConstraint.cpp:37
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
b
Scalar * b
Definition: benchVecAdd.cpp:17
gtsam::noiseModel::Robust::Create
static shared_ptr Create(const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise)
Definition: NoiseModel.cpp:732
gtsam::noiseModel::Diagonal
Definition: NoiseModel.h:301
gtsam::noiseModel::Diagonal::Diagonal
Diagonal()
Definition: NoiseModel.cpp:264
x
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 x
Definition: gnuplot_common_settings.hh:12
gtsam::noiseModel::Robust::print
void print(const std::string &name) const override
Definition: NoiseModel.cpp:689
gtsam::noiseModel::Isotropic::sigma_
double sigma_
Definition: NoiseModel.h:543
gtsam::noiseModel::Diagonal::invsigmas
const Vector & invsigmas() const
Definition: NoiseModel.h:361
Eigen::Upper
@ Upper
Definition: Constants.h:211
gtsam::noiseModel::Gaussian
Definition: NoiseModel.h:168
gtsam::equal_with_abs_tol
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
gtsam::noiseModel::Diagonal::print
void print(const std::string &name) const override
Definition: NoiseModel.cpp:309
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::noiseModel::Isotropic::print
void print(const std::string &name) const override
Definition: NoiseModel.cpp:628
gtsam::noiseModel::Isotropic::Variance
static shared_ptr Variance(size_t dim, double variance, bool smart=true)
Definition: NoiseModel.cpp:622
log
const EIGEN_DEVICE_FUNC LogReturnType log() const
Definition: ArrayCwiseUnaryOps.h:128
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:283
gtsam::noiseModel::updateAb
void updateAb(MATRIX &Ab, int j, const Vector &a, const Vector &rd)
Definition: NoiseModel.cpp:41
gtsam::noiseModel::Diagonal::WhitenInPlace
void WhitenInPlace(Matrix &H) const override
Definition: NoiseModel.cpp:326
gtsam::noiseModel::Base::dim
size_t dim() const
Dimensionality.
Definition: NoiseModel.h:79
gtsam::noiseModel::Constrained::Constrained
Constrained(const Vector &mu, const Vector &sigmas)
Definition: NoiseModel.cpp:362
gtsam::noiseModel::Robust::WhitenSystem
virtual void WhitenSystem(Vector &b) const
Definition: NoiseModel.cpp:700
gtsam::noiseModel::Gaussian::shared_ptr
std::shared_ptr< Gaussian > shared_ptr
Definition: NoiseModel.h:191
gtsam::noiseModel::Constrained::QR
Diagonal::shared_ptr QR(Matrix &Ab) const override
Definition: NoiseModel.cpp:494
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
diagonal
void diagonal(const MatrixType &m)
Definition: diagonal.cpp:12
gtsam::noiseModel::Isotropic::logDetR
virtual double logDetR() const override
Compute the log of |R|. Used for computing log(|Σ|)
Definition: NoiseModel.cpp:668
gtsam::noiseModel::Isotropic::sigma
double sigma() const
Definition: NoiseModel.h:593
gtsam::noiseModel::Isotropic::whitenInPlace
void whitenInPlace(Vector &v) const override
Definition: NoiseModel.cpp:658
gtsam::noiseModel::Constrained::print
void print(const std::string &name) const override
Definition: NoiseModel.cpp:380
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:170
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
gtsam::noiseModel::Isotropic::squaredMahalanobisDistance
double squaredMahalanobisDistance(const Vector &v) const override
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
Definition: NoiseModel.cpp:633
gtsam::noiseModel::Diagonal::invsigmas_
Vector invsigmas_
Definition: NoiseModel.h:309
gtsam::noiseModel::Diagonal::sigmas
Vector sigmas() const override
Calculate standard deviations.
Definition: NoiseModel.h:346
gtsam::noiseModel::Diagonal::precisions_
Vector precisions_
Definition: NoiseModel.h:309
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::noiseModel::Constrained::mu_
Vector mu_
Penalty function weight - needs to be large enough to dominate soft constraints.
Definition: NoiseModel.h:408
gtsam::noiseModel::Constrained::mu
const Vector & mu() const
Access mu as a vector.
Definition: NoiseModel.h:438
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:145
gtsam::noiseModel::Robust::Robust
Robust()
Default Constructor for serialization.
Definition: NoiseModel.h:692
gtsam::noiseModel::mEstimator::Base::shared_ptr
std::shared_ptr< Base > shared_ptr
Definition: LossFunctions.h:71
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
make_tuple
tuple make_tuple()
Definition: cast.h:1390
gtsam::vector_scale_inplace
void vector_scale_inplace(const Vector &v, Matrix &A, bool inf_mask)
Definition: Matrix.cpp:470
I
#define I
Definition: main.h:112
gtsam::noiseModel::Diagonal::precision
double precision(size_t i) const
Definition: NoiseModel.h:368
square
const EIGEN_DEVICE_FUNC SquareReturnType square() const
Definition: ArrayCwiseUnaryOps.h:425
gtsam::noiseModel::Isotropic::invsigma_
double invsigma_
Definition: NoiseModel.h:543
Eigen::all
static const Eigen::internal::all_t all
Definition: IndexedViewHelper.h:171
gtsam::internal::logDeterminant
double logDeterminant(const typename BAYESTREE::sharedClique &clique)
Definition: GaussianBayesTree-inl.h:42
gtsam::noiseModel::Unit::Create
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:631
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
A2
static const double A2[]
Definition: expn.h:7
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:916
gtsam::noiseModel::Unit::logDetR
virtual double logDetR() const override
Compute the log of |R|. Used for computing log(|Σ|)
Definition: NoiseModel.cpp:683
gtsam::noiseModel::Diagonal::sigmas_
Vector sigmas_
Definition: NoiseModel.h:309
isfinite
#define isfinite(X)
Definition: main.h:95
gtsam::noiseModel::Robust
Definition: NoiseModel.h:678
gtsam::noiseModel::Unit::squaredMahalanobisDistance
double squaredMahalanobisDistance(const Vector &v) const override
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
Definition: NoiseModel.cpp:678
gtsam::noiseModel::Isotropic::Whiten
Matrix Whiten(const Matrix &H) const override
Definition: NoiseModel.cpp:648
gtsam::noiseModel::Constrained::whiten
Vector whiten(const Vector &v) const override
Calculates error vector with weights applied.
Definition: NoiseModel.cpp:386
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::noiseModel::Robust::robust_
const RobustModel::shared_ptr robust_
robust error function used
Definition: NoiseModel.h:686
gtsam::noiseModel::Constrained::squaredMahalanobisDistance
double squaredMahalanobisDistance(const Vector &v) const override
Definition: NoiseModel.cpp:429
gtsam::noiseModel::Robust::weight
double weight(const Vector &v) const override
Definition: NoiseModel.cpp:728
gtsam::noiseModel::checkIfDiagonal
std::optional< Vector > checkIfDiagonal(const Matrix &M)
Definition: NoiseModel.cpp:48
gtsam::noiseModel::Diagonal::precisions
const Vector & precisions() const
Definition: NoiseModel.h:367
gtsam::noiseModel::Robust::noise_
const NoiseModel::shared_ptr noise_
noise model used
Definition: NoiseModel.h:687
gtsam::b
const G & b
Definition: Group.h:79
Eigen::LLT
Standard Cholesky decomposition (LL^T) of a matrix and associated features.
Definition: LLT.h:66
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::inplace_QR
void inplace_QR(Matrix &A)
Definition: Matrix.cpp:626
gtsam::noiseModel::Isotropic::whiten
Vector whiten(const Vector &v) const override
Whiten an error vector.
Definition: NoiseModel.cpp:638
array
Definition: numpy.h:821
gtsam::backSubstituteUpper
Vector backSubstituteUpper(const Matrix &U, const Vector &b, bool unit)
Definition: Matrix.cpp:365
gtsam
traits
Definition: SFMdata.h:40
NoiseModel.h
gtsam::noiseModel::Isotropic::WhitenInPlace
void WhitenInPlace(Matrix &H) const override
Definition: NoiseModel.cpp:653
gtsam::vector_scale
Matrix vector_scale(const Vector &v, const Matrix &A, bool inf_mask)
Definition: Matrix.cpp:486
gtsam::noiseModel::Diagonal::logDetR
virtual double logDetR() const override
Compute the log of |R|. Used for computing log(|Σ|)
Definition: NoiseModel.cpp:335
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
std
Definition: BFloat16.h:88
gtsam::noiseModel::Diagonal::shared_ptr
std::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:321
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Diagonal
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
Definition: ScenarioRunner.h:27
A1
static const double A1[]
Definition: expn.h:6
exampleQR::Rd
Matrix Rd
Definition: testNoiseModel.cpp:215
gtsam::noiseModel::Constrained::Whiten
Matrix Whiten(const Matrix &H) const override
Definition: NoiseModel.cpp:438
gtsam::noiseModel::Robust::shared_ptr
std::shared_ptr< Robust > shared_ptr
Definition: NoiseModel.h:680
exampleQR::Ab
Matrix Ab
Definition: testNoiseModel.cpp:207
gtsam::noiseModel::Constrained::MixedPrecisions
static shared_ptr MixedPrecisions(const Vector &mu, const Vector &precisions)
Definition: NoiseModel.cpp:420
gtsam::noiseModel::Unit::print
void print(const std::string &name) const override
Definition: NoiseModel.cpp:673
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::noiseModel::Constrained::constrained
bool constrained(size_t i) const
Return true if a particular dimension is free or constrained.
Definition: NoiseModel.cpp:374
min
#define min(a, b)
Definition: datatypes.h:19
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:616
abs
#define abs(x)
Definition: datatypes.h:17
internal
Definition: BandTriangularSolver.h:13
gtsam::noiseModel::Isotropic::shared_ptr
std::shared_ptr< Isotropic > shared_ptr
Definition: NoiseModel.h:559
gtsam::noiseModel::Base::dim_
size_t dim_
Definition: NoiseModel.h:64
gtsam::noiseModel::Robust::noise
const NoiseModel::shared_ptr & noise() const
Return the contained noise model.
Definition: NoiseModel.h:708
align_3::t
Point2 t(10, 10)
gtsam::noiseModel::Constrained::WhitenInPlace
void WhitenInPlace(Matrix &H) const override
Definition: NoiseModel.cpp:447
gtsam::noiseModel::Constrained::shared_ptr
std::shared_ptr< Constrained > shared_ptr
Definition: NoiseModel.h:419
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::noiseModel::Robust::equals
bool equals(const Base &expected, double tol=1e-9) const override
Definition: NoiseModel.cpp:694
R
Rot2 R(Rot2::fromAngle(0.1))
gtsam::noiseModel::Isotropic::unwhiten
Vector unwhiten(const Vector &v) const override
Unwhiten an error vector.
Definition: NoiseModel.cpp:643
gttic
#define gttic(label)
Definition: timing.h:326
gtsam::noiseModel::Diagonal::Variances
static shared_ptr Variances(const Vector &variances, bool smart=true)
Definition: NoiseModel.cpp:275
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74
isinf
#define isinf(X)
Definition: main.h:94
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:02:33