Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
gtsam::ShonanAveraging< d > Class Template Reference

#include <ShonanAveraging.h>

Public Types

using Measurements = std::vector< BinaryMeasurement< Rot >>
 
using Parameters = ShonanAveragingParameters< d >
 
using Rot = typename Parameters::Rot
 
using Sparse = Eigen::SparseMatrix< double >
 

Public Member Functions

template<typename T >
std::vector< BinaryMeasurement< T > > maybeRobust (const std::vector< BinaryMeasurement< T >> &measurements, bool useRobustModel=false) const
 
template<>
Values projectFrom (size_t p, const Values &values) const
 
template<>
Values projectFrom (size_t p, const Values &values) const
 
template<>
Values roundSolutionS (const Matrix &S) const
 
template<>
Values roundSolutionS (const Matrix &S) const
 
Standard Constructors
 ShonanAveraging (const Measurements &measurements, const Parameters &parameters=Parameters())
 
Query properties
size_t nrUnknowns () const
 Return number of unknowns. More...
 
size_t nrMeasurements () const
 Return number of measurements. More...
 
const BinaryMeasurement< Rot > & measurement (size_t k) const
 k^th binary measurement More...
 
Measurements makeNoiseModelRobust (const Measurements &measurements, double k=1.345) const
 
const Rotmeasured (size_t k) const
 k^th measurement, as a Rot. More...
 
const KeyVectorkeys (size_t k) const
 Keys for k^th measurement, as a vector of Key values. More...
 
Basic API
double cost (const Values &values) const
 
Values initializeRandomly (std::mt19937 &rng) const
 
Values initializeRandomly () const
 Random initialization for wrapper, fixed random seed. More...
 
std::pair< Values, double > run (const Values &initialEstimate, size_t pMin=d, size_t pMax=10) const
 

Private Member Functions

Sparse buildD () const
 Build 3Nx3N sparse degree matrix D. More...
 
Sparse buildQ () const
 

Private Attributes

Sparse D_
 
Sparse L_
 
Measurements measurements_
 
size_t nrUnknowns_
 
Parameters parameters_
 
Sparse Q_
 

Matrix API (advanced use, debugging)

Sparse D () const
 Sparse version of D. More...
 
Matrix denseD () const
 Dense version of D. More...
 
Sparse Q () const
 Sparse version of Q. More...
 
Matrix denseQ () const
 Dense version of Q. More...
 
Sparse L () const
 Sparse version of L. More...
 
Matrix denseL () const
 Dense version of L. More...
 
Sparse computeLambda (const Matrix &S) const
 Version that takes pxdN Stiefel manifold elements. More...
 
Matrix computeLambda_ (const Values &values) const
 Dense versions of computeLambda for wrapper/testing. More...
 
Matrix computeLambda_ (const Matrix &S) const
 Dense versions of computeLambda for wrapper/testing. More...
 
Sparse computeA (const Values &values) const
 Compute A matrix whose Eigenvalues we will examine. More...
 
Sparse computeA (const Matrix &S) const
 Version that takes pxdN Stiefel manifold elements. More...
 
Matrix computeA_ (const Values &values) const
 Dense version of computeA for wrapper/testing. More...
 
double computeMinEigenValue (const Values &values, Vector *minEigenVector=nullptr) const
 
double computeMinEigenValueAP (const Values &values, Vector *minEigenVector=nullptr) const
 
Values roundSolutionS (const Matrix &S) const
 Project pxdN Stiefel manifold matrix S to Rot3^N. More...
 
Matrix riemannianGradient (size_t p, const Values &values) const
 Calculate the riemannian gradient of F(values) at values. More...
 
Values initializeWithDescent (size_t p, const Values &values, const Vector &minEigenVector, double minEigenValue, double gradienTolerance=1e-2, double preconditionedGradNormTolerance=1e-4) const
 
static Matrix StiefelElementMatrix (const Values &values)
 Project to pxdN Stiefel manifold. More...
 
static VectorValues TangentVectorValues (size_t p, const Vector &v)
 Create a VectorValues with eigenvector v_i. More...
 
static Values LiftwithDescent (size_t p, const Values &values, const Vector &minEigenVector)
 

Advanced API

NonlinearFactorGraph buildGraphAt (size_t p) const
 
Values initializeRandomlyAt (size_t p, std::mt19937 &rng) const
 
Values initializeRandomlyAt (size_t p) const
 Version of initializeRandomlyAt with fixed random seed. More...
 
double costAt (size_t p, const Values &values) const
 
Sparse computeLambda (const Values &values) const
 
std::pair< double, VectorcomputeMinEigenVector (const Values &values) const
 
bool checkOptimality (const Values &values) const
 
boost::shared_ptr< LevenbergMarquardtOptimizercreateOptimizerAt (size_t p, const Values &initial) const
 
Values tryOptimizingAt (size_t p, const Values &initial) const
 
Values projectFrom (size_t p, const Values &values) const
 
Values roundSolution (const Values &values) const
 
template<class T >
static Values LiftTo (size_t p, const Values &values)
 Lift Values of type T to SO(p) More...
 

Detailed Description

template<size_t d>
class gtsam::ShonanAveraging< d >

Class that implements Shonan Averaging from our ECCV'20 paper. Note: The "basic" API uses all Rot values (Rot2 or Rot3, depending on value of d), whereas the different levels and "advanced" API at SO(p) needs Values of type SOn<Dynamic>.

The template parameter d can be 2 or 3. Both are specialized in the .cpp file.

If you use this code in your work, please consider citing our paper: Shonan Rotation Averaging, Global Optimality by Surfing SO(p)^n Frank Dellaert, David M. Rosen, Jing Wu, Robert Mahony, and Luca Carlone, European Computer Vision Conference, 2020. You can view our ECCV spotlight video at https://youtu.be/5ppaqMyHtE0

Definition at line 123 of file ShonanAveraging.h.

Member Typedef Documentation

template<size_t d>
using gtsam::ShonanAveraging< d >::Measurements = std::vector<BinaryMeasurement<Rot>>

Definition at line 132 of file ShonanAveraging.h.

template<size_t d>
using gtsam::ShonanAveraging< d >::Parameters = ShonanAveragingParameters<d>

Definition at line 128 of file ShonanAveraging.h.

template<size_t d>
using gtsam::ShonanAveraging< d >::Rot = typename Parameters::Rot

Definition at line 129 of file ShonanAveraging.h.

template<size_t d>
using gtsam::ShonanAveraging< d >::Sparse = Eigen::SparseMatrix<double>

Definition at line 125 of file ShonanAveraging.h.

Constructor & Destructor Documentation

template<size_t d>
gtsam::ShonanAveraging< d >::ShonanAveraging ( const Measurements measurements,
const Parameters parameters = Parameters() 
)

Construct from set of relative measurements (given as BetweenFactor<Rot3> for now) NoiseModel must be isotropic.

Definition at line 122 of file ShonanAveraging.cpp.

Member Function Documentation

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::buildD ( ) const
private

Build 3Nx3N sparse degree matrix D.

Definition at line 369 of file ShonanAveraging.cpp.

template<size_t d>
NonlinearFactorGraph gtsam::ShonanAveraging< d >::buildGraphAt ( size_t  p) const

Build graph for SO(p)

Parameters
pthe dimensionality of the rotation manifold to optimize over

Definition at line 143 of file ShonanAveraging.cpp.

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::buildQ ( ) const
private

Build 3Nx3N sparse matrix consisting of rotation measurements, arranged as (i,j) and (j,i) blocks within a sparse matrix.

Definition at line 404 of file ShonanAveraging.cpp.

template<size_t d>
bool gtsam::ShonanAveraging< d >::checkOptimality ( const Values values) const

Check optimality

Parameters
valuesshould be of type SOn

Definition at line 763 of file ShonanAveraging.cpp.

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::computeA ( const Values values) const

Compute A matrix whose Eigenvalues we will examine.

Definition at line 484 of file ShonanAveraging.cpp.

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::computeA ( const Matrix S) const

Version that takes pxdN Stiefel manifold elements.

Definition at line 493 of file ShonanAveraging.cpp.

template<size_t d>
Matrix gtsam::ShonanAveraging< d >::computeA_ ( const Values values) const
inline

Dense version of computeA for wrapper/testing.

Definition at line 242 of file ShonanAveraging.h.

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::computeLambda ( const Matrix S) const

Version that takes pxdN Stiefel manifold elements.

Definition at line 444 of file ShonanAveraging.cpp.

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::computeLambda ( const Values values) const

Given an estimated local minimum Yopt for the (possibly lifted) relaxation, this function computes and returns the block-diagonal elements of the corresponding Lagrange multiplier.

Definition at line 475 of file ShonanAveraging.cpp.

template<size_t d>
Matrix gtsam::ShonanAveraging< d >::computeLambda_ ( const Values values) const
inline

Dense versions of computeLambda for wrapper/testing.

Definition at line 226 of file ShonanAveraging.h.

template<size_t d>
Matrix gtsam::ShonanAveraging< d >::computeLambda_ ( const Matrix S) const
inline

Dense versions of computeLambda for wrapper/testing.

Definition at line 231 of file ShonanAveraging.h.

template<size_t d>
double gtsam::ShonanAveraging< d >::computeMinEigenValue ( const Values values,
Vector minEigenVector = nullptr 
) const

Compute minimum eigenvalue for optimality check.

Parameters
valuesshould be of type SOn

Definition at line 720 of file ShonanAveraging.cpp.

template<size_t d>
double gtsam::ShonanAveraging< d >::computeMinEigenValueAP ( const Values values,
Vector minEigenVector = nullptr 
) const

Compute minimum eigenvalue with accelerated power method.

Parameters
valuesshould be of type SOn

Definition at line 737 of file ShonanAveraging.cpp.

template<size_t d>
std::pair< double, Vector > gtsam::ShonanAveraging< d >::computeMinEigenVector ( const Values values) const

Compute minimum eigenvalue for optimality check.

Parameters
valuesshould be of type SOn
Returns
minEigenVector and minEigenValue

Definition at line 754 of file ShonanAveraging.cpp.

template<size_t d>
double gtsam::ShonanAveraging< d >::cost ( const Values values) const

Calculate cost for SO(3) Values should be of type Rot3

Definition at line 318 of file ShonanAveraging.cpp.

template<size_t d>
double gtsam::ShonanAveraging< d >::costAt ( size_t  p,
const Values values 
) const

Calculate cost for SO(p) Values should be of type SO(p)

Definition at line 168 of file ShonanAveraging.cpp.

template<size_t d>
boost::shared_ptr< LevenbergMarquardtOptimizer > gtsam::ShonanAveraging< d >::createOptimizerAt ( size_t  p,
const Values initial 
) const

Try to create optimizer at SO(p)

Parameters
pthe dimensionality of the rotation manifold to optimize over
initialinitial SO(p) values
Returns
lm optimizer

Definition at line 176 of file ShonanAveraging.cpp.

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::D ( ) const
inline

Sparse version of D.

Definition at line 215 of file ShonanAveraging.h.

template<size_t d>
Matrix gtsam::ShonanAveraging< d >::denseD ( ) const
inline

Dense version of D.

Definition at line 216 of file ShonanAveraging.h.

template<size_t d>
Matrix gtsam::ShonanAveraging< d >::denseL ( ) const
inline

Dense version of L.

Definition at line 220 of file ShonanAveraging.h.

template<size_t d>
Matrix gtsam::ShonanAveraging< d >::denseQ ( ) const
inline

Dense version of Q.

Definition at line 218 of file ShonanAveraging.h.

template<size_t d>
Values gtsam::ShonanAveraging< d >::initializeRandomly ( std::mt19937 &  rng) const

Initialize randomly at SO(d)

Parameters
rngrandom number generator Example: std::mt19937 rng(42); Values initial = initializeRandomly(rng, p);

Definition at line 866 of file ShonanAveraging.cpp.

template<size_t d>
Values gtsam::ShonanAveraging< d >::initializeRandomly ( ) const

Random initialization for wrapper, fixed random seed.

Definition at line 876 of file ShonanAveraging.cpp.

template<size_t d>
Values gtsam::ShonanAveraging< d >::initializeRandomlyAt ( size_t  p,
std::mt19937 &  rng 
) const

Create initial Values of type SO(p)

Parameters
pthe dimensionality of the rotation manifold

Definition at line 882 of file ShonanAveraging.cpp.

template<size_t d>
Values gtsam::ShonanAveraging< d >::initializeRandomlyAt ( size_t  p) const

Version of initializeRandomlyAt with fixed random seed.

Definition at line 890 of file ShonanAveraging.cpp.

template<size_t d>
Values gtsam::ShonanAveraging< d >::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, computed from the minimum eigenvector at p-1.

Parameters
valuesshould be of type SO(p-1)
minEigenVectorcorresponding to minEigenValue at level p-1
Returns
values of type SO(p)

Definition at line 827 of file ShonanAveraging.cpp.

template<size_t d>
const KeyVector& gtsam::ShonanAveraging< d >::keys ( size_t  k) const
inline

Keys for k^th measurement, as a vector of Key values.

Definition at line 209 of file ShonanAveraging.h.

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::L ( ) const
inline

Sparse version of L.

Definition at line 219 of file ShonanAveraging.h.

template<size_t d>
template<class T >
static Values gtsam::ShonanAveraging< d >::LiftTo ( size_t  p,
const Values values 
)
inlinestatic

Lift Values of type T to SO(p)

Definition at line 366 of file ShonanAveraging.h.

template<size_t d>
Values gtsam::ShonanAveraging< d >::LiftwithDescent ( size_t  p,
const Values values,
const Vector minEigenVector 
)
static

Lift up the dimension of values in type SO(p-1) with descent direction provided by minEigenVector and return new values in type SO(p)

Definition at line 818 of file ShonanAveraging.cpp.

template<size_t d>
Measurements gtsam::ShonanAveraging< d >::makeNoiseModelRobust ( const Measurements measurements,
double  k = 1.345 
) const
inline

Update factors to use robust Huber loss.

Parameters
measurementsVector of BinaryMeasurements.
kHuber noise model threshold.

Definition at line 181 of file ShonanAveraging.h.

template<size_t d>
template<typename T >
std::vector<BinaryMeasurement<T> > gtsam::ShonanAveraging< d >::maybeRobust ( const std::vector< BinaryMeasurement< T >> &  measurements,
bool  useRobustModel = false 
) const
inline

Helper function to convert measurements to robust noise model if flag is set.

Template Parameters
Tthe type of measurement, e.g. Rot3.
Parameters
measurementsvector of BinaryMeasurements of type T.
useRobustModelflag indicating whether use robust noise model instead.

Definition at line 417 of file ShonanAveraging.h.

template<size_t d>
const Rot& gtsam::ShonanAveraging< d >::measured ( size_t  k) const
inline

k^th measurement, as a Rot.

Definition at line 206 of file ShonanAveraging.h.

template<size_t d>
const BinaryMeasurement<Rot>& gtsam::ShonanAveraging< d >::measurement ( size_t  k) const
inline

k^th binary measurement

Definition at line 171 of file ShonanAveraging.h.

template<size_t d>
size_t gtsam::ShonanAveraging< d >::nrMeasurements ( ) const
inline

Return number of measurements.

Definition at line 168 of file ShonanAveraging.h.

template<size_t d>
size_t gtsam::ShonanAveraging< d >::nrUnknowns ( ) const
inline

Return number of unknowns.

Definition at line 165 of file ShonanAveraging.h.

template<>
Values gtsam::ShonanAveraging< 2 >::projectFrom ( size_t  p,
const Values values 
) const

Definition at line 219 of file ShonanAveraging.cpp.

template<>
Values gtsam::ShonanAveraging< 3 >::projectFrom ( size_t  p,
const Values values 
) const

Definition at line 231 of file ShonanAveraging.cpp.

template<size_t d>
Values gtsam::ShonanAveraging< d >::projectFrom ( size_t  p,
const Values values 
) const

Project from SO(p) to Rot2 or Rot3 Values should be of type SO(p)

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::Q ( ) const
inline

Sparse version of Q.

Definition at line 217 of file ShonanAveraging.h.

template<size_t d>
Matrix gtsam::ShonanAveraging< d >::riemannianGradient ( size_t  p,
const Values values 
) const

Calculate the riemannian gradient of F(values) at values.

Definition at line 792 of file ShonanAveraging.cpp.

template<size_t d>
Values gtsam::ShonanAveraging< d >::roundSolution ( const Values values) const

Project from SO(p)^N to Rot2^N or Rot3^N Values should be of type SO(p)

Definition at line 309 of file ShonanAveraging.cpp.

template<size_t d>
Values gtsam::ShonanAveraging< d >::roundSolutionS ( const Matrix S) const

Project pxdN Stiefel manifold matrix S to Rot3^N.

template<>
Values gtsam::ShonanAveraging< 2 >::roundSolutionS ( const Matrix S) const

Definition at line 280 of file ShonanAveraging.cpp.

template<>
Values gtsam::ShonanAveraging< 3 >::roundSolutionS ( const Matrix S) const

Definition at line 294 of file ShonanAveraging.cpp.

template<size_t d>
std::pair< Values, double > gtsam::ShonanAveraging< d >::run ( const Values initialEstimate,
size_t  pMin = d,
size_t  pMax = 10 
) const

Optimize at different values of p until convergence.

Parameters
initialinitial Rot3 values
pMinvalue of p to start Riemanian staircase at (default: d).
pMaxmaximum value of p to try (default: 10)
Returns
(Rot3 values, minimum eigenvalue)

Definition at line 896 of file ShonanAveraging.cpp.

template<size_t d>
Matrix gtsam::ShonanAveraging< d >::StiefelElementMatrix ( const Values values)
static

Project to pxdN Stiefel manifold.

Definition at line 206 of file ShonanAveraging.cpp.

template<size_t d>
VectorValues gtsam::ShonanAveraging< d >::TangentVectorValues ( size_t  p,
const Vector v 
)
static

Create a VectorValues with eigenvector v_i.

Definition at line 770 of file ShonanAveraging.cpp.

template<size_t d>
Values gtsam::ShonanAveraging< d >::tryOptimizingAt ( size_t  p,
const Values initial 
) const

Try to optimize at SO(p)

Parameters
pthe dimensionality of the rotation manifold to optimize over
initialinitial SO(p) values
Returns
SO(p) values

Definition at line 197 of file ShonanAveraging.cpp.

Member Data Documentation

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::D_
private

Definition at line 138 of file ShonanAveraging.h.

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::L_
private

Definition at line 140 of file ShonanAveraging.h.

template<size_t d>
Measurements gtsam::ShonanAveraging< d >::measurements_
private

Definition at line 136 of file ShonanAveraging.h.

template<size_t d>
size_t gtsam::ShonanAveraging< d >::nrUnknowns_
private

Definition at line 137 of file ShonanAveraging.h.

template<size_t d>
Parameters gtsam::ShonanAveraging< d >::parameters_
private

Definition at line 135 of file ShonanAveraging.h.

template<size_t d>
Sparse gtsam::ShonanAveraging< d >::Q_
private

Definition at line 139 of file ShonanAveraging.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:27