23#include <gtsam/dllexport.h>
33#include <Eigen/Sparse>
41class NonlinearFactorGraph;
42class LevenbergMarquardtOptimizer;
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",
66 double optimalityThreshold = -1e-4,
67 double alpha = 0.0,
double beta = 1.0,
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>>;
136 Measurements measurements_;
146 Sparse buildQ()
const;
149 Sparse buildD()
const;
172 return measurements_[k];
182 double k = 1.345)
const {
183 Measurements robustMeasurements;
184 for (
auto &measurement : measurements) {
185 auto model = measurement.noiseModel();
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);
199 measurement.measured(), robust_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;
227 return Matrix(computeLambda(values));
232 return Matrix(computeLambda(S));
236 Sparse computeA(
const Values &values)
const;
239 Sparse computeA(
const Matrix &S)
const;
243 return Matrix(computeA(values));
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;
267 static VectorValues TangentVectorValues(
size_t p,
const Vector &v);
270 Matrix riemannianGradient(
size_t p,
const Values &values)
const;
276 static Values LiftwithDescent(
size_t p,
const Values &values,
277 const Vector &minEigenVector);
286 Values initializeWithDescent(
287 size_t p,
const Values &values,
const Vector &minEigenVector,
288 double minEigenValue,
double gradienTolerance = 1e-2,
289 double preconditionedGradNormTolerance = 1e-4)
const;
304 Values initializeRandomlyAt(
size_t p, std::mt19937 &rng)
const;
307 Values initializeRandomlyAt(
size_t p)
const;
313 double costAt(
size_t p,
const Values &values)
const;
320 Sparse computeLambda(
const Values &values)
const;
327 std::pair<double, Vector> computeMinEigenVector(
const Values &values)
const;
333 bool checkOptimality(
const Values &values)
const;
341 boost::shared_ptr<LevenbergMarquardtOptimizer> createOptimizerAt(
342 size_t p,
const Values &initial)
const;
350 Values tryOptimizingAt(
size_t p,
const Values &initial)
const;
368 for (
const auto it : values.
filter<T>()) {
369 result.insert(it.key,
SOn::Lift(p, it.value.matrix()));
382 double cost(
const Values &values)
const;
391 Values initializeRandomly(std::mt19937 &rng)
const;
394 Values initializeRandomly()
const;
403 std::pair<Values, double> run(
const Values &initialEstimate,
size_t pMin = d,
404 size_t pMax = 10)
const;
416 template <
typename T>
419 bool useRobustModel =
false)
const {
420 return useRobustModel ? makeNoiseModelRobust(measurements) : measurements;
430 const Parameters ¶meters = Parameters());
432 const Parameters ¶meters = Parameters());
434 const Parameters ¶meters = Parameters());
440 const Parameters ¶meters = Parameters());
442 const Parameters ¶meters = Parameters());
446 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
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
static SO Lift(size_t n, const Eigen::MatrixBase< Derived > &R)
Named constructor from lower dimensional matrix.
Definition: SOn.h:99
This class represents a collection of vector-valued variables associated each with a unique integer i...
Definition: VectorValues.h:74
Parameters for Levenberg-Marquardt optimization.
Definition: LevenbergMarquardtParams.h:35
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:78
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:63
Filtered< Value > filter(const std::function< bool(Key)> &filterFcn)
Return a filtered view of this Values class, without copying any data.
Definition: Values-inl.h:239
Parameters governing optimization etc.
Definition: ShonanAveraging.h:46
double alpha
weight of anchor-based prior (default 0)
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
LM parameters.
Definition: ShonanAveraging.h:52
bool useHuber
if enabled, the Huber loss is used (default false)
Definition: ShonanAveraging.h:59
double optimalityThreshold
threshold used in checkOptimality
Definition: ShonanAveraging.h:53
double beta
weight of Karcher-based prior (default 1)
Definition: ShonanAveraging.h:56
double gamma
weight of gauge-fixing factors (default 0)
Definition: ShonanAveraging.h:57
Anchor anchor
pose to use as anchor if not Karcher
Definition: ShonanAveraging.h:54
bool certifyOptimality
if enabled solution optimality is certified (default true)
Definition: ShonanAveraging.h:61
Class that implements Shonan Averaging from our ECCV'20 paper.
Definition: ShonanAveraging.h:123
Sparse D() const
Sparse version of D.
Definition: ShonanAveraging.h:215
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 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:417
Sparse L() const
Sparse version of L.
Definition: ShonanAveraging.h:219
const Rot & measured(size_t k) const
k^th measurement, as a Rot.
Definition: ShonanAveraging.h:206
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)
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
Matrix denseQ() const
Dense version of Q.
Definition: ShonanAveraging.h:218
const KeyVector & keys(size_t k) const
Keys for k^th measurement, as a vector of Key values.
Definition: ShonanAveraging.h:209
size_t nrMeasurements() const
Return number of measurements.
Definition: ShonanAveraging.h:168
Matrix computeLambda_(const Values &values) const
Dense versions of computeLambda for wrapper/testing.
Definition: ShonanAveraging.h:226
Matrix computeA_(const Values &values) const
Dense version of computeA for wrapper/testing.
Definition: ShonanAveraging.h:242
static Values LiftTo(size_t p, const Values &values)
Lift Values of type T to SO(p)
Definition: ShonanAveraging.h:366
Definition: ShonanAveraging.h:427
Definition: ShonanAveraging.h:437