PardisoSupport.h
Go to the documentation of this file.
1 /*
2  Copyright (c) 2011, Intel Corporation. All rights reserved.
3 
4  Redistribution and use in source and binary forms, with or without modification,
5  are permitted provided that the following conditions are met:
6 
7  * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright notice,
10  this list of conditions and the following disclaimer in the documentation
11  and/or other materials provided with the distribution.
12  * Neither the name of Intel Corporation nor the names of its contributors may
13  be used to endorse or promote products derived from this software without
14  specific prior written permission.
15 
16  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17  ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19  DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR
20  ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21  (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
23  ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27  ********************************************************************************
28  * Content : Eigen bindings to Intel(R) MKL PARDISO
29  ********************************************************************************
30 */
31 
32 #ifndef EIGEN_PARDISOSUPPORT_H
33 #define EIGEN_PARDISOSUPPORT_H
34 
35 namespace Eigen {
36 
37 template<typename _MatrixType> class PardisoLU;
38 template<typename _MatrixType, int Options=Upper> class PardisoLLT;
39 template<typename _MatrixType, int Options=Upper> class PardisoLDLT;
40 
41 namespace internal
42 {
43  template<typename Index>
45  {
46  static Index run( _MKL_DSS_HANDLE_t pt, Index maxfct, Index mnum, Index type, Index phase, Index n, void *a,
47  Index *ia, Index *ja, Index *perm, Index nrhs, Index *iparm, Index msglvl, void *b, void *x)
48  {
49  Index error = 0;
50  ::pardiso(pt, &maxfct, &mnum, &type, &phase, &n, a, ia, ja, perm, &nrhs, iparm, &msglvl, b, x, &error);
51  return error;
52  }
53  };
54  template<>
55  struct pardiso_run_selector<long long int>
56  {
57  typedef long long int Index;
58  static Index run( _MKL_DSS_HANDLE_t pt, Index maxfct, Index mnum, Index type, Index phase, Index n, void *a,
59  Index *ia, Index *ja, Index *perm, Index nrhs, Index *iparm, Index msglvl, void *b, void *x)
60  {
61  Index error = 0;
62  ::pardiso_64(pt, &maxfct, &mnum, &type, &phase, &n, a, ia, ja, perm, &nrhs, iparm, &msglvl, b, x, &error);
63  return error;
64  }
65  };
66 
67  template<class Pardiso> struct pardiso_traits;
68 
69  template<typename _MatrixType>
70  struct pardiso_traits< PardisoLU<_MatrixType> >
71  {
72  typedef _MatrixType MatrixType;
73  typedef typename _MatrixType::Scalar Scalar;
74  typedef typename _MatrixType::RealScalar RealScalar;
75  typedef typename _MatrixType::Index Index;
76  };
77 
78  template<typename _MatrixType, int Options>
79  struct pardiso_traits< PardisoLLT<_MatrixType, Options> >
80  {
81  typedef _MatrixType MatrixType;
82  typedef typename _MatrixType::Scalar Scalar;
83  typedef typename _MatrixType::RealScalar RealScalar;
84  typedef typename _MatrixType::Index Index;
85  };
86 
87  template<typename _MatrixType, int Options>
88  struct pardiso_traits< PardisoLDLT<_MatrixType, Options> >
89  {
90  typedef _MatrixType MatrixType;
91  typedef typename _MatrixType::Scalar Scalar;
92  typedef typename _MatrixType::RealScalar RealScalar;
93  typedef typename _MatrixType::Index Index;
94  };
95 
96 }
97 
98 template<class Derived>
100 {
102  public:
103  typedef typename Traits::MatrixType MatrixType;
104  typedef typename Traits::Scalar Scalar;
105  typedef typename Traits::RealScalar RealScalar;
106  typedef typename Traits::Index Index;
112  enum {
114  };
115 
117  {
118  eigen_assert((sizeof(Index) >= sizeof(_INTEGER_t) && sizeof(Index) <= 8) && "Non-supported index type");
119  m_iparm.setZero();
120  m_msglvl = 0; // No output
121  m_initialized = false;
122  }
123 
125  {
126  pardisoRelease();
127  }
128 
129  inline Index cols() const { return m_size; }
130  inline Index rows() const { return m_size; }
131 
138  {
139  eigen_assert(m_initialized && "Decomposition is not initialized.");
140  return m_info;
141  }
142 
146  ParameterType& pardisoParameterArray()
147  {
148  return m_iparm;
149  }
150 
157  Derived& analyzePattern(const MatrixType& matrix);
158 
165  Derived& factorize(const MatrixType& matrix);
166 
167  Derived& compute(const MatrixType& matrix);
168 
173  template<typename Rhs>
175  solve(const MatrixBase<Rhs>& b) const
176  {
177  eigen_assert(m_initialized && "Pardiso solver is not initialized.");
178  eigen_assert(rows()==b.rows()
179  && "PardisoImpl::solve(): invalid number of rows of the right hand side matrix b");
180  return internal::solve_retval<PardisoImpl, Rhs>(*this, b.derived());
181  }
182 
187  template<typename Rhs>
189  solve(const SparseMatrixBase<Rhs>& b) const
190  {
191  eigen_assert(m_initialized && "Pardiso solver is not initialized.");
192  eigen_assert(rows()==b.rows()
193  && "PardisoImpl::solve(): invalid number of rows of the right hand side matrix b");
195  }
196 
197  Derived& derived()
198  {
199  return *static_cast<Derived*>(this);
200  }
201  const Derived& derived() const
202  {
203  return *static_cast<const Derived*>(this);
204  }
205 
206  template<typename BDerived, typename XDerived>
207  bool _solve(const MatrixBase<BDerived> &b, MatrixBase<XDerived>& x) const;
208 
209  protected:
211  {
212  if(m_initialized) // Factorization ran at least once
213  {
214  internal::pardiso_run_selector<Index>::run(m_pt, 1, 1, m_type, -1, m_size, 0, 0, 0, m_perm.data(), 0,
215  m_iparm.data(), m_msglvl, 0, 0);
216  }
217  }
218 
219  void pardisoInit(int type)
220  {
221  m_type = type;
222  bool symmetric = abs(m_type) < 10;
223  m_iparm[0] = 1; // No solver default
224  m_iparm[1] = 3; // use Metis for the ordering
225  m_iparm[2] = 1; // Numbers of processors, value of OMP_NUM_THREADS
226  m_iparm[3] = 0; // No iterative-direct algorithm
227  m_iparm[4] = 0; // No user fill-in reducing permutation
228  m_iparm[5] = 0; // Write solution into x
229  m_iparm[6] = 0; // Not in use
230  m_iparm[7] = 2; // Max numbers of iterative refinement steps
231  m_iparm[8] = 0; // Not in use
232  m_iparm[9] = 13; // Perturb the pivot elements with 1E-13
233  m_iparm[10] = symmetric ? 0 : 1; // Use nonsymmetric permutation and scaling MPS
234  m_iparm[11] = 0; // Not in use
235  m_iparm[12] = symmetric ? 0 : 1; // Maximum weighted matching algorithm is switched-off (default for symmetric).
236  // Try m_iparm[12] = 1 in case of inappropriate accuracy
237  m_iparm[13] = 0; // Output: Number of perturbed pivots
238  m_iparm[14] = 0; // Not in use
239  m_iparm[15] = 0; // Not in use
240  m_iparm[16] = 0; // Not in use
241  m_iparm[17] = -1; // Output: Number of nonzeros in the factor LU
242  m_iparm[18] = -1; // Output: Mflops for LU factorization
243  m_iparm[19] = 0; // Output: Numbers of CG Iterations
244 
245  m_iparm[20] = 0; // 1x1 pivoting
246  m_iparm[26] = 0; // No matrix checker
247  m_iparm[27] = (sizeof(RealScalar) == 4) ? 1 : 0;
248  m_iparm[34] = 1; // C indexing
249  m_iparm[59] = 1; // Automatic switch between In-Core and Out-of-Core modes
250  }
251 
252  protected:
253  // cached data to reduce reallocation, etc.
254 
255  void manageErrorCode(Index error)
256  {
257  switch(error)
258  {
259  case 0:
260  m_info = Success;
261  break;
262  case -4:
263  case -7:
264  m_info = NumericalIssue;
265  break;
266  default:
267  m_info = InvalidInput;
268  }
269  }
270 
271  mutable SparseMatrixType m_matrix;
273  bool m_initialized, m_analysisIsOk, m_factorizationIsOk;
274  Index m_type, m_msglvl;
275  mutable void *m_pt[64];
276  mutable ParameterType m_iparm;
277  mutable IntColVectorType m_perm;
278  Index m_size;
279 
280  private:
282 };
283 
284 template<class Derived>
286 {
287  m_size = a.rows();
288  eigen_assert(a.rows() == a.cols());
289 
290  pardisoRelease();
291  memset(m_pt, 0, sizeof(m_pt));
292  m_perm.setZero(m_size);
293  derived().getMatrix(a);
294 
295  Index error;
296  error = internal::pardiso_run_selector<Index>::run(m_pt, 1, 1, m_type, 12, m_size,
297  m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),
298  m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);
299 
300  manageErrorCode(error);
301  m_analysisIsOk = true;
302  m_factorizationIsOk = true;
303  m_initialized = true;
304  return derived();
305 }
306 
307 template<class Derived>
309 {
310  m_size = a.rows();
311  eigen_assert(m_size == a.cols());
312 
313  pardisoRelease();
314  memset(m_pt, 0, sizeof(m_pt));
315  m_perm.setZero(m_size);
316  derived().getMatrix(a);
317 
318  Index error;
319  error = internal::pardiso_run_selector<Index>::run(m_pt, 1, 1, m_type, 11, m_size,
320  m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),
321  m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);
322 
323  manageErrorCode(error);
324  m_analysisIsOk = true;
325  m_factorizationIsOk = false;
326  m_initialized = true;
327  return derived();
328 }
329 
330 template<class Derived>
332 {
333  eigen_assert(m_analysisIsOk && "You must first call analyzePattern()");
334  eigen_assert(m_size == a.rows() && m_size == a.cols());
335 
336  derived().getMatrix(a);
337 
338  Index error;
339  error = internal::pardiso_run_selector<Index>::run(m_pt, 1, 1, m_type, 22, m_size,
340  m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),
341  m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);
342 
343  manageErrorCode(error);
344  m_factorizationIsOk = true;
345  return derived();
346 }
347 
348 template<class Base>
349 template<typename BDerived,typename XDerived>
351 {
352  if(m_iparm[0] == 0) // Factorization was not computed
353  return false;
354 
355  //Index n = m_matrix.rows();
356  Index nrhs = Index(b.cols());
357  eigen_assert(m_size==b.rows());
358  eigen_assert(((MatrixBase<BDerived>::Flags & RowMajorBit) == 0 || nrhs == 1) && "Row-major right hand sides are not supported");
359  eigen_assert(((MatrixBase<XDerived>::Flags & RowMajorBit) == 0 || nrhs == 1) && "Row-major matrices of unknowns are not supported");
360  eigen_assert(((nrhs == 1) || b.outerStride() == b.rows()));
361 
362 
363 // switch (transposed) {
364 // case SvNoTrans : m_iparm[11] = 0 ; break;
365 // case SvTranspose : m_iparm[11] = 2 ; break;
366 // case SvAdjoint : m_iparm[11] = 1 ; break;
367 // default:
368 // //std::cerr << "Eigen: transposition option \"" << transposed << "\" not supported by the PARDISO backend\n";
369 // m_iparm[11] = 0;
370 // }
371 
372  Scalar* rhs_ptr = const_cast<Scalar*>(b.derived().data());
374 
375  // Pardiso cannot solve in-place
376  if(rhs_ptr == x.derived().data())
377  {
378  tmp = b;
379  rhs_ptr = tmp.data();
380  }
381 
382  Index error;
383  error = internal::pardiso_run_selector<Index>::run(m_pt, 1, 1, m_type, 33, m_size,
384  m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),
385  m_perm.data(), nrhs, m_iparm.data(), m_msglvl,
386  rhs_ptr, x.derived().data());
387 
388  return error==0;
389 }
390 
391 
404 template<typename MatrixType>
405 class PardisoLU : public PardisoImpl< PardisoLU<MatrixType> >
406 {
407  protected:
409  typedef typename Base::Scalar Scalar;
410  typedef typename Base::RealScalar RealScalar;
411  using Base::pardisoInit;
412  using Base::m_matrix;
413  friend class PardisoImpl< PardisoLU<MatrixType> >;
414 
415  public:
416 
417  using Base::compute;
418  using Base::solve;
419 
421  : Base()
422  {
423  pardisoInit(Base::ScalarIsComplex ? 13 : 11);
424  }
425 
426  PardisoLU(const MatrixType& matrix)
427  : Base()
428  {
429  pardisoInit(Base::ScalarIsComplex ? 13 : 11);
430  compute(matrix);
431  }
432  protected:
433  void getMatrix(const MatrixType& matrix)
434  {
435  m_matrix = matrix;
436  }
437 
438  private:
440 };
441 
456 template<typename MatrixType, int _UpLo>
457 class PardisoLLT : public PardisoImpl< PardisoLLT<MatrixType,_UpLo> >
458 {
459  protected:
461  typedef typename Base::Scalar Scalar;
462  typedef typename Base::Index Index;
463  typedef typename Base::RealScalar RealScalar;
464  using Base::pardisoInit;
465  using Base::m_matrix;
466  friend class PardisoImpl< PardisoLLT<MatrixType,_UpLo> >;
467 
468  public:
469 
470  enum { UpLo = _UpLo };
471  using Base::compute;
472  using Base::solve;
473 
475  : Base()
476  {
477  pardisoInit(Base::ScalarIsComplex ? 4 : 2);
478  }
479 
480  PardisoLLT(const MatrixType& matrix)
481  : Base()
482  {
483  pardisoInit(Base::ScalarIsComplex ? 4 : 2);
484  compute(matrix);
485  }
486 
487  protected:
488 
489  void getMatrix(const MatrixType& matrix)
490  {
491  // PARDISO supports only upper, row-major matrices
493  m_matrix.resize(matrix.rows(), matrix.cols());
494  m_matrix.template selfadjointView<Upper>() = matrix.template selfadjointView<UpLo>().twistedBy(p_null);
495  }
496 
497  private:
499 };
500 
517 template<typename MatrixType, int Options>
518 class PardisoLDLT : public PardisoImpl< PardisoLDLT<MatrixType,Options> >
519 {
520  protected:
522  typedef typename Base::Scalar Scalar;
523  typedef typename Base::Index Index;
524  typedef typename Base::RealScalar RealScalar;
525  using Base::pardisoInit;
526  using Base::m_matrix;
527  friend class PardisoImpl< PardisoLDLT<MatrixType,Options> >;
528 
529  public:
530 
531  using Base::compute;
532  using Base::solve;
533  enum { UpLo = Options&(Upper|Lower) };
534 
536  : Base()
537  {
538  pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2);
539  }
540 
541  PardisoLDLT(const MatrixType& matrix)
542  : Base()
543  {
544  pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2);
545  compute(matrix);
546  }
547 
548  void getMatrix(const MatrixType& matrix)
549  {
550  // PARDISO supports only upper, row-major matrices
552  m_matrix.resize(matrix.rows(), matrix.cols());
553  m_matrix.template selfadjointView<Upper>() = matrix.template selfadjointView<UpLo>().twistedBy(p_null);
554  }
555 
556  private:
558 };
559 
560 namespace internal {
561 
562 template<typename _Derived, typename Rhs>
563 struct solve_retval<PardisoImpl<_Derived>, Rhs>
564  : solve_retval_base<PardisoImpl<_Derived>, Rhs>
565 {
567  EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs)
568 
569  template<typename Dest> void evalTo(Dest& dst) const
570  {
571  dec()._solve(rhs(),dst);
572  }
573 };
574 
575 template<typename Derived, typename Rhs>
576 struct sparse_solve_retval<PardisoImpl<Derived>, Rhs>
577  : sparse_solve_retval_base<PardisoImpl<Derived>, Rhs>
578 {
581 
582  template<typename Dest> void evalTo(Dest& dst) const
583  {
584  this->defaultEvalTo(dst);
585  }
586 };
587 
588 } // end namespace internal
589 
590 } // end namespace Eigen
591 
592 #endif // EIGEN_PARDISOSUPPORT_H
Traits::Index Index
static Index run(_MKL_DSS_HANDLE_t pt, Index maxfct, Index mnum, Index type, Index phase, Index n, void *a, Index *ia, Index *ja, Index *perm, Index nrhs, Index *iparm, Index msglvl, void *b, void *x)
PardisoImpl< PardisoLU< MatrixType > > Base
Derived & compute(const MatrixType &matrix)
Matrix< Index, MatrixType::RowsAtCompileTime, 1 > IntColVectorType
Derived & factorize(const MatrixType &matrix)
Index rows() const
PardisoLDLT(const MatrixType &matrix)
PardisoLDLT(PardisoLDLT &)
Definition: LDLT.h:16
const Derived & derived() const
PardisoImpl< PardisoLLT< MatrixType, _UpLo > > Base
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
Definition: NumTraits.h:88
const internal::solve_retval< PardisoImpl, Rhs > solve(const MatrixBase< Rhs > &b) const
void getMatrix(const MatrixType &matrix)
const unsigned int RowMajorBit
Definition: Constants.h:53
void manageErrorCode(Index error)
Traits::RealScalar RealScalar
PardisoImpl(PardisoImpl &)
EIGEN_STRONG_INLINE const CwiseUnaryOp< internal::scalar_abs_op< Scalar >, const Derived > abs() const
Base::RealScalar RealScalar
A sparse direct Cholesky (LLT) factorization and solver based on the PARDISO library.
SparseMatrix< Scalar, RowMajor, Index > SparseMatrixType
Base::Scalar Scalar
void pardisoInit(int type)
Base class of any sparse matrices or sparse expressions.
Derived & analyzePattern(const MatrixType &matrix)
ComputationInfo m_info
Traits::Scalar Scalar
const internal::sparse_solve_retval< PardisoImpl, Rhs > solve(const SparseMatrixBase< Rhs > &b) const
Base::RealScalar RealScalar
static Index run(_MKL_DSS_HANDLE_t pt, Index maxfct, Index mnum, Index type, Index phase, Index n, void *a, Index *ia, Index *ja, Index *perm, Index nrhs, Index *iparm, Index msglvl, void *b, void *x)
TFSIMD_FORCE_INLINE const tfScalar & x() const
A sparse direct LU factorization and solver based on the PARDISO library.
Matrix< Scalar, Dynamic, 1 > VectorType
#define EIGEN_MAKE_SPARSE_SOLVE_HELPERS(DecompositionType, Rhs)
Definition: SparseSolve.h:71
PardisoLU(PardisoLU &)
Base::Scalar Scalar
PardisoLLT(PardisoLLT &)
internal::pardiso_traits< Derived > Traits
const Derived & derived() const
ComputationInfo info() const
Reports whether previous computation was successful.
void getMatrix(const MatrixType &matrix)
Matrix< Index, 1, MatrixType::ColsAtCompileTime > IntRowVectorType
Base::RealScalar RealScalar
PardisoImpl< PardisoLDLT< MatrixType, Options > > Base
bool _solve(const MatrixBase< BDerived > &b, MatrixBase< XDerived > &x) const
A sparse direct Cholesky (LDLT) factorization and solver based on the PARDISO library.
#define EIGEN_MAKE_SOLVE_HELPERS(DecompositionType, Rhs)
Definition: Solve.h:61
ParameterType & pardisoParameterArray()
void getMatrix(const MatrixType &matrix)
Array< Index, 64, 1, DontAlign > ParameterType
Base::Scalar Scalar
Index cols() const
ParameterType m_iparm
Traits::MatrixType MatrixType
#define eigen_assert(x)
void resize(Index newSize)
ComputationInfo
Definition: Constants.h:374
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
IntColVectorType m_perm
SparseMatrixType m_matrix
PardisoLLT(const MatrixType &matrix)
PardisoLU(const MatrixType &matrix)


tuw_aruco
Author(s): Lukas Pfeifhofer
autogenerated on Mon Jun 10 2019 15:40:55