Public Member Functions | Private Attributes | List of all members
gtsam::AcceleratedPowerMethod< Operator > Class Template Reference

Compute maximum Eigenpair with accelerated power method. More...

#include <AcceleratedPowerMethod.h>

Inheritance diagram for gtsam::AcceleratedPowerMethod< Operator >:
Inheritance graph
[legend]

Public Member Functions

Vector acceleratedPowerIteration (const Vector &x1, const Vector &x0, const double beta) const
 
Vector acceleratedPowerIteration () const
 
 AcceleratedPowerMethod (const Operator &A, const boost::optional< Vector > initial=boost::none, double initialBeta=0.0)
 
bool compute (size_t maxIterations, double tol)
 
double estimateBeta (const size_t T=10) const
 
- Public Member Functions inherited from gtsam::PowerMethod< Operator >
 PowerMethod (const Operator &A, const boost::optional< Vector > initial=boost::none)
 Construct from the aim matrix and intial ritz vector. More...
 
Vector powerIteration (const Vector &x) const
 
Vector powerIteration () const
 
bool converged (double tol) const
 
size_t nrIterations () const
 Return the number of iterations. More...
 
bool compute (size_t maxIterations, double tol)
 
double eigenvalue () const
 Return the eigenvalue. More...
 
Vector eigenvector () const
 Return the eigenvector. More...
 

Private Attributes

double beta_ = 0
 
Vector previousVector_
 

Additional Inherited Members

- Protected Attributes inherited from gtsam::PowerMethod< Operator >
const Operator & A_
 
const int dim_
 
size_t nrIterations_
 
double ritzValue_
 
Vector ritzVector_
 

Detailed Description

template<class Operator>
class gtsam::AcceleratedPowerMethod< Operator >

Compute maximum Eigenpair with accelerated power method.

References : 1) G. Golub and C. V. Loan, Matrix Computations, 3rd ed. Baltimore, Johns Hopkins University Press, 1996, pp.405-411 2) Rosen, D. and Carlone, L., 2017, September. Computational enhancements for certifiably correct SLAM. In Proceedings of the International Conference on Intelligent Robots and Systems. 3) Yulun Tian and Kasra Khosoussi and David M. Rosen and Jonathan P. How, 2020, Aug, Distributed Certifiably Correct Pose-Graph Optimization, Arxiv 4) C. de Sa, B. He, I. Mitliagkas, C. Ré, and P. Xu, “Accelerated stochastic power iteration,” in Proc. Mach. Learn. Res., no. 84, 2018, pp. 58–67

It performs the following iteration: $ x_{k+1} = A * x_k - \beta * x_{k-1} $ where A is the aim matrix we want to get eigenpair of, x is the Ritz vector

Template argument Operator just needs multiplication operator

Definition at line 51 of file AcceleratedPowerMethod.h.

Constructor & Destructor Documentation

template<class Operator>
gtsam::AcceleratedPowerMethod< Operator >::AcceleratedPowerMethod ( const Operator &  A,
const boost::optional< Vector initial = boost::none,
double  initialBeta = 0.0 
)
inlineexplicit

Constructor from aim matrix A (given as Matrix or Sparse), optional intial vector as ritzVector

Definition at line 62 of file AcceleratedPowerMethod.h.

Member Function Documentation

template<class Operator>
Vector gtsam::AcceleratedPowerMethod< Operator >::acceleratedPowerIteration ( const Vector x1,
const Vector x0,
const double  beta 
) const
inline

Run accelerated power iteration to get ritzVector with beta and previous two ritzVector x0 and x00, and return y = (A * x0 - * x00) / || A * x0

  • * x00 ||

Definition at line 80 of file AcceleratedPowerMethod.h.

template<class Operator>
Vector gtsam::AcceleratedPowerMethod< Operator >::acceleratedPowerIteration ( ) const
inline

Run accelerated power iteration to get ritzVector with beta and previous two ritzVector x0 and x00, and return y = (A * x0 - * x00) / || A * x0

  • * x00 ||

Definition at line 92 of file AcceleratedPowerMethod.h.

template<class Operator>
bool gtsam::AcceleratedPowerMethod< Operator >::compute ( size_t  maxIterations,
double  tol 
)
inline

Start the accelerated iteration, after performing the accelerated iteration, calculate the ritz error, repeat this operation until the ritz error converge. If converged return true, else false.

Definition at line 156 of file AcceleratedPowerMethod.h.

template<class Operator>
double gtsam::AcceleratedPowerMethod< Operator >::estimateBeta ( const size_t  T = 10) const
inline

Tuning the momentum beta using the Best Heavy Ball algorithm in Ref(3), T is the iteration time to find beta with largest Rayleigh quotient

Definition at line 101 of file AcceleratedPowerMethod.h.

Member Data Documentation

template<class Operator>
double gtsam::AcceleratedPowerMethod< Operator >::beta_ = 0
private

Definition at line 53 of file AcceleratedPowerMethod.h.

template<class Operator>
Vector gtsam::AcceleratedPowerMethod< Operator >::previousVector_
private

Definition at line 55 of file AcceleratedPowerMethod.h.


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


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