10 #ifndef EIGEN_CONJUGATE_GRADIENT_H 11 #define EIGEN_CONJUGATE_GRADIENT_H 26 template<
typename MatrixType,
typename Rhs,
typename Dest,
typename Preconditioner>
29 const Preconditioner& precond,
Index& iters,
38 RealScalar
tol = tol_error;
39 Index maxIters = iters;
43 VectorType residual = rhs - mat *
x;
45 RealScalar rhsNorm2 = rhs.squaredNorm();
54 RealScalar threshold =
numext::maxi(tol*tol*rhsNorm2,considerAsZero);
55 RealScalar residualNorm2 = residual.squaredNorm();
56 if (residualNorm2 < threshold)
59 tol_error =
sqrt(residualNorm2 / rhsNorm2);
64 p = precond.solve(residual);
66 VectorType
z(n), tmp(n);
71 tmp.noalias() = mat *
p;
73 Scalar
alpha = absNew / p.dot(tmp);
75 residual -= alpha * tmp;
77 residualNorm2 = residual.squaredNorm();
78 if(residualNorm2 < threshold)
81 z = precond.solve(residual);
83 RealScalar absOld = absNew;
85 RealScalar beta = absNew / absOld;
89 tol_error =
sqrt(residualNorm2 / rhsNorm2);
95 template<
typename _MatrixType,
int _UpLo=
Lower,
101 template<
typename _MatrixType,
int _UpLo,
typename _Preconditioner>
157 template<
typename _MatrixType,
int _UpLo,
typename _Preconditioner>
163 using Base::m_iterations;
165 using Base::m_isInitialized;
191 template<
typename MatrixDerived>
197 template<
typename Rhs,
typename Dest>
203 TransposeInput = (!MatrixWrapper::MatrixFree)
205 && (!MatrixType::IsRowMajor)
213 >::
type SelfAdjointWrapper;
215 m_error = Base::m_tolerance;
220 m_error = Base::m_tolerance;
223 RowMajorWrapper row_mat(
matrix());
227 m_isInitialized =
true;
232 using Base::_solve_impl;
233 template<
typename Rhs,
typename Dest>
237 _solve_with_guess_impl(b.derived(),
x);
246 #endif // EIGEN_CONJUGATE_GRADIENT_H A preconditioner based on the digonal entries.
void _solve_with_guess_impl(const Rhs &b, Dest &x) const
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Namespace containing all symbols from the Eigen library.
Block< Derived, internal::traits< Derived >::RowsAtCompileTime, 1,!IsRowMajor > ColXpr
A conjugate gradient solver for sparse (or dense) self-adjoint problems.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T maxi(const T &x, const T &y)
#define EIGEN_IMPLIES(a, b)
#define EIGEN_DONT_INLINE
_Preconditioner Preconditioner
MatrixWrapper::ActualMatrixType ActualMatrixType
internal::traits< SparseMatrix< _Scalar, _Options, _StorageIndex > >::Scalar Scalar
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
NumTraits< Scalar >::Real RealScalar
EIGEN_DONT_INLINE void conjugate_gradient(const MatrixType &mat, const Rhs &rhs, Dest &x, const Preconditioner &precond, Index &iters, typename Dest::RealScalar &tol_error)
MatrixType::RealScalar RealScalar
void _solve_impl(const MatrixBase< Rhs > &b, Dest &x) const
MatrixType::Scalar Scalar
IterativeSolverBase< ConjugateGradient > Base
ConjugateGradient(const EigenBase< MatrixDerived > &A)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
NumTraits< Scalar >::Real RealScalar
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.
_Preconditioner Preconditioner