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

#include <GenEigsBase.h>

Public Member Functions

Index compute (Index maxit=1000, Scalar tol=1e-10, int sort_rule=LARGEST_MAGN)
 
ComplexVector eigenvalues () const
 
ComplexMatrix eigenvectors (Index nvec) const
 
ComplexMatrix 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

ArnoldiFac m_fac
 
const Index m_n
 
const Index m_ncv
 
const Index m_nev
 
Index m_niter
 
Index m_nmatop
 
OpType * m_op
 
ComplexVector m_ritz_est
 
ComplexVector m_ritz_val
 
ComplexMatrix m_ritz_vec
 

Private Types

typedef Arnoldi< Scalar, ArnoldiOpTypeArnoldiFac
 
typedef ArnoldiOp< Scalar, OpType, BOpType > ArnoldiOpType
 
typedef Eigen::Array< Scalar, Eigen::Dynamic, 1 > Array
 
typedef Eigen::Array< bool, Eigen::Dynamic, 1 > BoolArray
 
typedef std::complex< ScalarComplex
 
typedef Eigen::Matrix< Complex, Eigen::Dynamic, Eigen::DynamicComplexMatrix
 
typedef Eigen::Matrix< Complex, Eigen::Dynamic, 1 > ComplexVector
 
typedef Eigen::Index Index
 
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 ()
 

Static Private Member Functions

static bool is_complex (const Complex &v)
 
static bool is_conj (const Complex &v1, const Complex &v2)
 

Private Attributes

const Scalar m_eps
 
const Scalar m_eps23
 
int m_info
 
const Scalar m_near_0
 
BoolArray m_ritz_conv
 

Detailed Description

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

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

Definition at line 40 of file GenEigsBase.h.

Member Typedef Documentation

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Arnoldi<Scalar, ArnoldiOpType> Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::ArnoldiFac
private

Definition at line 57 of file GenEigsBase.h.

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

Definition at line 56 of file GenEigsBase.h.

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

Definition at line 46 of file GenEigsBase.h.

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

Definition at line 47 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef std::complex<Scalar> Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::Complex
private

Definition at line 52 of file GenEigsBase.h.

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

Definition at line 53 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
typedef Eigen::Matrix<Complex, Eigen::Dynamic, 1> Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::ComplexVector
private

Definition at line 54 of file GenEigsBase.h.

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

Definition at line 43 of file GenEigsBase.h.

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

Definition at line 50 of file GenEigsBase.h.

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

Definition at line 48 of file GenEigsBase.h.

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

Definition at line 49 of file GenEigsBase.h.

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

Definition at line 44 of file GenEigsBase.h.

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

Definition at line 45 of file GenEigsBase.h.

Member Function Documentation

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
Index Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::compute ( Index  maxit = 1000,
Scalar  tol = 1e-10,
int  sort_rule = LARGEST_MAGN 
)
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_MAGN, Spectra::LARGEST_REAL, Spectra::LARGEST_IMAG, Spectra::SMALLEST_MAGN, Spectra::SMALLEST_REAL and Spectra::SMALLEST_IMAG, for example LARGEST_MAGN indicates that eigenvalues with largest magnitude 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 GenEigsSolver.
Returns
Number of converged eigenvalues.

Definition at line 368 of file GenEigsBase.h.

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

Returns the converged eigenvalues.

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

Definition at line 416 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
ComplexMatrix Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::eigenvectors ( Index  nvec) const
inline

Returns the eigenvectors associated with the converged eigenvalues.

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

Definition at line 446 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
ComplexMatrix Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::eigenvectors ( ) const
inline

Returns all converged eigenvectors.

Definition at line 474 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
int Spectra::GenEigsBase< 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 397 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
void Spectra::GenEigsBase< 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 313 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
void Spectra::GenEigsBase< 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 341 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
static bool Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::is_complex ( const Complex v)
inlinestaticprivate

Definition at line 88 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
static bool Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::is_conj ( const Complex v1,
const Complex v2 
)
inlinestaticprivate

Definition at line 89 of file GenEigsBase.h.

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

Definition at line 159 of file GenEigsBase.h.

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

Definition at line 147 of file GenEigsBase.h.

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

Returns the number of iterations used in the computation.

Definition at line 402 of file GenEigsBase.h.

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

Returns the number of matrix operations used in the computation.

Definition at line 407 of file GenEigsBase.h.

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

Definition at line 92 of file GenEigsBase.h.

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

Definition at line 190 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
virtual void Spectra::GenEigsBase< 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::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_eps
private

Definition at line 81 of file GenEigsBase.h.

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

Definition at line 82 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
ArnoldiFac Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_fac
protected

Definition at line 69 of file GenEigsBase.h.

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

Definition at line 77 of file GenEigsBase.h.

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

Definition at line 63 of file GenEigsBase.h.

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

Definition at line 65 of file GenEigsBase.h.

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

Definition at line 79 of file GenEigsBase.h.

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

Definition at line 64 of file GenEigsBase.h.

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

Definition at line 67 of file GenEigsBase.h.

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

Definition at line 66 of file GenEigsBase.h.

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

Definition at line 61 of file GenEigsBase.h.

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

Definition at line 76 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
ComplexVector Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_ritz_est
protected

Definition at line 73 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
ComplexVector Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_ritz_val
protected

Definition at line 71 of file GenEigsBase.h.

template<typename Scalar, int SelectionRule, typename OpType, typename BOpType>
ComplexMatrix Spectra::GenEigsBase< Scalar, SelectionRule, OpType, BOpType >::m_ritz_vec
protected

Definition at line 72 of file GenEigsBase.h.


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


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