ConjugateGradient.h
Go to the documentation of this file.
1 // This file is part of Eigen, a lightweight C++ template library
2 // for linear algebra.
3 //
4 // Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>
5 //
6 // This Source Code Form is subject to the terms of the Mozilla
7 // Public License v. 2.0. If a copy of the MPL was not distributed
8 // with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
9 
10 #ifndef EIGEN_CONJUGATE_GRADIENT_H
11 #define EIGEN_CONJUGATE_GRADIENT_H
12 
13 namespace Eigen {
14 
15 namespace internal {
16 
26 template<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>
28 void conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x,
29  const Preconditioner& precond, Index& iters,
30  typename Dest::RealScalar& tol_error)
31 {
32  using std::sqrt;
33  using std::abs;
34  typedef typename Dest::RealScalar RealScalar;
35  typedef typename Dest::Scalar Scalar;
37 
38  RealScalar tol = tol_error;
39  Index maxIters = iters;
40 
41  Index n = mat.cols();
42 
43  VectorType residual = rhs - mat * x; //initial residual
44 
45  RealScalar rhsNorm2 = rhs.squaredNorm();
46  if(rhsNorm2 == 0)
47  {
48  x.setZero();
49  iters = 0;
50  tol_error = 0;
51  return;
52  }
53  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();
54  RealScalar threshold = numext::maxi(tol*tol*rhsNorm2,considerAsZero);
55  RealScalar residualNorm2 = residual.squaredNorm();
56  if (residualNorm2 < threshold)
57  {
58  iters = 0;
59  tol_error = sqrt(residualNorm2 / rhsNorm2);
60  return;
61  }
62 
63  VectorType p(n);
64  p = precond.solve(residual); // initial search direction
65 
66  VectorType z(n), tmp(n);
67  RealScalar absNew = numext::real(residual.dot(p)); // the square of the absolute value of r scaled by invM
68  Index i = 0;
69  while(i < maxIters)
70  {
71  tmp.noalias() = mat * p; // the bottleneck of the algorithm
72 
73  Scalar alpha = absNew / p.dot(tmp); // the amount we travel on dir
74  x += alpha * p; // update solution
75  residual -= alpha * tmp; // update residual
76 
77  residualNorm2 = residual.squaredNorm();
78  if(residualNorm2 < threshold)
79  break;
80 
81  z = precond.solve(residual); // approximately solve for "A z = residual"
82 
83  RealScalar absOld = absNew;
84  absNew = numext::real(residual.dot(z)); // update the absolute value of r
85  RealScalar beta = absNew / absOld; // calculate the Gram-Schmidt value used to create the new search direction
86  p = z + beta * p; // update search direction
87  i++;
88  }
89  tol_error = sqrt(residualNorm2 / rhsNorm2);
90  iters = i;
91 }
92 
93 }
94 
95 template< typename _MatrixType, int _UpLo=Lower,
96  typename _Preconditioner = DiagonalPreconditioner<typename _MatrixType::Scalar> >
98 
99 namespace internal {
100 
101 template< typename _MatrixType, int _UpLo, typename _Preconditioner>
102 struct traits<ConjugateGradient<_MatrixType,_UpLo,_Preconditioner> >
103 {
104  typedef _MatrixType MatrixType;
105  typedef _Preconditioner Preconditioner;
106 };
107 
108 }
109 
157 template< typename _MatrixType, int _UpLo, typename _Preconditioner>
158 class ConjugateGradient : public IterativeSolverBase<ConjugateGradient<_MatrixType,_UpLo,_Preconditioner> >
159 {
161  using Base::matrix;
162  using Base::m_error;
163  using Base::m_iterations;
164  using Base::m_info;
165  using Base::m_isInitialized;
166 public:
167  typedef _MatrixType MatrixType;
168  typedef typename MatrixType::Scalar Scalar;
170  typedef _Preconditioner Preconditioner;
171 
172  enum {
173  UpLo = _UpLo
174  };
175 
176 public:
177 
179  ConjugateGradient() : Base() {}
180 
191  template<typename MatrixDerived>
192  explicit ConjugateGradient(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}
193 
195 
197  template<typename Rhs,typename Dest>
198  void _solve_with_guess_impl(const Rhs& b, Dest& x) const
199  {
200  typedef typename Base::MatrixWrapper MatrixWrapper;
201  typedef typename Base::ActualMatrixType ActualMatrixType;
202  enum {
203  TransposeInput = (!MatrixWrapper::MatrixFree)
204  && (UpLo==(Lower|Upper))
205  && (!MatrixType::IsRowMajor)
207  };
208  typedef typename internal::conditional<TransposeInput,Transpose<const ActualMatrixType>, ActualMatrixType const&>::type RowMajorWrapper;
209  EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(MatrixWrapper::MatrixFree,UpLo==(Lower|Upper)),MATRIX_FREE_CONJUGATE_GRADIENT_IS_COMPATIBLE_WITH_UPPER_UNION_LOWER_MODE_ONLY);
210  typedef typename internal::conditional<UpLo==(Lower|Upper),
211  RowMajorWrapper,
212  typename MatrixWrapper::template ConstSelfAdjointViewReturnType<UpLo>::Type
213  >::type SelfAdjointWrapper;
214  m_iterations = Base::maxIterations();
215  m_error = Base::m_tolerance;
216 
217  for(Index j=0; j<b.cols(); ++j)
218  {
219  m_iterations = Base::maxIterations();
220  m_error = Base::m_tolerance;
221 
222  typename Dest::ColXpr xj(x,j);
223  RowMajorWrapper row_mat(matrix());
224  internal::conjugate_gradient(SelfAdjointWrapper(row_mat), b.col(j), xj, Base::m_preconditioner, m_iterations, m_error);
225  }
226 
227  m_isInitialized = true;
228  m_info = m_error <= Base::m_tolerance ? Success : NoConvergence;
229  }
230 
232  using Base::_solve_impl;
233  template<typename Rhs,typename Dest>
234  void _solve_impl(const MatrixBase<Rhs>& b, Dest& x) const
235  {
236  x.setZero();
237  _solve_with_guess_impl(b.derived(),x);
238  }
239 
240 protected:
241 
242 };
243 
244 } // end namespace Eigen
245 
246 #endif // EIGEN_CONJUGATE_GRADIENT_H
A preconditioner based on the digonal entries.
SCALAR Scalar
Definition: bench_gemm.cpp:33
float real
Definition: datatypes.h:10
Scalar * b
Definition: benchVecAdd.cpp:17
#define min(a, b)
Definition: datatypes.h:19
void _solve_with_guess_impl(const Rhs &b, Dest &x) const
int n
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
Block< Derived, internal::traits< Derived >::RowsAtCompileTime, 1,!IsRowMajor > ColXpr
Definition: BlockMethods.h:14
A conjugate gradient solver for sparse (or dense) self-adjoint problems.
MatrixXf MatrixType
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
Definition: NumTraits.h:150
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
Definition: StaticAssert.h:124
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T maxi(const T &x, const T &y)
#define EIGEN_IMPLIES(a, b)
Definition: Macros.h:902
#define EIGEN_DONT_INLINE
Definition: Macros.h:517
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.
Definition: Meta.h:33
RealScalar alpha
NumTraits< Scalar >::Real RealScalar
Definition: bench_gemm.cpp:34
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
float * p
void _solve_impl(const MatrixBase< Rhs > &b, Dest &x) const
MatrixType::Scalar Scalar
IterativeSolverBase< ConjugateGradient > Base
ConjugateGradient(const EigenBase< MatrixDerived > &A)
const G double tol
Definition: Group.h:83
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
#define abs(x)
Definition: datatypes.h:17
Base class for linear iterative solvers.
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
std::ptrdiff_t j
Definition: pytypes.h:897
_Preconditioner Preconditioner


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:50