23 #include <gtsam/dllexport.h> 33 #include <Eigen/Sparse> 36 #include <type_traits> 41 class NonlinearFactorGraph;
42 class LevenbergMarquardtOptimizer;
49 using Anchor = std::pair<size_t, Rot>;
65 const std::string &method =
"JACOBI",
66 double optimalityThreshold = -1
e-4,
67 double alpha = 0.0,
double beta = 1.0,
76 std::pair<size_t, Rot>
getAnchor()
const {
return anchor; }
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;
172 return measurements_[k];
182 double k = 1.345)
const {
192 robust_model =
model;
200 robustMeasurements.push_back(meas);
202 return robustMeasurements;
206 const Rot &
measured(
size_t k)
const {
return measurements_[k].measured(); }
227 return Matrix(computeLambda(values));
232 return Matrix(computeLambda(S));
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;
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 = 1
e-2,
289 double preconditionedGradNormTolerance = 1
e-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;
327 std::pair<double, Vector> computeMinEigenVector(
const Values &values)
const;
333 bool checkOptimality(
const Values &values)
const;
341 boost::shared_ptr<LevenbergMarquardtOptimizer> createOptimizerAt(
350 Values tryOptimizingAt(
size_t p,
const Values &initial)
const;
356 Values projectFrom(
size_t p,
const Values &values)
const;
368 for (
const auto it : values.
filter<
T>()) {
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;
Measurements makeNoiseModelRobust(const Measurements &measurements, double k=1.345) const
std::vector< BetweenFactor< Pose3 >::shared_ptr > BetweenFactorPose3s
typename std::conditional< d==2, Rot2, Rot3 >::type Rot
const BinaryMeasurement< Rot > & measurement(size_t k) const
k^th binary measurement
double beta
weight of Karcher-based prior (default 1)
Parameters for Levenberg-Marquardt trust-region scheme.
Sparse L() const
Sparse version of L.
std::pair< size_t, Rot > Anchor
double getOptimalityThreshold() const
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
bool getCertifyOptimality() const
typename std::conditional< d==2, Rot2, Rot3 >::type Rot
size_t nrUnknowns() const
Return number of unknowns.
void print(const std::string &s="") const
Print the parameters and flags used for rotation averaging.
Matrix computeLambda_(const Values &values) const
Dense versions of computeLambda for wrapper/testing.
LevenbergMarquardtParams lm
LM parameters.
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
typename Parameters::Rot Rot
static shared_ptr Create(const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise)
static LevenbergMarquardtParams CeresDefaults()
Sparse Q() const
Sparse version of Q.
bool certifyOptimality
if enabled solution optimality is certified (default true)
double alpha
weight of anchor-based prior (default 0)
Parameters governing optimization etc.
accelerated power method for fast eigenvalue and eigenvector computation
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Matrix denseD() const
Dense version of D.
const mpreal gamma(const mpreal &x, mp_rnd_t r=mpreal::get_default_rnd())
void setKarcherWeight(double value)
void setOptimalityThreshold(double value)
Power method for fast eigenvalue and eigenvector computation.
void setAnchorWeight(double value)
std::vector< BinaryMeasurement< T > > maybeRobust(const std::vector< BinaryMeasurement< T >> &measurements, bool useRobustModel=false) const
double getGaugesWeight() const
size_t nrMeasurements() const
Return number of measurements.
Anchor anchor
pose to use as anchor if not Karcher
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const KeyVector & keys(size_t k) const
Keys for k^th measurement, as a vector of Key values.
Matrix computeA_(const Values &values) const
Dense version of computeA for wrapper/testing.
Matrix computeLambda_(const Matrix &S) const
Dense versions of computeLambda for wrapper/testing.
double optimalityThreshold
threshold used in checkOptimality
Measurements measurements_
static ConjugateGradientParameters parameters
void setGaugesWeight(double value)
const Rot & measured(size_t k) const
k^th measurement, as a Rot.
typedef and functions to augment Eigen's VectorXd
static SO Lift(size_t n, const Eigen::MatrixBase< Derived > &R)
Named constructor from lower dimensional matrix.
double getAnchorWeight() const
double getKarcherWeight() const
std::pair< size_t, Rot > getAnchor() const
Sparse D() const
Sparse version of D.
void setUseHuber(bool value)
void setAnchor(size_t index, const Rot &value)
void setCertifyOptimality(bool value)
LevenbergMarquardtParams getLMParams() const
static Values LiftTo(size_t p, const Values &values)
Lift Values of type T to SO(p)
Matrix denseL() const
Dense version of L.
void run(Expr &expr, Dev &dev)
Binary measurement represents a measurement between two keys in a graph. A binary measurement is simi...
utility functions for loading datasets
static shared_ptr Create(double k, const ReweightScheme reweight=Block)
Matrix denseQ() const
Dense version of Q.
noiseModel::Base::shared_ptr SharedNoiseModel
std::vector< BinaryMeasurement< Rot >> Measurements
3D rotation represented as a rotation matrix or quaternion
Filtered< Value > filter(const boost::function< bool(Key)> &filterFcn)