|
typedef Matrix< std::complex< RealScalar >, Dynamic, 1 > | ComplexVector |
|
typedef Matrix< Scalar, Dynamic, Dynamic > | DenseMatrix |
|
typedef Matrix< RealScalar, Dynamic, Dynamic > | DenseRealMatrix |
|
typedef Matrix< RealScalar, Dynamic, 1 > | DenseRealVector |
|
typedef Matrix< Scalar, Dynamic, 1 > | DenseVector |
|
typedef MatrixType::Index | Index |
|
typedef _MatrixType | MatrixType |
|
typedef _Preconditioner | Preconditioner |
|
typedef MatrixType::RealScalar | RealScalar |
|
typedef MatrixType::Scalar | Scalar |
|
typedef MatrixType::Index | Index |
|
typedef internal::traits< DGMRES< _MatrixType, _Preconditioner > >::MatrixType | MatrixType |
|
typedef internal::traits< DGMRES< _MatrixType, _Preconditioner > >::Preconditioner | Preconditioner |
|
typedef MatrixType::RealScalar | RealScalar |
|
typedef MatrixType::Scalar | Scalar |
|
|
template<typename Rhs , typename Dest > |
void | _solve (const Rhs &b, Dest &x) const |
|
template<typename Rhs , typename Dest > |
void | _solveWithGuess (const Rhs &b, Dest &x) const |
|
int | deflSize () |
|
| DGMRES () |
|
| DGMRES (const MatrixType &A) |
|
int | restart () |
|
void | set_restart (const int restart) |
|
void | setEigenv (const int neig) |
|
void | setMaxEigenv (const int maxNeig) |
|
template<typename Rhs , typename Guess > |
const internal::solve_retval_with_guess< DGMRES, Rhs, Guess > | solveWithGuess (const MatrixBase< Rhs > &b, const Guess &x0) const |
|
| ~DGMRES () |
|
void | _solve_sparse (const Rhs &b, SparseMatrix< DestScalar, DestOptions, DestIndex > &dest) const |
|
DGMRES< _MatrixType, _Preconditioner > & | analyzePattern (const MatrixType &A) |
|
Index | cols () const |
|
DGMRES< _MatrixType, _Preconditioner > & | compute (const MatrixType &A) |
|
DGMRES< _MatrixType, _Preconditioner > & | derived () |
|
const DGMRES< _MatrixType, _Preconditioner > & | derived () const |
|
RealScalar | error () const |
|
DGMRES< _MatrixType, _Preconditioner > & | factorize (const MatrixType &A) |
|
ComputationInfo | info () const |
|
int | iterations () const |
|
| IterativeSolverBase () |
|
| IterativeSolverBase (const MatrixType &A) |
|
int | maxIterations () const |
|
Preconditioner & | preconditioner () |
|
const Preconditioner & | preconditioner () const |
|
Index | rows () const |
|
DGMRES< _MatrixType, _Preconditioner > & | setMaxIterations (int maxIters) |
|
DGMRES< _MatrixType, _Preconditioner > & | setTolerance (const RealScalar &tolerance) |
|
const internal::solve_retval< DGMRES< _MatrixType, _Preconditioner >, Rhs > | solve (const MatrixBase< Rhs > &b) const |
|
const internal::sparse_solve_retval< IterativeSolverBase, Rhs > | solve (const SparseMatrixBase< Rhs > &b) const |
|
RealScalar | tolerance () const |
|
| ~IterativeSolverBase () |
|
|
template<typename Rhs , typename Dest > |
void | dgmres (const MatrixType &mat, const Rhs &rhs, Dest &x, const Preconditioner &precond) const |
| Perform several cycles of restarted GMRES with modified Gram Schmidt,. More...
|
|
template<typename RhsType , typename DestType > |
int | dgmresApplyDeflation (const RhsType &In, DestType &Out) const |
|
int | dgmresComputeDeflationData (const MatrixType &mat, const Preconditioner &precond, const Index &it, Index &neig) const |
|
template<typename Dest > |
int | dgmresCycle (const MatrixType &mat, const Preconditioner &precond, Dest &x, DenseVector &r0, RealScalar &beta, const RealScalar &normRhs, int &nbIts) const |
| Perform one restart cycle of DGMRES. More...
|
|
void | dgmresInitDeflation (Index &rows) const |
|
ComplexVector | schurValues (const ComplexSchur< DenseMatrix > &schurofH) const |
|
ComplexVector | schurValues (const RealSchur< DenseMatrix > &schurofH) const |
|
void | init () |
|
template<typename _MatrixType, typename _Preconditioner>
class Eigen::DGMRES< _MatrixType, _Preconditioner >
A Restarted GMRES with deflation. This class implements a modification of the GMRES solver for sparse linear systems. The basis is built with modified Gram-Schmidt. At each restart, a few approximated eigenvectors corresponding to the smallest eigenvalues are used to build a preconditioner for the next cycle. This preconditioner for deflation can be combined with any other preconditioner, the IncompleteLUT for instance. The preconditioner is applied at right of the matrix and the combination is multiplicative.
- Template Parameters
-
_MatrixType | the type of the sparse matrix A, can be a dense or a sparse matrix. |
_Preconditioner | the type of the preconditioner. Default is DiagonalPreconditioner Typical usage : VectorXd x, b; DGMRES<SparseMatrix<double> > solver; solver.set_restart(30); solver.setEigenv(1); solver.compute(A); x = solver.solve(b); |
References : [1] D. NUENTSA WAKAM and F. PACULL, Memory Efficient Hybrid Algebraic Solvers for Linear Systems Arising from Compressible Flows, Computers and Fluids, In Press, http://dx.doi.org/10.1016/j.compfluid.2012.03.023 [2] K. Burrage and J. Erhel, On the performance of various adaptive preconditioned GMRES strategies, 5(1998), 101-121. [3] J. Erhel, K. Burrage and B. Pohl, Restarted GMRES preconditioned by deflation,J. Computational and Applied Mathematics, 69(1996), 303-318.
Definition at line 19 of file DGMRES.h.
template<typename _MatrixType , typename _Preconditioner >
template<typename Rhs , typename Dest >
Perform several cycles of restarted GMRES with modified Gram Schmidt,.
A right preconditioner is used combined with deflation.
Definition at line 256 of file DGMRES.h.