23#include <gtsam/dllexport.h>
33#include <Eigen/Sparse>
46struct GTSAM_EXPORT ShonanAveragingParameters {
48 using Rot =
typename std::conditional<d == 2, Rot2, Rot3>::type;
49 using Anchor = std::pair<size_t, Rot>;
64 LevenbergMarquardtParams::CeresDefaults(),
65 const std::string &method =
"JACOBI",
72 void setOptimalityThreshold(
double value) { optimalityThreshold = value; }
73 double getOptimalityThreshold()
const {
return optimalityThreshold; }
75 void setAnchor(
size_t index,
const Rot &value) { anchor = {index, value}; }
76 std::pair<size_t, Rot> getAnchor()
const {
return anchor; }
78 void setAnchorWeight(
double value) { alpha = value; }
79 double getAnchorWeight()
const {
return alpha; }
81 void setKarcherWeight(
double value) { beta = value; }
82 double getKarcherWeight()
const {
return beta; }
84 void setGaugesWeight(
double value) { gamma = value; }
85 double getGaugesWeight()
const {
return gamma; }
87 void setUseHuber(
bool value) { useHuber = value; }
88 bool getUseHuber()
const {
return useHuber; }
90 void setCertifyOptimality(
bool value) { certifyOptimality = value; }
91 bool getCertifyOptimality()
const {
return certifyOptimality; }
94 void print(
const std::string &s =
"")
const {
95 std::cout << (s.empty() ? s : s +
" ");
96 std::cout <<
" ShonanAveragingParameters: " << std::endl;
97 std::cout <<
" alpha: " <<
alpha << std::endl;
98 std::cout <<
" beta: " <<
beta << std::endl;
99 std::cout <<
" gamma: " <<
gamma << std::endl;
100 std::cout <<
" useHuber: " <<
useHuber << std::endl;
104using ShonanAveragingParameters2 = ShonanAveragingParameters<2>;
105using ShonanAveragingParameters3 = ShonanAveragingParameters<3>;
125 using Sparse = Eigen::SparseMatrix<double>;
129 using Rot =
typename Parameters::Rot;
132 using Measurements = std::vector<BinaryMeasurement<Rot>>;
135 Parameters parameters_;
136 Measurements measurements_;
146 Sparse buildQ()
const;
149 Sparse buildD()
const;
158 const Parameters ¶meters = Parameters());
172 return measurements_[k];
182 double k = 1.345)
const {
183 Measurements robustMeasurements;
187 boost::dynamic_pointer_cast<noiseModel::Robust>(model);
192 robust_model = model;
195 robust_model = noiseModel::Robust::Create(
196 noiseModel::mEstimator::Huber::Create(k), model);
200 robustMeasurements.push_back(meas);
202 return robustMeasurements;
206 const Rot &
measured(
size_t k)
const {
return measurements_[k].measured(); }
215 Sparse
D()
const {
return D_; }
216 Matrix
denseD()
const {
return Matrix(D_); }
217 Sparse
Q()
const {
return Q_; }
218 Matrix
denseQ()
const {
return Matrix(Q_); }
219 Sparse
L()
const {
return L_; }
220 Matrix
denseL()
const {
return Matrix(L_); }
223 Sparse computeLambda(
const Matrix &S)
const;
236 Sparse computeA(
const Values &values)
const;
239 Sparse computeA(
const Matrix &S)
const;
247 static Matrix StiefelElementMatrix(
const Values &values);
253 double computeMinEigenValue(
const Values &values,
254 Vector *minEigenVector =
nullptr)
const;
260 double computeMinEigenValueAP(
const Values &values,
261 Vector *minEigenVector =
nullptr)
const;
277 const Vector &minEigenVector);
287 size_t p,
const Values &values,
const Vector &minEigenVector,
288 double minEigenValue,
double gradienTolerance = 1e-2,
289 double preconditionedGradNormTolerance = 1e-4)
const;
343 size_t p,
const Values &initial)
const;
369 for (
const auto it : values.
extract<T>()) {
383 double cost(
const Values &values)
const;
392 Values initializeRandomly(std::mt19937 &rng)
const;
395 Values initializeRandomly()
const;
404 std::pair<Values, double> run(
const Values &initialEstimate,
size_t pMin = d,
405 size_t pMax = 10)
const;
417 template <
typename T>
420 bool useRobustModel =
false)
const {
430 ShonanAveraging2(
const Measurements &measurements,
431 const Parameters ¶meters = Parameters());
432 explicit ShonanAveraging2(std::string g2oFile,
433 const Parameters ¶meters = Parameters());
434 ShonanAveraging2(
const BetweenFactorPose2s &factors,
435 const Parameters ¶meters = Parameters());
440 ShonanAveraging3(
const Measurements &measurements,
441 const Parameters ¶meters = Parameters());
442 explicit ShonanAveraging3(std::string g2oFile,
443 const Parameters ¶meters = Parameters());
446 ShonanAveraging3(
const BetweenFactorPose3s &factors,
447 const Parameters ¶meters = Parameters());
typedef and functions to augment Eigen's MatrixXd
typedef and functions to augment Eigen's VectorXd
3D rotation represented as a rotation matrix or quaternion
accelerated power method for fast eigenvalue and eigenvector computation
Power method for fast eigenvalue and eigenvector computation.
Parameters for Levenberg-Marquardt trust-region scheme.
Binary measurement represents a measurement between two keys in a graph. A binary measurement is simi...
utility functions for loading datasets
Global functions in a separate testing namespace.
Definition chartTesting.h:28
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition Key.h:86
noiseModel::Base::shared_ptr SharedNoiseModel
Aliases.
Definition NoiseModel.h:724
static SO Lift(size_t n, const Eigen::MatrixBase< Derived > &R)
Definition SOn.h:101
VectorValues represents a collection of vector-valued variables associated each with a unique integer...
Definition VectorValues.h:74
This class performs Levenberg-Marquardt nonlinear optimization.
Definition LevenbergMarquardtOptimizer.h:35
Parameters for Levenberg-Marquardt optimization.
Definition LevenbergMarquardtParams.h:35
Definition NonlinearFactorGraph.h:55
A non-templated config holding any types of Manifold-group elements.
Definition Values.h:65
std::map< Key, ValueType > extract(const std::function< bool(Key)> &filterFcn=&_truePredicate< Key >) const
Extract a subset of values of the given type ValueType.
Definition Values-inl.h:94
void insert(Key j, const Value &val)
Add a variable with the given j, throws KeyAlreadyExists<J> if j is already present.
Definition Values.cpp:157
Definition BinaryMeasurement.h:36
Parameters governing optimization etc.
Definition ShonanAveraging.h:46
double alpha
Definition ShonanAveraging.h:55
void print(const std::string &s="") const
Print the parameters and flags used for rotation averaging.
Definition ShonanAveraging.h:94
LevenbergMarquardtParams lm
Definition ShonanAveraging.h:52
bool useHuber
Definition ShonanAveraging.h:59
double optimalityThreshold
Definition ShonanAveraging.h:53
double beta
Definition ShonanAveraging.h:56
double gamma
Definition ShonanAveraging.h:57
Anchor anchor
Definition ShonanAveraging.h:54
bool certifyOptimality
Definition ShonanAveraging.h:61
boost::shared_ptr< LevenbergMarquardtOptimizer > createOptimizerAt(size_t p, const Values &initial) const
Try to create optimizer at SO(p).
Definition ShonanAveraging.cpp:176
Sparse D() const
Sparse version of D.
Definition ShonanAveraging.h:215
std::pair< double, Vector > computeMinEigenVector(const Values &values) const
Compute minimum eigenvalue for optimality check.
Definition ShonanAveraging.cpp:754
const BinaryMeasurement< Rot > & measurement(size_t k) const
k^th binary measurement
Definition ShonanAveraging.h:171
Measurements makeNoiseModelRobust(const Measurements &measurements, double k=1.345) const
Update factors to use robust Huber loss.
Definition ShonanAveraging.h:181
Values roundSolution(const Values &values) const
Project from SO(p)^N to Rot2^N or Rot3^N Values should be of type SO(p).
Definition ShonanAveraging.cpp:309
Values roundSolutionS(const Matrix &S) const
Project pxdN Stiefel manifold matrix S to Rot3^N.
std::vector< BinaryMeasurement< T > > maybeRobust(const std::vector< BinaryMeasurement< T > > &measurements, bool useRobustModel=false) const
Helper function to convert measurements to robust noise model if flag is set.
Definition ShonanAveraging.h:418
Values initializeWithDescent(size_t p, const Values &values, const Vector &minEigenVector, double minEigenValue, double gradienTolerance=1e-2, double preconditionedGradNormTolerance=1e-4) const
Given some values at p-1, return new values at p, by doing a line search along the descent direction,...
Definition ShonanAveraging.cpp:827
Sparse L() const
Sparse version of L.
Definition ShonanAveraging.h:219
static VectorValues TangentVectorValues(size_t p, const Vector &v)
Create a VectorValues with eigenvector v_i.
Definition ShonanAveraging.cpp:770
const Rot & measured(size_t k) const
k^th measurement, as a Rot.
Definition ShonanAveraging.h:206
static Values LiftwithDescent(size_t p, const Values &values, const Vector &minEigenVector)
Lift up the dimension of values in type SO(p-1) with descent direction provided by minEigenVector and...
Definition ShonanAveraging.cpp:818
Sparse Q() const
Sparse version of Q.
Definition ShonanAveraging.h:217
Matrix denseD() const
Dense version of D.
Definition ShonanAveraging.h:216
size_t nrUnknowns() const
Return number of unknowns.
Definition ShonanAveraging.h:165
Values projectFrom(size_t p, const Values &values) const
Project from SO(p) to Rot2 or Rot3 Values should be of type SO(p).
size_t numberMeasurements() const
Return number of measurements.
Definition ShonanAveraging.h:168
Matrix denseL() const
Dense version of L.
Definition ShonanAveraging.h:220
Matrix computeLambda_(const Matrix &S) const
Dense versions of computeLambda for wrapper/testing.
Definition ShonanAveraging.h:231
Sparse computeLambda(const Matrix &S) const
Version that takes pxdN Stiefel manifold elements.
Definition ShonanAveraging.cpp:444
Matrix denseQ() const
Dense version of Q.
Definition ShonanAveraging.h:218
double costAt(size_t p, const Values &values) const
Calculate cost for SO(p) Values should be of type SO(p).
Definition ShonanAveraging.cpp:168
const KeyVector & keys(size_t k) const
Keys for k^th measurement, as a vector of Key values.
Definition ShonanAveraging.h:209
ShonanAveraging(const Measurements &measurements, const Parameters ¶meters=Parameters())
Construct from set of relative measurements (given as BetweenFactor<Rot3> for now) NoiseModel must be...
Definition ShonanAveraging.cpp:122
bool checkOptimality(const Values &values) const
Check optimality.
Definition ShonanAveraging.cpp:763
Sparse computeA(const Values &values) const
Compute A matrix whose Eigenvalues we will examine.
Definition ShonanAveraging.cpp:484
Values tryOptimizingAt(size_t p, const Values &initial) const
Try to optimize at SO(p).
Definition ShonanAveraging.cpp:197
Matrix computeLambda_(const Values &values) const
Dense versions of computeLambda for wrapper/testing.
Definition ShonanAveraging.h:226
Values initializeRandomlyAt(size_t p, std::mt19937 &rng) const
Create initial Values of type SO(p).
Definition ShonanAveraging.cpp:882
Matrix riemannianGradient(size_t p, const Values &values) const
Calculate the riemannian gradient of F(values) at values.
Definition ShonanAveraging.cpp:792
Matrix computeA_(const Values &values) const
Dense version of computeA for wrapper/testing.
Definition ShonanAveraging.h:242
NonlinearFactorGraph buildGraphAt(size_t p) const
Build graph for SO(p).
Definition ShonanAveraging.cpp:143
static Values LiftTo(size_t p, const Values &values)
Lift Values of type T to SO(p).
Definition ShonanAveraging.h:367