11 #ifndef EIGEN_BICGSTAB_H 12 #define EIGEN_BICGSTAB_H 28 template<
typename MatrixType,
typename Rhs,
typename Dest,
typename Preconditioner>
30 const Preconditioner& precond,
Index& iters,
38 RealScalar
tol = tol_error;
39 Index maxIters = iters;
42 VectorType r = rhs - mat *
x;
45 RealScalar r0_sqnorm = r0.squaredNorm();
46 RealScalar rhs_sqnorm = rhs.squaredNorm();
56 VectorType
v = VectorType::Zero(n),
p = VectorType::Zero(n);
57 VectorType
y(n),
z(n);
58 VectorType kt(n), ks(n);
60 VectorType
s(n),
t(n);
62 RealScalar tol2 = tol*tol*rhs_sqnorm;
67 while ( r.squaredNorm() > tol2 && i<maxIters )
72 if (
abs(rho) < eps2*r0_sqnorm)
78 rho = r0_sqnorm = r.squaredNorm();
82 Scalar beta = (rho/rho_old) * (alpha / w);
83 p = r + beta * (
p - w *
v);
87 v.noalias() = mat *
y;
89 alpha = rho / r0.dot(v);
93 t.noalias() = mat *
z;
95 RealScalar tmp = t.squaredNorm();
100 x += alpha * y + w *
z;
104 tol_error =
sqrt(r.squaredNorm()/rhs_sqnorm);
111 template<
typename _MatrixType,
117 template<
typename _MatrixType,
typename _Preconditioner>
157 template<
typename _MatrixType,
typename _Preconditioner>
163 using Base::m_iterations;
165 using Base::m_isInitialized;
187 template<
typename MatrixDerived>
193 template<
typename Rhs,
typename Dest>
196 m_iterations = Base::maxIterations();
197 m_error = Base::m_tolerance;
202 : m_error <= Base::m_tolerance ?
Success 212 #endif // EIGEN_BICGSTAB_H A preconditioner based on the digonal entries.
bool bicgstab(const MatrixType &mat, const Rhs &rhs, Dest &x, const Preconditioner &precond, Index &iters, typename Dest::RealScalar &tol_error)
_Preconditioner Preconditioner
Namespace containing all symbols from the Eigen library.
BiCGSTAB(const EigenBase< MatrixDerived > &A)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Array< int, Dynamic, 1 > v
_Preconditioner Preconditioner
NumTraits< Scalar >::Real RealScalar
MatrixType::RealScalar RealScalar
void _solve_vector_with_guess_impl(const Rhs &b, Dest &x) const
Jet< T, N > sqrt(const Jet< T, N > &f)
A bi conjugate gradient stabilized solver for sparse square problems.
MatrixType::Scalar Scalar
IterativeSolverBase< BiCGSTAB > Base
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.