#include <LOBPCGSolver.h>
Public Member Functions | |
void | compute (int maxit=10, Scalar tol_div_n=1e-7) |
Vector | eigenvalues () |
Matrix | eigenvectors () |
int | info () |
LOBPCGSolver (const SparseMatrix &A, const SparseMatrix X) | |
Matrix | residuals () |
void | setB (const SparseMatrix &B) |
void | setConstraints (const SparseMatrix &Y) |
void | setPreconditioner (const SparseMatrix &preconditioner) |
Public Attributes | |
Vector | m_evalues |
Matrix | m_evectors |
int | m_info |
SparseMatrix | m_residuals |
Private Types | |
typedef std::complex< Scalar > | Complex |
typedef Eigen::Matrix< Complex, Eigen::Dynamic, Eigen::Dynamic > | ComplexMatrix |
typedef Eigen::Matrix< Complex, Eigen::Dynamic, 1 > | ComplexVector |
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > | Matrix |
typedef Eigen::SparseMatrix< Complex > | SparseComplexMatrix |
typedef Eigen::SparseMatrix< Scalar > | SparseMatrix |
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > | Vector |
Private Member Functions | |
void | applyConstraintsInPlace (SparseMatrix &X, SparseMatrix &Y, SparseMatrix &B) |
int | checkConvergence_getBlocksize (SparseMatrix &m_residuals, Scalar tolerance_L2, std::vector< int > &columnsToDelete) |
int | orthogonalizeInPlace (SparseMatrix &M, SparseMatrix &B, SparseMatrix &true_BM, bool has_true_BM=false) |
void | removeColumns (SparseMatrix &matrix, std::vector< int > &colToRemove) |
void | sort_epairs (Vector &evalues, Matrix &evectors, int SelectionRule) |
Matrix | stack_4_matricies (Matrix A, Matrix B, Matrix C, Matrix D) |
Matrix | stack_9_matricies (Matrix A, Matrix B, Matrix C, Matrix D, Matrix E, Matrix F, Matrix G, Matrix H, Matrix I) |
Private Attributes | |
SparseMatrix | A |
bool | flag_with_B |
bool | flag_with_constraints |
bool | flag_with_preconditioner |
SparseMatrix | m_B |
const int | m_n |
const int | m_nev |
SparseMatrix | m_preconditioner |
SparseMatrix | m_Y |
SparseMatrix | X |
*** METHOD The class represent the LOBPCG algorithm, which was invented by Andrew Knyazev Theoretical background of the procedure can be found in the articles below
*** CONDITIONS OF USE Locally Optimal Block Preconditioned Conjugate Gradient(LOBPCG) is a method for finding the M smallest eigenvalues and eigenvectors of a large symmetric positive definite generalized eigenvalue problem where is a symmetric matrix, is symmetric and positive - definite. are also assumed large and sparse should be (at least )
*** ARGUMENTS Eigen::SparseMatrix<long double> A; // N*N - Ax = lambda*Bx, lrage and sparse Eigen::SparseMatrix<long double> X; // N*M - initial approximations to eigenvectors (random in general case) Spectra::LOBPCGSolver<long double> solver(A, X); *Eigen::SparseMatrix<long double> B; // N*N - Ax = lambda*Bx, sparse, positive definite solver.setConstraints(B); *Eigen::SparseMatrix<long double> Y; // N*K - constraints, already found eigenvectors solver.setB(B); *Eigen::SparseMatrix<long double> T; // N*N - preconditioner ~ A^-1 solver.setPreconditioner(T);
*** OUTCOMES solver.solve(); // compute eigenpairs // void solver.info(); // state of converjance // int solver.residuals(); // get residuals to evaluate biases // Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> solver.eigenvalues(); // get eigenvalues // Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> solver.eigenvectors(); // get eigenvectors // Eigen::Matrix<Scalar, Eigen::Dynamic, 1>
*** EXAMPLE
Definition at line 83 of file LOBPCGSolver.h.
|
private |
Definition at line 89 of file LOBPCGSolver.h.
|
private |
Definition at line 90 of file LOBPCGSolver.h.
|
private |
Definition at line 91 of file LOBPCGSolver.h.
|
private |
Definition at line 86 of file LOBPCGSolver.h.
|
private |
Definition at line 94 of file LOBPCGSolver.h.
|
private |
Definition at line 93 of file LOBPCGSolver.h.
|
private |
Definition at line 87 of file LOBPCGSolver.h.
|
inline |
Definition at line 291 of file LOBPCGSolver.h.
|
inlineprivate |
Definition at line 170 of file LOBPCGSolver.h.
|
inlineprivate |
Definition at line 266 of file LOBPCGSolver.h.
|
inline |
Definition at line 328 of file LOBPCGSolver.h.
|
inline |
Definition at line 532 of file LOBPCGSolver.h.
|
inline |
Definition at line 537 of file LOBPCGSolver.h.
|
inline |
Definition at line 547 of file LOBPCGSolver.h.
|
inlineprivate |
Definition at line 110 of file LOBPCGSolver.h.
|
inlineprivate |
Definition at line 245 of file LOBPCGSolver.h.
|
inline |
Definition at line 542 of file LOBPCGSolver.h.
|
inline |
Definition at line 314 of file LOBPCGSolver.h.
|
inline |
Definition at line 308 of file LOBPCGSolver.h.
|
inline |
Definition at line 322 of file LOBPCGSolver.h.
|
inlineprivate |
Definition at line 224 of file LOBPCGSolver.h.
|
inlineprivate |
Definition at line 195 of file LOBPCGSolver.h.
|
inlineprivate |
Definition at line 206 of file LOBPCGSolver.h.
|
private |
Definition at line 98 of file LOBPCGSolver.h.
|
private |
Definition at line 100 of file LOBPCGSolver.h.
|
private |
Definition at line 100 of file LOBPCGSolver.h.
|
private |
Definition at line 100 of file LOBPCGSolver.h.
|
private |
Definition at line 99 of file LOBPCGSolver.h.
Vector Spectra::LOBPCGSolver< Scalar >::m_evalues |
Definition at line 105 of file LOBPCGSolver.h.
Matrix Spectra::LOBPCGSolver< Scalar >::m_evectors |
Definition at line 104 of file LOBPCGSolver.h.
int Spectra::LOBPCGSolver< Scalar >::m_info |
Definition at line 106 of file LOBPCGSolver.h.
|
private |
Definition at line 96 of file LOBPCGSolver.h.
|
private |
Definition at line 97 of file LOBPCGSolver.h.
|
private |
Definition at line 99 of file LOBPCGSolver.h.
SparseMatrix Spectra::LOBPCGSolver< Scalar >::m_residuals |
Definition at line 103 of file LOBPCGSolver.h.
|
private |
Definition at line 99 of file LOBPCGSolver.h.
|
private |
Definition at line 98 of file LOBPCGSolver.h.