31 namespace noiseModel {
39 template<
class MATRIX>
41 size_t n = Ab.cols()-1;
42 Ab.middleCols(j+1,n-j) -= a * rd.segment(j+1, n-j).transpose();
48 size_t m = M.rows(),
n = M.cols();
53 for (i = 0; i <
m; i++)
55 for (j = i + 1; j <
n; j++)
64 for (j = 0; j <
n; j++)
66 return std::move(diagonal);
72 throw(
"Base::sigmas: sigmas() not implemented for this noise model");
76 double Base::squaredMahalanobisDistance(
const Vector&
v)
const {
84 size_t m = R.rows(),
n = R.cols();
86 throw invalid_argument(
"Gaussian::SqrtInformation: R not square");
90 return Diagonal::Sigmas(diagonal->array().inverse(),
true);
93 return std::make_shared<Gaussian>(R.rows(),
R);
98 size_t m = information.rows(),
n = information.cols();
100 throw invalid_argument(
"Gaussian::Information: R not square");
101 std::optional<Vector>
diagonal = {};
105 return Diagonal::Precisions(*diagonal,
true);
109 return std::make_shared<Gaussian>(
n,
R);
116 size_t m = covariance.rows(),
n = covariance.cols();
118 throw invalid_argument(
"Gaussian::Covariance: covariance not square");
119 std::optional<Vector> variances = {};
123 return Diagonal::Variances(*variances,
true);
129 return Information(covariance.inverse(),
false);
141 if (p ==
nullptr)
return false;
142 if (
typeid(*
this) !=
typeid(*p))
return false;
150 Matrix I = Matrix::Identity(R.rows(), R.cols());
154 return Rinv * Rinv.transpose();
178 void Gaussian::WhitenInPlace(
Matrix&
H)
const {
191 gttic(Gaussian_noise_model_QR);
193 static const bool debug =
false;
197 size_t m = Ab.rows(),
n = Ab.cols()-1;
198 size_t maxRank =
min(m,
n);
213 return noiseModel::Unit::Create(maxRank);
216 void Gaussian::WhitenSystem(vector<Matrix>& A,
Vector&
b)
const {
217 for(
Matrix& Aj: A) { WhitenInPlace(Aj); }
239 Matrix Gaussian::information()
const {
return R().transpose() *
R(); }
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++)
289 return Variances(precisions.array().inverse(), smart);
302 return v.cwiseProduct(
sigmas_);
371 assert (b.size()==a.size());
373 for(
size_t i = 0;
i <
n;
i++ ) {
374 const double& ai =
a(
i), bi =
b(
i);
375 c(
i) = (bi==0.0) ? ai : ai/bi;
387 return MixedSigmas(Vector::Constant(sigmas.size(),
m), sigmas);
391 const Vector& variances) {
441 for (
size_t i=0;
i<
dim(); ++
i)
454 template <
typename VECTOR>
456 std::optional<size_t> constraint_row;
459 double max_element = 1
e-9;
460 for (
size_t i = 0;
i <
m;
i++) {
464 if (abs_ai > max_element) {
465 max_element = abs_ai;
469 return constraint_row;
473 static const double kInfinity = std::numeric_limits<double>::infinity();
476 size_t m = Ab.rows();
477 const size_t n = Ab.cols() - 1;
478 const size_t maxRank =
min(m, n);
481 typedef std::tuple<size_t, Matrix, double> Triple;
486 Vector weights = invsigmas.array().square();
492 for (
size_t j = 0;
j <
n; ++
j) {
499 if (constraint_row) {
504 rd = Ab.row(*constraint_row);
510 if (Rd.size() >= maxRank)
516 if (*constraint_row != m) {
517 Ab.row(*constraint_row) = Ab.row(m);
518 weights(*constraint_row) = weights(m);
524 a_reduced *= (1.0/rd(0,
j));
527 Ab.block(0,
j + 1, m, n -
j).noalias() -= a_reduced * rd.middleCols(
j + 1, n -
j);
536 for (
size_t i = 0;
i <
m;
i++) {
539 pseudo[
i] = weights[
i] * ai;
540 precision += pseudo[
i] * ai;
545 if (precision > 1
e-8) {
550 rd.block(0,
j + 1, 1, n -
j) = pseudo.transpose() * Ab.block(0,
j + 1, m, n -
j);
562 if (Rd.size() >= maxRank)
566 Ab.block(0,
j + 1, m, n -
j).noalias() -= a * rd.middleCols(
j + 1, n -
j);
577 for (
const Triple&
t: Rd) {
578 const size_t&
j = std::get<0>(
t);
579 const Matrix& rd = std::get<1>(
t);
583 Ab.block(i, j, 1, n + 1 - j) = rd.block(0, j, 1, n + 1 - j);
607 cout <<
"isotropic dim=" <<
dim() <<
" sigma=" << sigma_ << endl;
612 return v.dot(v) * invsigma_ * invsigma_;
617 return v * invsigma_;
627 return invsigma_ *
H;
649 cout << name <<
"unit (" <<
dim_ <<
") " << endl;
662 robust_->print(name);
668 if (p ==
nullptr)
return false;
673 noise_->whitenInPlace(b);
674 robust_->reweight(b);
678 noise_->WhitenSystem(A,b);
679 robust_->reweight(A,b);
683 noise_->WhitenSystem(A,b);
684 robust_->reweight(A,b);
688 noise_->WhitenSystem(A1,A2,b);
689 robust_->reweight(A1,A2,b);
693 noise_->WhitenSystem(A1,A2,A3,b);
694 robust_->reweight(A1,A2,A3,b);
698 return noise_->unweightedWhiten(v);
701 return robust_->weight(v.norm());
void print(const Matrix &A, const string &s, ostream &stream)
Vector unweightedWhiten(const Vector &v) const override
Vector mu_
Penalty function weight - needs to be large enough to dominate soft constraints.
void print(const std::string &name) const override
Matrix< RealScalar, Dynamic, Dynamic > M
std::optional< size_t > check_if_constraint(VECTOR a, const Vector &invsigmas, size_t m)
Vector backSubstituteUpper(const Matrix &U, const Vector &b, bool unit)
void inplace_QR(Matrix &A)
void print(const std::string &name) const override
const Vector & invsigmas() const
std::shared_ptr< Base > shared_ptr
void updateAb(MATRIX &Ab, int j, const Vector &a, const Vector &rd)
double squaredMahalanobisDistance(const Vector &v) const override
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_STRONG_INLINE Packet4f print(const Packet4f &a)
Matrix Whiten(const Matrix &H) const override
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
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 Create(const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise)
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
ptrdiff_t DenseIndex
The index type for Eigen objects.
Matrix vector_scale(const Vector &v, const Matrix &A, bool inf_mask)
static constexpr bool debug
static shared_ptr MixedPrecisions(const Vector &mu, const Vector &precisions)
static shared_ptr Create(size_t dim)
virtual void WhitenSystem(Vector &b) const
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
std::shared_ptr< Constrained > shared_ptr
double sigma(size_t i) const
EIGEN_DONT_INLINE void llt(const Mat &A, const Mat &B, Mat &C)
static shared_ptr MixedSigmas(const Vector &mu, const Vector &sigmas)
EIGEN_DEVICE_FUNC const SquareReturnType square() const
const RobustModel::shared_ptr robust_
robust error function used
void whitenInPlace(Vector &v) const override
const Vector & precisions() const
Vector sigmas() const override
Calculate standard deviations.
bool constrained(size_t i) const
Return true if a particular dimension is free or constrained.
const NoiseModel::shared_ptr noise_
noise model used
std::shared_ptr< Base > shared_ptr
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< int, Dynamic, 1 > v
double weight(const Vector &v) const override
static shared_ptr MixedVariances(const Vector &mu, const Vector &variances)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::shared_ptr< Isotropic > shared_ptr
Vector unwhiten(const Vector &v) const override
Unwhiten an error vector.
Vector whiten(const Vector &v) const override
Whiten an error vector.
void print(const std::string &name) const override
static shared_ptr Precisions(const Vector &precisions, bool smart=true)
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
noiseModel::Diagonal::shared_ptr SharedDiagonal
Matrix Whiten(const Matrix &H) const override
std::optional< Vector > checkIfDiagonal(const Matrix &M)
Matrix Whiten(const Matrix &H) const override
std::shared_ptr< Robust > shared_ptr
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
Traits::MatrixU matrixU() const
Diagonal::shared_ptr QR(Matrix &Ab) const override
const Vector & mu() const
Access mu as a vector.
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
bool equals(const Base &expected, double tol=1e-9) const override
Jet< T, N > sqrt(const Jet< T, N > &f)
Annotation for function names.
void vector_scale_inplace(const Vector &v, Matrix &A, bool inf_mask)
double precision(size_t i) const
std::shared_ptr< Gaussian > shared_ptr
void print(const std::string &name) const override
std::shared_ptr< Diagonal > shared_ptr
size_t dim() const
Dimensionality.
double squaredMahalanobisDistance(const Vector &v) const override
Squared Mahalanobis distance v'*R'*R*v = <R*v,R*v>
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)
Constrained(const Vector &mu, const Vector &sigmas)
Vector whiten(const Vector &v) const override
Whiten an error vector.
static void fix(const Vector &sigmas, Vector &precisions, Vector &invsigmas)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
virtual Matrix R() const
Return R itself, but note that Whiten(H) is cheaper than R*H.