Public Member Functions | Private Types | Private Attributes | List of all members
Spectra::DavidsonSymEigsSolver< OpType > Class Template Reference

#include <DavidsonSymEigsSolver.h>

Inheritance diagram for Spectra::DavidsonSymEigsSolver< OpType >:
Inheritance graph
[legend]

Public Member Functions

Matrix calculate_correction_vector () const
 
 DavidsonSymEigsSolver (OpType &op, Index nev)
 
 DavidsonSymEigsSolver (OpType &op, Index nev, Index nvec_init, Index nvec_max)
 
Matrix setup_initial_search_space (SortRule selection) const
 
- Public Member Functions inherited from Spectra::JDSymEigsBase< DavidsonSymEigsSolver< OpType >, OpType >
Index compute (SortRule selection=SortRule::LargestMagn, Index maxit=100, Scalar tol=100 *Eigen::NumTraits< Scalar >::dummy_precision())
 
Index compute_with_guess (const Eigen::Ref< const Matrix > &initial_space, SortRule selection=SortRule::LargestMagn, Index maxit=100, Scalar tol=100 *Eigen::NumTraits< Scalar >::dummy_precision())
 
Vector eigenvalues () const
 
Matrix eigenvectors () const
 
CompInfo info () const
 
 JDSymEigsBase (OpType &op, Index nev)
 
 JDSymEigsBase (OpType &op, Index nev, Index nvec_init, Index nvec_max)
 
Index num_iterations () const
 
void set_correction_size (Index correction_size)
 
void set_initial_search_space_size (Index initial_search_space_size)
 
void set_max_search_space_size (Index max_search_space_size)
 
virtual ~JDSymEigsBase ()
 

Private Types

using Index = Eigen::Index
 
using Matrix = Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic >
 
using Scalar = typename OpType::Scalar
 
using Vector = Eigen::Matrix< Scalar, Eigen::Dynamic, 1 >
 

Private Attributes

Vector m_diagonal
 

Additional Inherited Members

- Protected Types inherited from Spectra::JDSymEigsBase< DavidsonSymEigsSolver< OpType >, OpType >
using Index = Eigen::Index
 
using Matrix = Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic >
 
using Scalar = typename OpType::Scalar
 
using Vector = Eigen::Matrix< Scalar, Eigen::Dynamic, 1 >
 
- Protected Attributes inherited from Spectra::JDSymEigsBase< DavidsonSymEigsSolver< OpType >, OpType >
Index m_correction_size
 
Index m_initial_search_space_size
 
const OpType & m_matrix_operator
 
Index m_max_search_space_size
 
const Index m_number_eigenvalues
 
RitzPairs< Scalarm_ritz_pairs
 
SearchSpace< Scalarm_search_space
 
Index niter_
 

Detailed Description

template<typename OpType>
class Spectra::DavidsonSymEigsSolver< OpType >

This class implement the DPR correction for the Davidson algorithms. The algorithms in the Davidson family only differ in how the correction vectors are computed and optionally in the initial orthogonal basis set.

the DPR correction compute the new correction vector using the following expression:

\[ correction = -(\boldsymbol{D} - \rho \boldsymbol{I})^{-1} \boldsymbol{r} \]

where $D$ is the diagonal of the target matrix, $\rho$ the Ritz eigenvalue, $I$ the identity matrix and $r$ the residue vector.

Definition at line 31 of file DavidsonSymEigsSolver.h.

Member Typedef Documentation

◆ Index

template<typename OpType >
using Spectra::DavidsonSymEigsSolver< OpType >::Index = Eigen::Index
private

Definition at line 34 of file DavidsonSymEigsSolver.h.

◆ Matrix

template<typename OpType >
using Spectra::DavidsonSymEigsSolver< OpType >::Matrix = Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic>
private

Definition at line 36 of file DavidsonSymEigsSolver.h.

◆ Scalar

template<typename OpType >
using Spectra::DavidsonSymEigsSolver< OpType >::Scalar = typename OpType::Scalar
private

Definition at line 35 of file DavidsonSymEigsSolver.h.

◆ Vector

template<typename OpType >
using Spectra::DavidsonSymEigsSolver< OpType >::Vector = Eigen::Matrix<Scalar, Eigen::Dynamic, 1>
private

Definition at line 37 of file DavidsonSymEigsSolver.h.

Constructor & Destructor Documentation

◆ DavidsonSymEigsSolver() [1/2]

template<typename OpType >
Spectra::DavidsonSymEigsSolver< OpType >::DavidsonSymEigsSolver ( OpType &  op,
Index  nev,
Index  nvec_init,
Index  nvec_max 
)
inline

Definition at line 42 of file DavidsonSymEigsSolver.h.

◆ DavidsonSymEigsSolver() [2/2]

template<typename OpType >
Spectra::DavidsonSymEigsSolver< OpType >::DavidsonSymEigsSolver ( OpType &  op,
Index  nev 
)
inline

Definition at line 52 of file DavidsonSymEigsSolver.h.

Member Function Documentation

◆ calculate_correction_vector()

template<typename OpType >
Matrix Spectra::DavidsonSymEigsSolver< OpType >::calculate_correction_vector ( ) const
inline

Compute the corrections using the DPR method.

Returns
New correction vectors.

Definition at line 77 of file DavidsonSymEigsSolver.h.

◆ setup_initial_search_space()

template<typename OpType >
Matrix Spectra::DavidsonSymEigsSolver< OpType >::setup_initial_search_space ( SortRule  selection) const
inline

Create initial search space based on the diagonal and the spectrum'target (highest or lowest)

Parameters
selectionSpectrum section to target (e.g. lowest, etc.)
Returns
Matrix with the initial orthonormal basis

Definition at line 60 of file DavidsonSymEigsSolver.h.

Member Data Documentation

◆ m_diagonal

template<typename OpType >
Vector Spectra::DavidsonSymEigsSolver< OpType >::m_diagonal
private

Definition at line 39 of file DavidsonSymEigsSolver.h.


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


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:15:49