Compute maximum Eigenpair with power method. More...
#include <PowerMethod.h>
Public Member Functions | |
Standard Constructors | |
PowerMethod (const Operator &A, const std::optional< Vector > initial={}) | |
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_ |
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: 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 58 of file PowerMethod.h.
|
inlineexplicit |
Construct from the aim matrix and intial ritz vector.
Definition at line 78 of file PowerMethod.h.
|
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 130 of file PowerMethod.h.
|
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 113 of file PowerMethod.h.
|
inline |
Return the eigenvalue.
Definition at line 147 of file PowerMethod.h.
|
inline |
Return the eigenvector.
Definition at line 150 of file PowerMethod.h.
|
inline |
Return the number of iterations.
Definition at line 122 of file PowerMethod.h.
|
inline |
Run power iteration to get ritzVector with previous ritzVector x, and return A * x / || A * x ||
Definition at line 106 of file PowerMethod.h.
|
inline |
Run power iteration to get ritzVector with previous ritzVector x, and return A * x / || A * x ||
Definition at line 96 of file PowerMethod.h.
|
protected |
Const reference to an externally-held matrix whose minimum-eigenvalue we want to compute
Definition at line 64 of file PowerMethod.h.
|
protected |
Definition at line 66 of file PowerMethod.h.
|
protected |
Definition at line 68 of file PowerMethod.h.
|
protected |
Definition at line 70 of file PowerMethod.h.
|
protected |
Definition at line 71 of file PowerMethod.h.