13 #ifndef EIGEN_MINRES_H_ 14 #define EIGEN_MINRES_H_ 30 template<
typename MatrixType,
typename Rhs,
typename Dest,
typename Preconditioner>
33 const Preconditioner& precond,
Index& iters,
42 const RealScalar rhsNorm2(rhs.squaredNorm());
52 const Index maxIters(iters);
54 const RealScalar threshold2(tol_error*tol_error*rhsNorm2);
58 VectorType
v( VectorType::Zero(
N) );
59 VectorType v_new(rhs-mat*x);
60 RealScalar residualNorm2(v_new.squaredNorm());
62 VectorType w_new(precond.solve(v_new));
64 RealScalar beta_new2(v_new.dot(w_new));
65 eigen_assert(beta_new2 >= 0.0 &&
"PRECONDITIONER IS NOT POSITIVE DEFINITE");
66 RealScalar beta_new(
sqrt(beta_new2));
67 const RealScalar beta_one(beta_new);
70 RealScalar c_old(1.0);
72 RealScalar s_old(0.0);
74 VectorType p_old(VectorType::Zero(
N));
79 while ( iters < maxIters )
91 const RealScalar beta(beta_new);
97 v_new.noalias() = mat*w - beta*v_old;
98 const RealScalar
alpha = v_new.dot(w);
100 w_new = precond.solve(v_new);
101 beta_new2 = v_new.dot(w_new);
102 eigen_assert(beta_new2 >= 0.0 &&
"PRECONDITIONER IS NOT POSITIVE DEFINITE");
103 beta_new =
sqrt(beta_new2);
106 const RealScalar
r2 =s*alpha+c*c_old*beta;
107 const RealScalar
r3 =s_old*beta;
108 const RealScalar r1_hat=c*alpha-c_old*s*beta;
118 p.noalias()=(w-r2*p_old-r3*p_oold) /r1;
119 x += beta_one*c*eta*
p;
123 residualNorm2 *= s*
s;
125 if ( residualNorm2 < threshold2)
136 tol_error =
std::sqrt(residualNorm2 / rhsNorm2);
141 template<
typename _MatrixType,
int _UpLo=
Lower,
147 template<
typename _MatrixType,
int _UpLo,
typename _Preconditioner>
194 template<
typename _MatrixType,
int _UpLo,
typename _Preconditioner>
201 using Base::m_iterations;
203 using Base::m_isInitialized;
205 using Base::_solve_impl;
228 template<
typename MatrixDerived>
235 template<
typename Rhs,
typename Dest>
241 TransposeInput = (!MatrixWrapper::MatrixFree)
243 && (!MatrixType::IsRowMajor)
251 >::
type SelfAdjointWrapper;
253 m_iterations = Base::maxIterations();
254 m_error = Base::m_tolerance;
255 RowMajorWrapper row_mat(
matrix());
257 Base::m_preconditioner, m_iterations, m_error);
267 #endif // EIGEN_MINRES_H MatrixType::Scalar Scalar
Namespace containing all symbols from the Eigen library.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
#define EIGEN_IMPLIES(a, b)
#define EIGEN_DONT_INLINE
_Preconditioner Preconditioner
MINRES(const EigenBase< MatrixDerived > &A)
MatrixWrapper::ActualMatrixType ActualMatrixType
A minimal residual solver for sparse symmetric problems.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Array< int, Dynamic, 1 > v
NumTraits< Scalar >::Real RealScalar
IterativeSolverBase< MINRES > Base
_Preconditioner Preconditioner
void _solve_vector_with_guess_impl(const Rhs &b, Dest &x) const
A naive preconditioner which approximates any matrix as the identity matrix.
Jet< T, N > sqrt(const Jet< T, N > &f)
MatrixType::RealScalar RealScalar
Jet< T, N > pow(const Jet< T, N > &f, double g)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Base class for linear iterative solvers.
EIGEN_DONT_INLINE void minres(const MatrixType &mat, const Rhs &rhs, Dest &x, const Preconditioner &precond, Index &iters, typename Dest::RealScalar &tol_error)