IterativeSolverBase.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_ITERATIVE_SOLVER_BASE_H
11 #define EIGEN_ITERATIVE_SOLVER_BASE_H
12 
13 namespace Eigen {
14 
15 namespace internal {
16 
17 template<typename MatrixType>
19 {
20 private:
21  template <typename T0>
23  {
24  template <typename T> any_conversion(const volatile T&);
25  template <typename T> any_conversion(T&);
26  };
27  struct yes {int a[1];};
28  struct no {int a[2];};
29 
30  template<typename T>
31  static yes test(const Ref<const T>&, int);
32  template<typename T>
33  static no test(any_conversion<T>, ...);
34 
35 public:
37  enum { value = sizeof(test<MatrixType>(ms_from, 0))==sizeof(yes) };
38 };
39 
40 template<typename MatrixType>
42 {
44 };
45 
48 
49 // We have an explicit matrix at hand, compatible with Ref<>
50 template<typename MatrixType>
52 {
53 public:
55  template<int UpLo> struct ConstSelfAdjointViewReturnType {
56  typedef typename ActualMatrixType::template ConstSelfAdjointViewReturnType<UpLo>::Type Type;
57  };
58 
59  enum {
60  MatrixFree = false
61  };
62 
64  : m_dummy(0,0), m_matrix(m_dummy)
65  {}
66 
67  template<typename InputType>
68  generic_matrix_wrapper(const InputType &mat)
69  : m_matrix(mat)
70  {}
71 
72  const ActualMatrixType& matrix() const
73  {
74  return m_matrix;
75  }
76 
77  template<typename MatrixDerived>
79  {
80  m_matrix.~Ref<const MatrixType>();
81  ::new (&m_matrix) Ref<const MatrixType>(mat.derived());
82  }
83 
85  {
86  if(&(mat.derived()) != &m_matrix)
87  {
88  m_matrix.~Ref<const MatrixType>();
89  ::new (&m_matrix) Ref<const MatrixType>(mat);
90  }
91  }
92 
93 protected:
94  MatrixType m_dummy; // used to default initialize the Ref<> object
95  ActualMatrixType m_matrix;
96 };
97 
98 // MatrixType is not compatible with Ref<> -> matrix-free wrapper
99 template<typename MatrixType>
101 {
102 public:
104  template<int UpLo> struct ConstSelfAdjointViewReturnType
105  {
106  typedef ActualMatrixType Type;
107  };
108 
109  enum {
110  MatrixFree = true
111  };
112 
114  : mp_matrix(0)
115  {}
116 
118  : mp_matrix(&mat)
119  {}
120 
121  const ActualMatrixType& matrix() const
122  {
123  return *mp_matrix;
124  }
125 
126  void grab(const MatrixType &mat)
127  {
128  mp_matrix = &mat;
129  }
130 
131 protected:
132  const ActualMatrixType *mp_matrix;
133 };
134 
135 }
136 
142 template< typename Derived>
143 class IterativeSolverBase : public SparseSolverBase<Derived>
144 {
145 protected:
147  using Base::m_isInitialized;
148 
149 public:
152  typedef typename MatrixType::Scalar Scalar;
153  typedef typename MatrixType::StorageIndex StorageIndex;
155 
156  enum {
157  ColsAtCompileTime = MatrixType::ColsAtCompileTime,
158  MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
159  };
160 
161 public:
162 
163  using Base::derived;
164 
167  {
168  init();
169  }
170 
181  template<typename MatrixDerived>
183  : m_matrixWrapper(A.derived())
184  {
185  init();
186  compute(matrix());
187  }
188 
190 
196  template<typename MatrixDerived>
198  {
199  grab(A.derived());
200  m_preconditioner.analyzePattern(matrix());
201  m_isInitialized = true;
202  m_analysisIsOk = true;
203  m_info = m_preconditioner.info();
204  return derived();
205  }
206 
216  template<typename MatrixDerived>
218  {
219  eigen_assert(m_analysisIsOk && "You must first call analyzePattern()");
220  grab(A.derived());
221  m_preconditioner.factorize(matrix());
222  m_factorizationIsOk = true;
223  m_info = m_preconditioner.info();
224  return derived();
225  }
226 
237  template<typename MatrixDerived>
239  {
240  grab(A.derived());
241  m_preconditioner.compute(matrix());
242  m_isInitialized = true;
243  m_analysisIsOk = true;
244  m_factorizationIsOk = true;
245  m_info = m_preconditioner.info();
246  return derived();
247  }
248 
250  EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return matrix().rows(); }
251 
253  EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return matrix().cols(); }
254 
258  RealScalar tolerance() const { return m_tolerance; }
259 
265  Derived& setTolerance(const RealScalar& tolerance)
266  {
267  m_tolerance = tolerance;
268  return derived();
269  }
270 
272  Preconditioner& preconditioner() { return m_preconditioner; }
273 
275  const Preconditioner& preconditioner() const { return m_preconditioner; }
276 
282  {
283  return (m_maxIterations<0) ? 2*matrix().cols() : m_maxIterations;
284  }
285 
289  Derived& setMaxIterations(Index maxIters)
290  {
291  m_maxIterations = maxIters;
292  return derived();
293  }
294 
297  {
298  eigen_assert(m_isInitialized && "ConjugateGradient is not initialized.");
299  return m_iterations;
300  }
301 
305  RealScalar error() const
306  {
307  eigen_assert(m_isInitialized && "ConjugateGradient is not initialized.");
308  return m_error;
309  }
310 
316  template<typename Rhs,typename Guess>
318  solveWithGuess(const MatrixBase<Rhs>& b, const Guess& x0) const
319  {
320  eigen_assert(m_isInitialized && "Solver is not initialized.");
321  eigen_assert(derived().rows()==b.rows() && "solve(): invalid number of rows of the right hand side matrix b");
322  return SolveWithGuess<Derived, Rhs, Guess>(derived(), b.derived(), x0);
323  }
324 
327  {
328  eigen_assert(m_isInitialized && "IterativeSolverBase is not initialized.");
329  return m_info;
330  }
331 
333  template<typename Rhs, typename DestDerived>
335  {
336  eigen_assert(rows()==b.rows());
337 
338  Index rhsCols = b.cols();
339  Index size = b.rows();
340  DestDerived& dest(aDest.derived());
341  typedef typename DestDerived::Scalar DestScalar;
344  // We do not directly fill dest because sparse expressions have to be free of aliasing issue.
345  // For non square least-square problems, b and dest might not have the same size whereas they might alias each-other.
346  typename DestDerived::PlainObject tmp(cols(),rhsCols);
347  ComputationInfo global_info = Success;
348  for(Index k=0; k<rhsCols; ++k)
349  {
350  tb = b.col(k);
351  tx = dest.col(k);
352  derived()._solve_vector_with_guess_impl(tb,tx);
353  tmp.col(k) = tx.sparseView(0);
354 
355  // The call to _solve_vector_with_guess_impl updates m_info, so if it failed for a previous column
356  // we need to restore it to the worst value.
357  if(m_info==NumericalIssue)
358  global_info = NumericalIssue;
359  else if(m_info==NoConvergence)
360  global_info = NoConvergence;
361  }
362  m_info = global_info;
363  dest.swap(tmp);
364  }
365 
366  template<typename Rhs, typename DestDerived>
369  {
370  eigen_assert(rows()==b.rows());
371 
372  Index rhsCols = b.cols();
373  DestDerived& dest(aDest.derived());
374  ComputationInfo global_info = Success;
375  for(Index k=0; k<rhsCols; ++k)
376  {
377  typename DestDerived::ColXpr xk(dest,k);
378  typename Rhs::ConstColXpr bk(b,k);
379  derived()._solve_vector_with_guess_impl(bk,xk);
380 
381  // The call to _solve_vector_with_guess updates m_info, so if it failed for a previous column
382  // we need to restore it to the worst value.
383  if(m_info==NumericalIssue)
384  global_info = NumericalIssue;
385  else if(m_info==NoConvergence)
386  global_info = NoConvergence;
387  }
388  m_info = global_info;
389  }
390 
391  template<typename Rhs, typename DestDerived>
394  {
395  derived()._solve_vector_with_guess_impl(b,dest.derived());
396  }
397 
399  template<typename Rhs,typename Dest>
400  void _solve_impl(const Rhs& b, Dest& x) const
401  {
402  x.setZero();
403  derived()._solve_with_guess_impl(b,x);
404  }
405 
406 protected:
407  void init()
408  {
409  m_isInitialized = false;
410  m_analysisIsOk = false;
411  m_factorizationIsOk = false;
412  m_maxIterations = -1;
413  m_tolerance = NumTraits<Scalar>::epsilon();
414  }
415 
417  typedef typename MatrixWrapper::ActualMatrixType ActualMatrixType;
418 
419  const ActualMatrixType& matrix() const
420  {
421  return m_matrixWrapper.matrix();
422  }
423 
424  template<typename InputType>
425  void grab(const InputType &A)
426  {
427  m_matrixWrapper.grab(A);
428  }
429 
430  MatrixWrapper m_matrixWrapper;
431  Preconditioner m_preconditioner;
432 
434  RealScalar m_tolerance;
435 
436  mutable RealScalar m_error;
439  mutable bool m_analysisIsOk, m_factorizationIsOk;
440 };
441 
442 } // end namespace Eigen
443 
444 #endif // EIGEN_ITERATIVE_SOLVER_BASE_H
SCALAR Scalar
Definition: bench_gemm.cpp:46
Pseudo expression representing a solving operation.
Scalar * b
Definition: benchVecAdd.cpp:17
Derived & setTolerance(const RealScalar &tolerance)
const Block< const Derived, internal::traits< Derived >::RowsAtCompileTime, 1, !IsRowMajor > ConstColXpr
Definition: BlockMethods.h:15
static yes test(const Ref< const T > &, int)
ComputationInfo info() const
IterativeSolverBase(const EigenBase< MatrixDerived > &A)
A base class for sparse solvers.
EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
internal::generic_matrix_wrapper< MatrixType > MatrixWrapper
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
MatrixXf MatrixType
internal::traits< Derived >::Preconditioner Preconditioner
const Preconditioner & preconditioner() const
void grab(const EigenBase< MatrixDerived > &mat)
Derived & factorize(const EigenBase< MatrixDerived > &A)
MatrixType::StorageIndex StorageIndex
SparseSolverBase< Derived > Base
static double epsilon
Definition: testRot3.cpp:37
void _solve_with_guess_impl(const Rhs &b, SparseMatrixBase< DestDerived > &aDest) const
Base class of any sparse matrices or sparse expressions.
MatrixWrapper::ActualMatrixType ActualMatrixType
Derived & analyzePattern(const EigenBase< MatrixDerived > &A)
Derived & compute(const EigenBase< MatrixDerived > &A)
internal::enable_if< Rhs::ColsAtCompileTime==1||DestDerived::ColsAtCompileTime==1 >::type _solve_with_guess_impl(const Rhs &b, MatrixBase< DestDerived > &dest) const
#define EIGEN_NOEXCEPT
Definition: Macros.h:1418
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74
const ActualMatrixType & matrix() const
#define eigen_assert(x)
Definition: Macros.h:1037
#define EIGEN_CONSTEXPR
Definition: Macros.h:787
const SolveWithGuess< Derived, Rhs, Guess > solveWithGuess(const MatrixBase< Rhs > &b, const Guess &x0) const
NumTraits< Scalar >::Real RealScalar
Definition: bench_gemm.cpp:47
Derived & setMaxIterations(Index maxIters)
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:281
EIGEN_CONSTEXPR Index size(const T &x)
Definition: Meta.h:479
static Symbol x0('x', 0)
ActualMatrixType::template ConstSelfAdjointViewReturnType< UpLo >::Type Type
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:1882
internal::enable_if< Rhs::ColsAtCompileTime!=1 &&DestDerived::ColsAtCompileTime!=1 >::type _solve_with_guess_impl(const Rhs &b, MatrixBase< DestDerived > &aDest) const
EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
const Derived & derived() const
void _solve_impl(const Rhs &b, Dest &x) const
MatrixType::RealScalar RealScalar
Preconditioner & preconditioner()
EIGEN_DONT_INLINE void compute(Solver &solver, const MatrixType &A)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
The matrix class, also used for vectors and row-vectors.
internal::traits< Derived >::MatrixType MatrixType
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
ComputationInfo
Definition: Constants.h:440
Base class for linear iterative solvers.
EIGEN_DEVICE_FUNC Derived & derived()
Definition: EigenBase.h:46
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
void grab(const InputType &A)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:27