BiCGSTAB.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 // Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>
6 //
7 // This Source Code Form is subject to the terms of the Mozilla
8 // Public License v. 2.0. If a copy of the MPL was not distributed
9 // with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
10 
11 #ifndef EIGEN_BICGSTAB_H
12 #define EIGEN_BICGSTAB_H
13 
14 namespace Eigen {
15 
16 namespace internal {
17 
28 template<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>
29 bool bicgstab(const MatrixType& mat, const Rhs& rhs, Dest& x,
30  const Preconditioner& precond, Index& iters,
31  typename Dest::RealScalar& tol_error)
32 {
33  using std::sqrt;
34  using std::abs;
35  typedef typename Dest::RealScalar RealScalar;
36  typedef typename Dest::Scalar Scalar;
38  RealScalar tol = tol_error;
39  Index maxIters = iters;
40 
41  Index n = mat.cols();
42  VectorType r = rhs - mat * x;
43  VectorType r0 = r;
44 
45  RealScalar r0_sqnorm = r0.squaredNorm();
46  RealScalar rhs_sqnorm = rhs.squaredNorm();
47  if(rhs_sqnorm == 0)
48  {
49  x.setZero();
50  return true;
51  }
52  Scalar rho = 1;
53  Scalar alpha = 1;
54  Scalar w = 1;
55 
56  VectorType v = VectorType::Zero(n), p = VectorType::Zero(n);
57  VectorType y(n), z(n);
58  VectorType kt(n), ks(n);
59 
60  VectorType s(n), t(n);
61 
62  RealScalar tol2 = tol*tol*rhs_sqnorm;
64  Index i = 0;
65  Index restarts = 0;
66 
67  while ( r.squaredNorm() > tol2 && i<maxIters )
68  {
69  Scalar rho_old = rho;
70 
71  rho = r0.dot(r);
72  if (abs(rho) < eps2*r0_sqnorm)
73  {
74  // The new residual vector became too orthogonal to the arbitrarily chosen direction r0
75  // Let's restart with a new r0:
76  r = rhs - mat * x;
77  r0 = r;
78  rho = r0_sqnorm = r.squaredNorm();
79  if(restarts++ == 0)
80  i = 0;
81  }
82  Scalar beta = (rho/rho_old) * (alpha / w);
83  p = r + beta * (p - w * v);
84 
85  y = precond.solve(p);
86 
87  v.noalias() = mat * y;
88 
89  alpha = rho / r0.dot(v);
90  s = r - alpha * v;
91 
92  z = precond.solve(s);
93  t.noalias() = mat * z;
94 
95  RealScalar tmp = t.squaredNorm();
96  if(tmp>RealScalar(0))
97  w = t.dot(s) / tmp;
98  else
99  w = Scalar(0);
100  x += alpha * y + w * z;
101  r = s - w * t;
102  ++i;
103  }
104  tol_error = sqrt(r.squaredNorm()/rhs_sqnorm);
105  iters = i;
106  return true;
107 }
108 
109 }
110 
111 template< typename _MatrixType,
112  typename _Preconditioner = DiagonalPreconditioner<typename _MatrixType::Scalar> >
113 class BiCGSTAB;
114 
115 namespace internal {
116 
117 template< typename _MatrixType, typename _Preconditioner>
118 struct traits<BiCGSTAB<_MatrixType,_Preconditioner> >
119 {
120  typedef _MatrixType MatrixType;
121  typedef _Preconditioner Preconditioner;
122 };
123 
124 }
125 
157 template< typename _MatrixType, typename _Preconditioner>
158 class BiCGSTAB : public IterativeSolverBase<BiCGSTAB<_MatrixType,_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 public:
173 
175  BiCGSTAB() : Base() {}
176 
187  template<typename MatrixDerived>
188  explicit BiCGSTAB(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}
189 
191 
193  template<typename Rhs,typename Dest>
194  void _solve_with_guess_impl(const Rhs& b, Dest& x) const
195  {
196  bool failed = false;
197  for(Index j=0; j<b.cols(); ++j)
198  {
199  m_iterations = Base::maxIterations();
200  m_error = Base::m_tolerance;
201 
202  typename Dest::ColXpr xj(x,j);
203  if(!internal::bicgstab(matrix(), b.col(j), xj, Base::m_preconditioner, m_iterations, m_error))
204  failed = true;
205  }
206  m_info = failed ? NumericalIssue
207  : m_error <= Base::m_tolerance ? Success
208  : NoConvergence;
209  m_isInitialized = true;
210  }
211 
213  using Base::_solve_impl;
214  template<typename Rhs,typename Dest>
215  void _solve_impl(const MatrixBase<Rhs>& b, Dest& x) const
216  {
217  x.resize(this->rows(),b.cols());
218  x.setZero();
219  _solve_with_guess_impl(b,x);
220  }
221 
222 protected:
223 
224 };
225 
226 } // end namespace Eigen
227 
228 #endif // EIGEN_BICGSTAB_H
A preconditioner based on the digonal entries.
SCALAR Scalar
Definition: bench_gemm.cpp:33
Scalar * b
Definition: benchVecAdd.cpp:17
ArrayXcf v
Definition: Cwise_arg.cpp:1
_MatrixType MatrixType
Definition: BiCGSTAB.h:167
bool bicgstab(const MatrixType &mat, const Rhs &rhs, Dest &x, const Preconditioner &precond, Index &iters, typename Dest::RealScalar &tol_error)
Definition: BiCGSTAB.h:29
int n
_Preconditioner Preconditioner
Definition: BiCGSTAB.h:170
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
MatrixXf MatrixType
static double epsilon
Definition: testRot3.cpp:39
BiCGSTAB(const EigenBase< MatrixDerived > &A)
Definition: BiCGSTAB.h:188
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:33
RealScalar alpha
RealScalar s
NumTraits< Scalar >::Real RealScalar
Definition: bench_gemm.cpp:34
RowVector3d w
MatrixType::RealScalar RealScalar
Definition: BiCGSTAB.h:169
float * p
const G double tol
Definition: Group.h:83
A bi conjugate gradient stabilized solver for sparse square problems.
Definition: BiCGSTAB.h:113
MatrixType::Scalar Scalar
Definition: BiCGSTAB.h:168
IterativeSolverBase< BiCGSTAB > Base
Definition: BiCGSTAB.h:160
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
void _solve_with_guess_impl(const Rhs &b, Dest &x) const
Definition: BiCGSTAB.h:194
std::ptrdiff_t j
Point2 t(10, 10)
void _solve_impl(const MatrixBase< Rhs > &b, Dest &x) const
Definition: BiCGSTAB.h:215


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