Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType > Class Template Reference

#include <SymEigsBase.h>

Public Member Functions

Index compute (Index maxit=1000, Scalar tol=1e-10, int sort_rule=LARGEST_ALGE)
 
Vector eigenvalues () const
 
virtual Matrix eigenvectors (Index nvec) const
 
virtual Matrix eigenvectors () const
 
int info () const
 
void init (const Scalar *init_resid)
 
void init ()
 
Index num_iterations () const
 
Index num_operations () const
 

Protected Member Functions

virtual void sort_ritzpair (int sort_rule)
 

Protected Attributes

LanczosFac m_fac
 
const Index m_n
 
const Index m_ncv
 
const Index m_nev
 
Index m_niter
 
Index m_nmatop
 
OpType * m_op
 
Vector m_ritz_val
 

Private Types

typedef ArnoldiOp< Scalar, OpType, BOpType > ArnoldiOpType
 
typedef Eigen::Array< Scalar, Eigen::Dynamic, 1 > Array
 
typedef Eigen::Array< bool, Eigen::Dynamic, 1 > BoolArray
 
typedef Eigen::Index Index
 
typedef Lanczos< Scalar, ArnoldiOpTypeLanczosFac
 
typedef Eigen::Map< const VectorMapConstVec
 
typedef Eigen::Map< MatrixMapMat
 
typedef Eigen::Map< VectorMapVec
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::DynamicMatrix
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
 

Private Member Functions

Index nev_adjusted (Index nconv)
 
Index num_converged (Scalar tol)
 
void restart (Index k)
 
void retrieve_ritzpair ()
 

Private Attributes

const Scalar m_eps
 
const Scalar m_eps23
 
int m_info
 
const Scalar m_near_0
 
BoolArray m_ritz_conv
 
Vector m_ritz_est
 
Matrix m_ritz_vec
 

Detailed Description

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
class Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >

This is the base class for symmetric eigen solvers, mainly for internal use. It is kept here to provide the documentation for member functions of concrete eigen solvers such as SymEigsSolver and SymEigsShiftSolver.

Definition at line 44 of file SymEigsBase.h.

Member Typedef Documentation

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef ArnoldiOp<Scalar, OpType, BOpType> Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::ArnoldiOpType
private

Definition at line 56 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Eigen::Array<Scalar, Eigen::Dynamic, 1> Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::Array
private

Definition at line 50 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Eigen::Array<bool, Eigen::Dynamic, 1> Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::BoolArray
private

Definition at line 51 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Eigen::Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::Index
private

Definition at line 47 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Lanczos<Scalar, ArnoldiOpType> Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::LanczosFac
private

Definition at line 57 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Eigen::Map<const Vector> Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::MapConstVec
private

Definition at line 54 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Eigen::Map<Matrix> Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::MapMat
private

Definition at line 52 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Eigen::Map<Vector> Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::MapVec
private

Definition at line 53 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::Matrix
private

Definition at line 48 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1> Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::Vector
private

Definition at line 49 of file SymEigsBase.h.

Member Function Documentation

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::compute ( Index  maxit = 1000,
Scalar  tol = 1e-10,
int  sort_rule = LARGEST_ALGE 
)
inline

Conducts the major computation procedure.

Parameters
maxitMaximum number of iterations allowed in the algorithm.
tolPrecision parameter for the calculated eigenvalues.
sort_ruleRule to sort the eigenvalues and eigenvectors. Supported values are Spectra::LARGEST_ALGE, Spectra::LARGEST_MAGN, Spectra::SMALLEST_ALGE and Spectra::SMALLEST_MAGN, for example LARGEST_ALGE indicates that largest eigenvalues come first. Note that this argument is only used to sort the final result, and the selection rule (e.g. selecting the largest or smallest eigenvalues in the full spectrum) is specified by the template parameter SelectionRule of SymEigsSolver.
Returns
Number of converged eigenvalues.

Definition at line 334 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Vector Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::eigenvalues ( ) const
inline

Returns the converged eigenvalues.

Returns
A vector containing the eigenvalues. Returned vector type will be Eigen::Vector<Scalar, ...>, depending on the template parameter Scalar defined.

Definition at line 382 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
virtual Matrix Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::eigenvectors ( Index  nvec) const
inlinevirtual

Returns the eigenvectors associated with the converged eigenvalues.

Parameters
nvecThe number of eigenvectors to return.
Returns
A matrix containing the eigenvectors. Returned matrix type will be Eigen::Matrix<Scalar, ...>, depending on the template parameter Scalar defined.

Definition at line 412 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
virtual Matrix Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::eigenvectors ( ) const
inlinevirtual

Returns all converged eigenvectors.

Definition at line 440 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
int Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::info ( ) const
inline

Returns the status of the computation. The full list of enumeration values can be found in Enumerations.

Definition at line 363 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
void Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::init ( const Scalar init_resid)
inline

Initializes the solver by providing an initial residual vector.

Parameters
init_residPointer to the initial residual vector.

Spectra (and also ARPACK) uses an iterative algorithm to find eigenvalues. This function allows the user to provide the initial residual vector.

Definition at line 281 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
void Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::init ( )
inline

Initializes the solver by providing a random initial residual vector.

This overloaded function generates a random initial residual vector (with a fixed random seed) for the algorithm. Elements in the vector follow independent Uniform(-0.5, 0.5) distribution.

Definition at line 309 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::nev_adjusted ( Index  nconv)
inlineprivate

Definition at line 125 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::num_converged ( Scalar  tol)
inlineprivate

Definition at line 113 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::num_iterations ( ) const
inline

Returns the number of iterations used in the computation.

Definition at line 368 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::num_operations ( ) const
inline

Returns the number of matrix operations used in the computation.

Definition at line 373 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
void Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::restart ( Index  k)
inlineprivate

Definition at line 85 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
void Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::retrieve_ritzpair ( )
inlineprivate

Definition at line 148 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
virtual void Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::sort_ritzpair ( int  sort_rule)
inlineprotectedvirtual

Member Data Documentation

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
const Scalar Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_eps
private

Definition at line 80 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
const Scalar Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_eps23
private

Definition at line 81 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
LanczosFac Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_fac
protected

Definition at line 69 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
int Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_info
private

Definition at line 76 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
const Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_n
protected

Definition at line 63 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
const Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_ncv
protected

Definition at line 65 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
const Scalar Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_near_0
private

Definition at line 78 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
const Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_nev
protected

Definition at line 64 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_niter
protected

Definition at line 67 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Index Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_nmatop
protected

Definition at line 66 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
OpType* Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_op
protected

Definition at line 61 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
BoolArray Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_ritz_conv
private

Definition at line 75 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Vector Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_ritz_est
private

Definition at line 74 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Vector Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_ritz_val
protected

Definition at line 70 of file SymEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Matrix Spectra::SymEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_ritz_vec
private

Definition at line 73 of file SymEigsBase.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:59:21