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 IndexType>
45  {
46  static IndexType run( _MKL_DSS_HANDLE_t pt, IndexType maxfct, IndexType mnum, IndexType type, IndexType phase, IndexType n, void *a,
47  IndexType *ia, IndexType *ja, IndexType *perm, IndexType nrhs, IndexType *iparm, IndexType msglvl, void *b, void *x)
48  {
49  IndexType 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 IndexType;
58  static IndexType run( _MKL_DSS_HANDLE_t pt, IndexType maxfct, IndexType mnum, IndexType type, IndexType phase, IndexType n, void *a,
59  IndexType *ia, IndexType *ja, IndexType *perm, IndexType nrhs, IndexType *iparm, IndexType msglvl, void *b, void *x)
60  {
61  IndexType 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;
75  typedef typename _MatrixType::StorageIndex StorageIndex;
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;
84  typedef typename _MatrixType::StorageIndex StorageIndex;
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;
93  typedef typename _MatrixType::StorageIndex StorageIndex;
94  };
95 
96 } // end namespace internal
97 
98 template<class Derived>
99 class PardisoImpl : public SparseSolverBase<Derived>
100 {
101  protected:
103  using Base::derived;
104  using Base::m_isInitialized;
105 
107  public:
108  using Base::_solve_impl;
109 
110  typedef typename Traits::MatrixType MatrixType;
111  typedef typename Traits::Scalar Scalar;
112  typedef typename Traits::RealScalar RealScalar;
113  typedef typename Traits::StorageIndex StorageIndex;
119  enum {
123  };
124 
126  {
127  eigen_assert((sizeof(StorageIndex) >= sizeof(_INTEGER_t) && sizeof(StorageIndex) <= 8) && "Non-supported index type");
128  m_iparm.setZero();
129  m_msglvl = 0; // No output
130  m_isInitialized = false;
131  }
132 
134  {
135  pardisoRelease();
136  }
137 
138  inline Index cols() const { return m_size; }
139  inline Index rows() const { return m_size; }
140 
147  {
148  eigen_assert(m_isInitialized && "Decomposition is not initialized.");
149  return m_info;
150  }
151 
156  {
157  return m_iparm;
158  }
159 
166  Derived& analyzePattern(const MatrixType& matrix);
167 
174  Derived& factorize(const MatrixType& matrix);
175 
176  Derived& compute(const MatrixType& matrix);
177 
178  template<typename Rhs,typename Dest>
179  void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const;
180 
181  protected:
183  {
184  if(m_isInitialized) // Factorization ran at least once
185  {
186  internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, -1, internal::convert_index<StorageIndex>(m_size),0, 0, 0, m_perm.data(), 0,
187  m_iparm.data(), m_msglvl, NULL, NULL);
188  m_isInitialized = false;
189  }
190  }
191 
192  void pardisoInit(int type)
193  {
194  m_type = type;
195  bool symmetric = std::abs(m_type) < 10;
196  m_iparm[0] = 1; // No solver default
197  m_iparm[1] = 2; // use Metis for the ordering
198  m_iparm[2] = 0; // Reserved. Set to zero. (??Numbers of processors, value of OMP_NUM_THREADS??)
199  m_iparm[3] = 0; // No iterative-direct algorithm
200  m_iparm[4] = 0; // No user fill-in reducing permutation
201  m_iparm[5] = 0; // Write solution into x, b is left unchanged
202  m_iparm[6] = 0; // Not in use
203  m_iparm[7] = 2; // Max numbers of iterative refinement steps
204  m_iparm[8] = 0; // Not in use
205  m_iparm[9] = 13; // Perturb the pivot elements with 1E-13
206  m_iparm[10] = symmetric ? 0 : 1; // Use nonsymmetric permutation and scaling MPS
207  m_iparm[11] = 0; // Not in use
208  m_iparm[12] = symmetric ? 0 : 1; // Maximum weighted matching algorithm is switched-off (default for symmetric).
209  // Try m_iparm[12] = 1 in case of inappropriate accuracy
210  m_iparm[13] = 0; // Output: Number of perturbed pivots
211  m_iparm[14] = 0; // Not in use
212  m_iparm[15] = 0; // Not in use
213  m_iparm[16] = 0; // Not in use
214  m_iparm[17] = -1; // Output: Number of nonzeros in the factor LU
215  m_iparm[18] = -1; // Output: Mflops for LU factorization
216  m_iparm[19] = 0; // Output: Numbers of CG Iterations
217 
218  m_iparm[20] = 0; // 1x1 pivoting
219  m_iparm[26] = 0; // No matrix checker
220  m_iparm[27] = (sizeof(RealScalar) == 4) ? 1 : 0;
221  m_iparm[34] = 1; // C indexing
222  m_iparm[36] = 0; // CSR
223  m_iparm[59] = 0; // 0 - In-Core ; 1 - Automatic switch between In-Core and Out-of-Core modes ; 2 - Out-of-Core
224 
225  memset(m_pt, 0, sizeof(m_pt));
226  }
227 
228  protected:
229  // cached data to reduce reallocation, etc.
230 
231  void manageErrorCode(Index error) const
232  {
233  switch(error)
234  {
235  case 0:
236  m_info = Success;
237  break;
238  case -4:
239  case -7:
241  break;
242  default:
244  }
245  }
246 
251  mutable void *m_pt[64];
255 
256 };
257 
258 template<class Derived>
260 {
261  m_size = a.rows();
262  eigen_assert(a.rows() == a.cols());
263 
264  pardisoRelease();
265  m_perm.setZero(m_size);
266  derived().getMatrix(a);
267 
268  Index error;
269  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 12, internal::convert_index<StorageIndex>(m_size),
270  m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),
271  m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);
272  manageErrorCode(error);
273  m_analysisIsOk = true;
274  m_factorizationIsOk = true;
275  m_isInitialized = true;
276  return derived();
277 }
278 
279 template<class Derived>
281 {
282  m_size = a.rows();
283  eigen_assert(m_size == a.cols());
284 
285  pardisoRelease();
286  m_perm.setZero(m_size);
287  derived().getMatrix(a);
288 
289  Index error;
290  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 11, internal::convert_index<StorageIndex>(m_size),
291  m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),
292  m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);
293 
294  manageErrorCode(error);
295  m_analysisIsOk = true;
296  m_factorizationIsOk = false;
297  m_isInitialized = true;
298  return derived();
299 }
300 
301 template<class Derived>
303 {
304  eigen_assert(m_analysisIsOk && "You must first call analyzePattern()");
305  eigen_assert(m_size == a.rows() && m_size == a.cols());
306 
307  derived().getMatrix(a);
308 
309  Index error;
310  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 22, internal::convert_index<StorageIndex>(m_size),
311  m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),
312  m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);
313 
314  manageErrorCode(error);
315  m_factorizationIsOk = true;
316  return derived();
317 }
318 
319 template<class Derived>
320 template<typename BDerived,typename XDerived>
322 {
323  if(m_iparm[0] == 0) // Factorization was not computed
324  {
325  m_info = InvalidInput;
326  return;
327  }
328 
329  //Index n = m_matrix.rows();
330  Index nrhs = Index(b.cols());
331  eigen_assert(m_size==b.rows());
332  eigen_assert(((MatrixBase<BDerived>::Flags & RowMajorBit) == 0 || nrhs == 1) && "Row-major right hand sides are not supported");
333  eigen_assert(((MatrixBase<XDerived>::Flags & RowMajorBit) == 0 || nrhs == 1) && "Row-major matrices of unknowns are not supported");
334  eigen_assert(((nrhs == 1) || b.outerStride() == b.rows()));
335 
336 
337 // switch (transposed) {
338 // case SvNoTrans : m_iparm[11] = 0 ; break;
339 // case SvTranspose : m_iparm[11] = 2 ; break;
340 // case SvAdjoint : m_iparm[11] = 1 ; break;
341 // default:
342 // //std::cerr << "Eigen: transposition option \"" << transposed << "\" not supported by the PARDISO backend\n";
343 // m_iparm[11] = 0;
344 // }
345 
346  Scalar* rhs_ptr = const_cast<Scalar*>(b.derived().data());
348 
349  // Pardiso cannot solve in-place
350  if(rhs_ptr == x.derived().data())
351  {
352  tmp = b;
353  rhs_ptr = tmp.data();
354  }
355 
356  Index error;
357  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 33, internal::convert_index<StorageIndex>(m_size),
358  m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),
359  m_perm.data(), internal::convert_index<StorageIndex>(nrhs), m_iparm.data(), m_msglvl,
360  rhs_ptr, x.derived().data());
361 
362  manageErrorCode(error);
363 }
364 
365 
383 template<typename MatrixType>
384 class PardisoLU : public PardisoImpl< PardisoLU<MatrixType> >
385 {
386  protected:
388  typedef typename Base::Scalar Scalar;
389  typedef typename Base::RealScalar RealScalar;
390  using Base::pardisoInit;
391  using Base::m_matrix;
392  friend class PardisoImpl< PardisoLU<MatrixType> >;
393 
394  public:
395 
396  using Base::compute;
397  using Base::solve;
398 
400  : Base()
401  {
403  }
404 
405  explicit PardisoLU(const MatrixType& matrix)
406  : Base()
407  {
409  compute(matrix);
410  }
411  protected:
413  {
414  m_matrix = matrix;
415  m_matrix.makeCompressed();
416  }
417 };
418 
438 template<typename MatrixType, int _UpLo>
439 class PardisoLLT : public PardisoImpl< PardisoLLT<MatrixType,_UpLo> >
440 {
441  protected:
443  typedef typename Base::Scalar Scalar;
444  typedef typename Base::RealScalar RealScalar;
445  using Base::pardisoInit;
446  using Base::m_matrix;
447  friend class PardisoImpl< PardisoLLT<MatrixType,_UpLo> >;
448 
449  public:
450 
452  enum { UpLo = _UpLo };
453  using Base::compute;
454 
456  : Base()
457  {
459  }
460 
461  explicit PardisoLLT(const MatrixType& matrix)
462  : Base()
463  {
465  compute(matrix);
466  }
467 
468  protected:
469 
471  {
472  // PARDISO supports only upper, row-major matrices
474  m_matrix.resize(matrix.rows(), matrix.cols());
475  m_matrix.template selfadjointView<Upper>() = matrix.template selfadjointView<UpLo>().twistedBy(p_null);
476  m_matrix.makeCompressed();
477  }
478 };
479 
501 template<typename MatrixType, int Options>
502 class PardisoLDLT : public PardisoImpl< PardisoLDLT<MatrixType,Options> >
503 {
504  protected:
506  typedef typename Base::Scalar Scalar;
507  typedef typename Base::RealScalar RealScalar;
508  using Base::pardisoInit;
509  using Base::m_matrix;
510  friend class PardisoImpl< PardisoLDLT<MatrixType,Options> >;
511 
512  public:
513 
515  using Base::compute;
516  enum { UpLo = Options&(Upper|Lower) };
517 
519  : Base()
520  {
521  pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2);
522  }
523 
524  explicit PardisoLDLT(const MatrixType& matrix)
525  : Base()
526  {
527  pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2);
528  compute(matrix);
529  }
530 
532  {
533  // PARDISO supports only upper, row-major matrices
535  m_matrix.resize(matrix.rows(), matrix.cols());
536  m_matrix.template selfadjointView<Upper>() = matrix.template selfadjointView<UpLo>().twistedBy(p_null);
537  m_matrix.makeCompressed();
538  }
539 };
540 
541 } // end namespace Eigen
542 
543 #endif // EIGEN_PARDISOSUPPORT_H
Eigen::PardisoImpl::compute
Derived & compute(const MatrixType &matrix)
Definition: PardisoSupport.h:259
Eigen::PardisoImpl::m_size
Index m_size
Definition: PardisoSupport.h:254
Eigen::NumericalIssue
@ NumericalIssue
Definition: Constants.h:434
Eigen::PardisoLLT::m_matrix
SparseMatrixType m_matrix
Definition: PardisoSupport.h:247
Eigen::PardisoImpl::m_iparm
ParameterType m_iparm
Definition: PardisoSupport.h:252
Eigen::internal::pardiso_traits< PardisoLU< _MatrixType > >::MatrixType
_MatrixType MatrixType
Definition: PardisoSupport.h:72
Eigen::Symmetric
@ Symmetric
Definition: Constants.h:222
Eigen
Definition: common.h:73
Eigen::PardisoImpl::IntRowVectorType
Matrix< StorageIndex, 1, MatrixType::ColsAtCompileTime > IntRowVectorType
Definition: PardisoSupport.h:116
Eigen::SparseMatrix< Scalar, RowMajor, StorageIndex >
Eigen::PardisoLDLT::PardisoLDLT
PardisoLDLT(const MatrixType &matrix)
Definition: PardisoSupport.h:524
b
Scalar * b
Definition: cholesky.cpp:56
MatrixType
Map< Matrix< Scalar, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > MatrixType
Definition: common.h:95
Eigen::PardisoImpl::StorageIndex
Traits::StorageIndex StorageIndex
Definition: PardisoSupport.h:113
Eigen::PardisoLLT::PardisoLLT
PardisoLLT(const MatrixType &matrix)
Definition: PardisoSupport.h:461
Eigen::SparseSolverBase::_solve_impl
void _solve_impl(const SparseMatrixBase< Rhs > &b, SparseMatrixBase< Dest > &dest) const
Definition: SparseSolverBase.h:111
Eigen::PardisoImpl::pardisoRelease
void pardisoRelease()
Definition: PardisoSupport.h:182
Eigen::PardisoLU::m_matrix
SparseMatrixType m_matrix
Definition: PardisoSupport.h:247
Eigen::PardisoImpl::IntColVectorType
Matrix< StorageIndex, MatrixType::RowsAtCompileTime, 1 > IntColVectorType
Definition: PardisoSupport.h:117
Eigen::PardisoImpl::MatrixType
Traits::MatrixType MatrixType
Definition: PardisoSupport.h:110
Eigen::PardisoImpl::_solve_impl
void _solve_impl(const MatrixBase< Rhs > &b, MatrixBase< Dest > &dest) const
RealScalar
NumTraits< Scalar >::Real RealScalar
Definition: common.h:85
Eigen::PardisoImpl::m_type
StorageIndex m_type
Definition: PardisoSupport.h:250
eigen_assert
#define eigen_assert(x)
Definition: Macros.h:579
Eigen::PardisoLDLT
A sparse direct Cholesky (LDLT) factorization and solver based on the PARDISO library.
Definition: PardisoSupport.h:39
Eigen::internal::pardiso_traits< PardisoLLT< _MatrixType, Options > >::RealScalar
_MatrixType::RealScalar RealScalar
Definition: PardisoSupport.h:83
Eigen::PardisoLU::RealScalar
Base::RealScalar RealScalar
Definition: PardisoSupport.h:389
Eigen::PardisoLLT::compute
Derived & compute(const MatrixType &matrix)
Definition: PardisoSupport.h:259
Eigen::RowMajorBit
const unsigned int RowMajorBit
Definition: Constants.h:61
Eigen::PardisoLDLT::Scalar
Base::Scalar Scalar
Definition: PardisoSupport.h:506
Eigen::Upper
@ Upper
Definition: Constants.h:206
Eigen::PardisoImpl::MaxColsAtCompileTime
@ MaxColsAtCompileTime
Definition: PardisoSupport.h:122
Eigen::internal::pardiso_traits< PardisoLDLT< _MatrixType, Options > >::Scalar
_MatrixType::Scalar Scalar
Definition: PardisoSupport.h:91
Eigen::Success
@ Success
Definition: Constants.h:432
Eigen::Array< StorageIndex, 64, 1, DontAlign >
Eigen::PardisoLU::Base
PardisoImpl< PardisoLU > Base
Definition: PardisoSupport.h:387
Eigen::internal::pardiso_traits< PardisoLU< _MatrixType > >::Scalar
_MatrixType::Scalar Scalar
Definition: PardisoSupport.h:73
Eigen::PardisoLDLT::getMatrix
void getMatrix(const MatrixType &matrix)
Definition: PardisoSupport.h:531
Scalar
SCALAR Scalar
Definition: common.h:84
Eigen::internal::pardiso_traits< PardisoLLT< _MatrixType, Options > >::StorageIndex
_MatrixType::StorageIndex StorageIndex
Definition: PardisoSupport.h:84
Eigen::PardisoImpl::pardisoInit
void pardisoInit(int type)
Definition: PardisoSupport.h:192
Eigen::internal::pardiso_run_selector::run
static IndexType run(_MKL_DSS_HANDLE_t pt, IndexType maxfct, IndexType mnum, IndexType type, IndexType phase, IndexType n, void *a, IndexType *ia, IndexType *ja, IndexType *perm, IndexType nrhs, IndexType *iparm, IndexType msglvl, void *b, void *x)
Definition: PardisoSupport.h:46
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: common.h:102
Eigen::PardisoImpl::analyzePattern
Derived & analyzePattern(const MatrixType &matrix)
Definition: PardisoSupport.h:280
Eigen::PardisoImpl
Definition: PardisoSupport.h:99
Eigen::PardisoLU::compute
Derived & compute(const MatrixType &matrix)
Definition: PardisoSupport.h:259
Eigen::PardisoImpl::m_info
ComputationInfo m_info
Definition: PardisoSupport.h:248
Eigen::internal::pardiso_traits< PardisoLDLT< _MatrixType, Options > >::MatrixType
_MatrixType MatrixType
Definition: PardisoSupport.h:90
Eigen::PardisoLU::PardisoLU
PardisoLU(const MatrixType &matrix)
Definition: PardisoSupport.h:405
Eigen::internal::pardiso_traits
Definition: PardisoSupport.h:67
Eigen::PardisoLU::Scalar
Base::Scalar Scalar
Definition: PardisoSupport.h:388
Eigen::PardisoImpl::m_msglvl
StorageIndex m_msglvl
Definition: PardisoSupport.h:250
Eigen::PardisoLLT::StorageIndex
Base::StorageIndex StorageIndex
Definition: PardisoSupport.h:451
Eigen::PardisoLLT::pardisoInit
void pardisoInit(int type)
Definition: PardisoSupport.h:192
Eigen::internal::pardiso_traits< PardisoLLT< _MatrixType, Options > >::MatrixType
_MatrixType MatrixType
Definition: PardisoSupport.h:81
abs
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE AbsReturnType abs() const
Definition: ArrayCwiseUnaryOps.h:43
Eigen::PardisoImpl::ColsAtCompileTime
@ ColsAtCompileTime
Definition: PardisoSupport.h:121
Eigen::PardisoImpl::manageErrorCode
void manageErrorCode(Index error) const
Definition: PardisoSupport.h:231
Eigen::PardisoImpl::ParameterType
Array< StorageIndex, 64, 1, DontAlign > ParameterType
Definition: PardisoSupport.h:118
Eigen::internal::pardiso_traits< PardisoLDLT< _MatrixType, Options > >::StorageIndex
_MatrixType::StorageIndex StorageIndex
Definition: PardisoSupport.h:93
Eigen::PardisoLLT::getMatrix
void getMatrix(const MatrixType &matrix)
Definition: PardisoSupport.h:470
Eigen::PardisoLU::getMatrix
void getMatrix(const MatrixType &matrix)
Definition: PardisoSupport.h:412
Eigen::Dynamic
const int Dynamic
Definition: Constants.h:21
Eigen::SparseSolverBase::solve
const Solve< Derived, Rhs > solve(const MatrixBase< Rhs > &b) const
Definition: SparseSolverBase.h:88
x
Scalar * x
Definition: level1_cplx_impl.h:89
Eigen::PardisoLDLT::Base
PardisoImpl< PardisoLDLT< MatrixType, Options > > Base
Definition: PardisoSupport.h:505
Eigen::PardisoImpl::Base
SparseSolverBase< Derived > Base
Definition: PardisoSupport.h:102
Eigen::PardisoLDLT::pardisoInit
void pardisoInit(int type)
Definition: PardisoSupport.h:192
Eigen::PardisoImpl::info
ComputationInfo info() const
Reports whether previous computation was successful.
Definition: PardisoSupport.h:146
Eigen::PardisoLU::PardisoLU
PardisoLU()
Definition: PardisoSupport.h:399
Eigen::PardisoImpl::RealScalar
Traits::RealScalar RealScalar
Definition: PardisoSupport.h:112
Eigen::PardisoImpl::VectorType
Matrix< Scalar, Dynamic, 1 > VectorType
Definition: PardisoSupport.h:115
Eigen::internal::pardiso_run_selector
Definition: PardisoSupport.h:44
Eigen::Lower
@ Lower
Definition: Constants.h:204
Eigen::Map< Matrix< Scalar, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> >
int
return int(ret)+1
Eigen::PardisoLU
A sparse direct LU factorization and solver based on the PARDISO library.
Definition: PardisoSupport.h:37
Eigen::PardisoImpl::m_factorizationIsOk
bool m_factorizationIsOk
Definition: PardisoSupport.h:249
Eigen::PardisoLLT::Scalar
Base::Scalar Scalar
Definition: PardisoSupport.h:443
Eigen::PardisoLLT::Base
PardisoImpl< PardisoLLT< MatrixType, _UpLo > > Base
Definition: PardisoSupport.h:442
Eigen::PardisoLLT::RealScalar
Base::RealScalar RealScalar
Definition: PardisoSupport.h:444
Eigen::PardisoLDLT::PardisoLDLT
PardisoLDLT()
Definition: PardisoSupport.h:518
Eigen::SparseSolverBase
A base class for sparse solvers.
Definition: SparseSolverBase.h:67
Eigen::PardisoLDLT::m_matrix
SparseMatrixType m_matrix
Definition: PardisoSupport.h:247
Eigen::PardisoImpl::m_pt
void * m_pt[64]
Definition: PardisoSupport.h:251
Eigen::PardisoLDLT::StorageIndex
Base::StorageIndex StorageIndex
Definition: PardisoSupport.h:514
Eigen::PardisoImpl::PardisoImpl
PardisoImpl()
Definition: PardisoSupport.h:125
Eigen::SparseSolverBase::derived
Derived & derived()
Definition: SparseSolverBase.h:79
a
Scalar * a
Definition: cholesky.cpp:26
Eigen::PardisoImpl::m_analysisIsOk
bool m_analysisIsOk
Definition: PardisoSupport.h:249
Eigen::internal::pardiso_traits< PardisoLDLT< _MatrixType, Options > >::RealScalar
_MatrixType::RealScalar RealScalar
Definition: PardisoSupport.h:92
Eigen::PermutationMatrix< Dynamic, Dynamic, StorageIndex >
Eigen::PardisoImpl::Traits
internal::pardiso_traits< Derived > Traits
Definition: PardisoSupport.h:106
Eigen::PardisoImpl::cols
Index cols() const
Definition: PardisoSupport.h:138
Eigen::PardisoLDLT::compute
Derived & compute(const MatrixType &matrix)
Definition: PardisoSupport.h:259
Eigen::PardisoImpl::Scalar
Traits::Scalar Scalar
Definition: PardisoSupport.h:111
Eigen::PardisoImpl::rows
Index rows() const
Definition: PardisoSupport.h:139
Eigen::PardisoImpl::ScalarIsComplex
@ ScalarIsComplex
Definition: PardisoSupport.h:120
Eigen::PlainObjectBase::data
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar * data() const
Definition: PlainObjectBase.h:255
Eigen::PardisoImpl::m_perm
IntColVectorType m_perm
Definition: PardisoSupport.h:253
Eigen::internal::pardiso_traits< PardisoLU< _MatrixType > >::StorageIndex
_MatrixType::StorageIndex StorageIndex
Definition: PardisoSupport.h:75
Eigen::Matrix< Scalar, Dynamic, 1 >
Eigen::InvalidInput
@ InvalidInput
Definition: Constants.h:439
Eigen::PardisoImpl::pardisoParameterArray
ParameterType & pardisoParameterArray()
Definition: PardisoSupport.h:155
Eigen::PardisoLLT::UpLo
@ UpLo
Definition: PardisoSupport.h:452
internal
Definition: BandTriangularSolver.h:13
Eigen::PlainObjectBase::setZero
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
Definition: CwiseNullaryOp.h:515
Eigen::MatrixBase
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
Eigen::PardisoImpl::SparseMatrixType
SparseMatrix< Scalar, RowMajor, StorageIndex > SparseMatrixType
Definition: PardisoSupport.h:114
Eigen::internal::pardiso_traits< PardisoLU< _MatrixType > >::RealScalar
_MatrixType::RealScalar RealScalar
Definition: PardisoSupport.h:74
Eigen::PardisoLDLT::RealScalar
Base::RealScalar RealScalar
Definition: PardisoSupport.h:507
Eigen::PardisoLDLT::UpLo
@ UpLo
Definition: PardisoSupport.h:516
Eigen::PardisoImpl::factorize
Derived & factorize(const MatrixType &matrix)
Definition: PardisoSupport.h:302
Eigen::internal::pardiso_run_selector< long long int >::IndexType
long long int IndexType
Definition: PardisoSupport.h:57
Eigen::ComputationInfo
ComputationInfo
Definition: Constants.h:430
Eigen::PardisoLLT::PardisoLLT
PardisoLLT()
Definition: PardisoSupport.h:455
Eigen::internal::pardiso_traits< PardisoLLT< _MatrixType, Options > >::Scalar
_MatrixType::Scalar Scalar
Definition: PardisoSupport.h:82
Eigen::NumTraits
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
Definition: NumTraits.h:150
Eigen::PardisoLU::pardisoInit
void pardisoInit(int type)
Definition: PardisoSupport.h:192
Eigen::PardisoImpl::~PardisoImpl
~PardisoImpl()
Definition: PardisoSupport.h:133
Eigen::PardisoLLT
A sparse direct Cholesky (LLT) factorization and solver based on the PARDISO library.
Definition: PardisoSupport.h:38
Eigen::PardisoImpl::m_matrix
SparseMatrixType m_matrix
Definition: PardisoSupport.h:247
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:33
Eigen::internal::pardiso_run_selector< long long int >::run
static IndexType run(_MKL_DSS_HANDLE_t pt, IndexType maxfct, IndexType mnum, IndexType type, IndexType phase, IndexType n, void *a, IndexType *ia, IndexType *ja, IndexType *perm, IndexType nrhs, IndexType *iparm, IndexType msglvl, void *b, void *x)
Definition: PardisoSupport.h:58
Eigen::SparseSolverBase::m_isInitialized
bool m_isInitialized
Definition: SparseSolverBase.h:119


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:02