12 #ifndef EIGEN_MINRES_H_ 13 #define EIGEN_MINRES_H_ 29 template<
typename MatrixType,
typename Rhs,
typename Dest,
typename Preconditioner>
32 const Preconditioner& precond,
Index& iters,
41 const RealScalar rhsNorm2(rhs.squaredNorm());
51 const Index maxIters(iters);
53 const RealScalar threshold2(tol_error*tol_error*rhsNorm2);
57 VectorType
v( VectorType::Zero(
N) );
58 VectorType v_new(rhs-mat*x);
59 RealScalar residualNorm2(v_new.squaredNorm());
61 VectorType w_new(precond.solve(v_new));
63 RealScalar beta_new2(v_new.dot(w_new));
64 eigen_assert(beta_new2 >= 0.0 &&
"PRECONDITIONER IS NOT POSITIVE DEFINITE");
65 RealScalar beta_new(
sqrt(beta_new2));
66 const RealScalar beta_one(beta_new);
71 RealScalar c_old(1.0);
73 RealScalar s_old(0.0);
75 VectorType p_old(VectorType::Zero(
N));
80 while ( iters < maxIters )
92 const RealScalar beta(beta_new);
98 v_new.noalias() = mat*w - beta*v_old;
99 const RealScalar
alpha = v_new.dot(w);
101 w_new = precond.solve(v_new);
102 beta_new2 = v_new.dot(w_new);
103 eigen_assert(beta_new2 >= 0.0 &&
"PRECONDITIONER IS NOT POSITIVE DEFINITE");
104 beta_new =
sqrt(beta_new2);
109 const RealScalar
r2 =s*alpha+c*c_old*beta;
110 const RealScalar
r3 =s_old*beta;
111 const RealScalar r1_hat=c*alpha-c_old*s*beta;
122 p.noalias()=(w-r2*p_old-r3*p_oold) /r1;
123 x += beta_one*c*eta*
p;
127 residualNorm2 *= s*
s;
129 if ( residualNorm2 < threshold2)
140 tol_error =
std::sqrt(residualNorm2 / rhsNorm2);
145 template<
typename _MatrixType,
int _UpLo=
Lower,
151 template<
typename _MatrixType,
int _UpLo,
typename _Preconditioner>
198 template<
typename _MatrixType,
int _UpLo,
typename _Preconditioner>
205 using Base::m_iterations;
207 using Base::m_isInitialized;
209 using Base::_solve_impl;
232 template<
typename MatrixDerived>
239 template<
typename Rhs,
typename Dest>
245 TransposeInput = (!MatrixWrapper::MatrixFree)
247 && (!MatrixType::IsRowMajor)
255 >::
type SelfAdjointWrapper;
258 m_error = Base::m_tolerance;
259 RowMajorWrapper row_mat(
matrix());
260 for(
int j=0;
j<b.cols(); ++
j)
263 m_error = Base::m_tolerance;
267 Base::m_preconditioner, m_iterations, m_error);
270 m_isInitialized =
true;
275 template<
typename Rhs,
typename Dest>
279 _solve_with_guess_impl(b,x.derived());
288 #endif // EIGEN_MINRES_H MatrixType::Scalar Scalar
EIGEN_DEVICE_FUNC Derived & setZero()
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Namespace containing all symbols from the Eigen library.
Block< Derived, internal::traits< Derived >::RowsAtCompileTime, 1,!IsRowMajor > ColXpr
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
void _solve_with_guess_impl(const Rhs &b, Dest &x) const
#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.
NumTraits< Scalar >::Real RealScalar
IterativeSolverBase< MINRES > Base
void _solve_impl(const Rhs &b, MatrixBase< Dest > &x) const
_Preconditioner Preconditioner
A naive preconditioner which approximates any matrix as the identity matrix.
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.
Base class for all dense matrices, vectors, and expressions.
EIGEN_DONT_INLINE void minres(const MatrixType &mat, const Rhs &rhs, Dest &x, const Preconditioner &precond, Index &iters, typename Dest::RealScalar &tol_error)