10 #ifndef EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H 11 #define EIGEN_LEAST_SQUARE_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;
41 Index m = mat.rows(),
n = mat.cols();
43 VectorType residual = rhs - mat *
x;
44 VectorType normal_residual = mat.adjoint() * residual;
46 RealScalar rhsNorm2 = (mat.adjoint()*rhs).squaredNorm();
54 RealScalar threshold = tol*tol*rhsNorm2;
55 RealScalar residualNorm2 = normal_residual.squaredNorm();
56 if (residualNorm2 < threshold)
59 tol_error =
sqrt(residualNorm2 / rhsNorm2);
64 p = precond.solve(normal_residual);
66 VectorType
z(
n), tmp(m);
67 RealScalar absNew =
numext::real(normal_residual.dot(p));
71 tmp.noalias() = mat *
p;
73 Scalar
alpha = absNew / tmp.squaredNorm();
75 residual -= alpha * tmp;
76 normal_residual = mat.adjoint() * residual;
78 residualNorm2 = normal_residual.squaredNorm();
79 if(residualNorm2 < threshold)
82 z = precond.solve(normal_residual);
84 RealScalar absOld = absNew;
86 RealScalar beta = absNew / absOld;
90 tol_error =
sqrt(residualNorm2 / rhsNorm2);
96 template<
typename _MatrixType,
102 template<
typename _MatrixType,
typename _Preconditioner>
148 template<
typename _MatrixType,
typename _Preconditioner>
154 using Base::m_iterations;
156 using Base::m_isInitialized;
178 template<
typename MatrixDerived>
184 template<
typename Rhs,
typename Dest>
187 m_iterations = Base::maxIterations();
188 m_error = Base::m_tolerance;
198 #endif // EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H
_Preconditioner Preconditioner
void _solve_vector_with_guess_impl(const Rhs &b, Dest &x) const
IterativeSolverBase< LeastSquaresConjugateGradient > Base
Namespace containing all symbols from the Eigen library.
A conjugate gradient solver for sparse (or dense) least-square problems.
~LeastSquaresConjugateGradient()
_Preconditioner Preconditioner
Jacobi preconditioner for LeastSquaresConjugateGradient.
#define EIGEN_DONT_INLINE
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
NumTraits< Scalar >::Real RealScalar
MatrixType::RealScalar RealScalar
MatrixType::Scalar Scalar
EIGEN_DONT_INLINE void least_square_conjugate_gradient(const MatrixType &mat, const Rhs &rhs, Dest &x, const Preconditioner &precond, Index &iters, typename Dest::RealScalar &tol_error)
LeastSquaresConjugateGradient()
LeastSquaresConjugateGradient(const EigenBase< MatrixDerived > &A)
Jet< T, N > sqrt(const Jet< T, N > &f)
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.