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


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:04:13