Protected Attributes | List of all members
gtsam::PowerMethod< Operator > Class Template Reference

Compute maximum Eigenpair with power method. More...

#include <PowerMethod.h>

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

Public Member Functions

Standard Constructors
 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...
 

Protected Attributes

const Operator & A_
 
const int dim_
 
size_t nrIterations_
 
double ritzValue_
 
Vector ritzVector_
 

Detailed Description

template<class Operator>
class gtsam::PowerMethod< Operator >

Compute maximum Eigenpair with 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 $ 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 57 of file PowerMethod.h.

Constructor & Destructor Documentation

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

Construct from the aim matrix and intial ritz vector.

Definition at line 77 of file PowerMethod.h.

Member Function Documentation

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

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

Definition at line 129 of file PowerMethod.h.

template<class Operator>
bool gtsam::PowerMethod< Operator >::converged ( double  tol) const
inline

After Perform power iteration on a single Ritz value, check if the Ritz residual for the current Ritz pair is less than the required convergence tol, return true if yes, else false

Definition at line 112 of file PowerMethod.h.

template<class Operator>
double gtsam::PowerMethod< Operator >::eigenvalue ( ) const
inline

Return the eigenvalue.

Definition at line 146 of file PowerMethod.h.

template<class Operator>
Vector gtsam::PowerMethod< Operator >::eigenvector ( ) const
inline

Return the eigenvector.

Definition at line 149 of file PowerMethod.h.

template<class Operator>
size_t gtsam::PowerMethod< Operator >::nrIterations ( ) const
inline

Return the number of iterations.

Definition at line 121 of file PowerMethod.h.

template<class Operator>
Vector gtsam::PowerMethod< Operator >::powerIteration ( const Vector x) const
inline

Run power iteration to get ritzVector with previous ritzVector x, and return A * x / || A * x ||

Definition at line 95 of file PowerMethod.h.

template<class Operator>
Vector gtsam::PowerMethod< Operator >::powerIteration ( ) const
inline

Run power iteration to get ritzVector with previous ritzVector x, and return A * x / || A * x ||

Definition at line 105 of file PowerMethod.h.

Member Data Documentation

template<class Operator>
const Operator& gtsam::PowerMethod< Operator >::A_
protected

Const reference to an externally-held matrix whose minimum-eigenvalue we want to compute

Definition at line 63 of file PowerMethod.h.

template<class Operator>
const int gtsam::PowerMethod< Operator >::dim_
protected

Definition at line 65 of file PowerMethod.h.

template<class Operator>
size_t gtsam::PowerMethod< Operator >::nrIterations_
protected

Definition at line 67 of file PowerMethod.h.

template<class Operator>
double gtsam::PowerMethod< Operator >::ritzValue_
protected

Definition at line 69 of file PowerMethod.h.

template<class Operator>
Vector gtsam::PowerMethod< Operator >::ritzVector_
protected

Definition at line 70 of file PowerMethod.h.


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


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