CholmodSupport.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) 2008-2010 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_CHOLMODSUPPORT_H
11 #define EIGEN_CHOLMODSUPPORT_H
12 
13 namespace Eigen {
14 
15 namespace internal {
16 
17 template<typename Scalar> struct cholmod_configure_matrix;
18 
19 template<> struct cholmod_configure_matrix<double> {
20  template<typename CholmodType>
21  static void run(CholmodType& mat) {
22  mat.xtype = CHOLMOD_REAL;
23  mat.dtype = CHOLMOD_DOUBLE;
24  }
25 };
26 
27 template<> struct cholmod_configure_matrix<std::complex<double> > {
28  template<typename CholmodType>
29  static void run(CholmodType& mat) {
30  mat.xtype = CHOLMOD_COMPLEX;
31  mat.dtype = CHOLMOD_DOUBLE;
32  }
33 };
34 
35 // Other scalar types are not yet supported by Cholmod
36 // template<> struct cholmod_configure_matrix<float> {
37 // template<typename CholmodType>
38 // static void run(CholmodType& mat) {
39 // mat.xtype = CHOLMOD_REAL;
40 // mat.dtype = CHOLMOD_SINGLE;
41 // }
42 // };
43 //
44 // template<> struct cholmod_configure_matrix<std::complex<float> > {
45 // template<typename CholmodType>
46 // static void run(CholmodType& mat) {
47 // mat.xtype = CHOLMOD_COMPLEX;
48 // mat.dtype = CHOLMOD_SINGLE;
49 // }
50 // };
51 
52 } // namespace internal
53 
57 template<typename _Scalar, int _Options, typename _StorageIndex>
59 {
60  cholmod_sparse res;
61  res.nzmax = mat.nonZeros();
62  res.nrow = mat.rows();
63  res.ncol = mat.cols();
64  res.p = mat.outerIndexPtr();
65  res.i = mat.innerIndexPtr();
66  res.x = mat.valuePtr();
67  res.z = 0;
68  res.sorted = 1;
69  if(mat.isCompressed())
70  {
71  res.packed = 1;
72  res.nz = 0;
73  }
74  else
75  {
76  res.packed = 0;
77  res.nz = mat.innerNonZeroPtr();
78  }
79 
80  res.dtype = 0;
81  res.stype = -1;
82 
84  {
85  res.itype = CHOLMOD_INT;
86  }
88  {
89  res.itype = CHOLMOD_LONG;
90  }
91  else
92  {
93  eigen_assert(false && "Index type not supported yet");
94  }
95 
96  // setup res.xtype
98 
99  res.stype = 0;
100 
101  return res;
102 }
103 
104 template<typename _Scalar, int _Options, typename _Index>
106 {
107  cholmod_sparse res = viewAsCholmod(Ref<SparseMatrix<_Scalar,_Options,_Index> >(mat.const_cast_derived()));
108  return res;
109 }
110 
111 template<typename _Scalar, int _Options, typename _Index>
113 {
114  cholmod_sparse res = viewAsCholmod(Ref<SparseMatrix<_Scalar,_Options,_Index> >(mat.const_cast_derived()));
115  return res;
116 }
117 
120 template<typename _Scalar, int _Options, typename _Index, unsigned int UpLo>
122 {
123  cholmod_sparse res = viewAsCholmod(Ref<SparseMatrix<_Scalar,_Options,_Index> >(mat.matrix().const_cast_derived()));
124 
125  if(UpLo==Upper) res.stype = 1;
126  if(UpLo==Lower) res.stype = -1;
127  // swap stype for rowmajor matrices (only works for real matrices)
128  EIGEN_STATIC_ASSERT((_Options & RowMajorBit) == 0 || NumTraits<_Scalar>::IsComplex == 0, THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);
129  if(_Options & RowMajorBit) res.stype *=-1;
130 
131  return res;
132 }
133 
136 template<typename Derived>
138 {
139  EIGEN_STATIC_ASSERT((internal::traits<Derived>::Flags&RowMajorBit)==0,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);
140  typedef typename Derived::Scalar Scalar;
141 
142  cholmod_dense res;
143  res.nrow = mat.rows();
144  res.ncol = mat.cols();
145  res.nzmax = res.nrow * res.ncol;
146  res.d = Derived::IsVectorAtCompileTime ? mat.derived().size() : mat.derived().outerStride();
147  res.x = (void*)(mat.derived().data());
148  res.z = 0;
149 
151 
152  return res;
153 }
154 
157 template<typename Scalar, int Flags, typename StorageIndex>
159 {
161  (cm.nrow, cm.ncol, static_cast<StorageIndex*>(cm.p)[cm.ncol],
162  static_cast<StorageIndex*>(cm.p), static_cast<StorageIndex*>(cm.i),static_cast<Scalar*>(cm.x) );
163 }
164 
165 namespace internal {
166 
167 // template specializations for int and long that call the correct cholmod method
168 
169 #define EIGEN_CHOLMOD_SPECIALIZE0(ret, name) \
170  template<typename _StorageIndex> inline ret cm_ ## name (cholmod_common &Common) { return cholmod_ ## name (&Common); } \
171  template<> inline ret cm_ ## name<SuiteSparse_long> (cholmod_common &Common) { return cholmod_l_ ## name (&Common); }
172 
173 #define EIGEN_CHOLMOD_SPECIALIZE1(ret, name, t1, a1) \
174  template<typename _StorageIndex> inline ret cm_ ## name (t1& a1, cholmod_common &Common) { return cholmod_ ## name (&a1, &Common); } \
175  template<> inline ret cm_ ## name<SuiteSparse_long> (t1& a1, cholmod_common &Common) { return cholmod_l_ ## name (&a1, &Common); }
176 
177 EIGEN_CHOLMOD_SPECIALIZE0(int, start)
178 EIGEN_CHOLMOD_SPECIALIZE0(int, finish)
179 
180 EIGEN_CHOLMOD_SPECIALIZE1(int, free_factor, cholmod_factor*, L)
181 EIGEN_CHOLMOD_SPECIALIZE1(int, free_dense, cholmod_dense*, X)
182 EIGEN_CHOLMOD_SPECIALIZE1(int, free_sparse, cholmod_sparse*, A)
183 
184 EIGEN_CHOLMOD_SPECIALIZE1(cholmod_factor*, analyze, cholmod_sparse, A)
185 
186 template<typename _StorageIndex> inline cholmod_dense* cm_solve (int sys, cholmod_factor& L, cholmod_dense& B, cholmod_common &Common) { return cholmod_solve (sys, &L, &B, &Common); }
187 template<> inline cholmod_dense* cm_solve<SuiteSparse_long> (int sys, cholmod_factor& L, cholmod_dense& B, cholmod_common &Common) { return cholmod_l_solve (sys, &L, &B, &Common); }
188 
189 template<typename _StorageIndex> inline cholmod_sparse* cm_spsolve (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_spsolve (sys, &L, &B, &Common); }
190 template<> inline cholmod_sparse* cm_spsolve<SuiteSparse_long> (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_l_spsolve (sys, &L, &B, &Common); }
191 
192 template<typename _StorageIndex>
193 inline int cm_factorize_p (cholmod_sparse* A, double beta[2], _StorageIndex* fset, std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_factorize_p (A, beta, fset, fsize, L, &Common); }
194 template<>
195 inline int cm_factorize_p<SuiteSparse_long> (cholmod_sparse* A, double beta[2], SuiteSparse_long* fset, std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_l_factorize_p (A, beta, fset, fsize, L, &Common); }
196 
197 #undef EIGEN_CHOLMOD_SPECIALIZE0
198 #undef EIGEN_CHOLMOD_SPECIALIZE1
199 
200 } // namespace internal
201 
202 
205 };
206 
207 
213 template<typename _MatrixType, int _UpLo, typename Derived>
214 class CholmodBase : public SparseSolverBase<Derived>
215 {
216  protected:
218  using Base::derived;
219  using Base::m_isInitialized;
220  public:
221  typedef _MatrixType MatrixType;
222  enum { UpLo = _UpLo };
223  typedef typename MatrixType::Scalar Scalar;
226  typedef typename MatrixType::StorageIndex StorageIndex;
227  enum {
228  ColsAtCompileTime = MatrixType::ColsAtCompileTime,
229  MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
230  };
231 
232  public:
233 
236  {
237  EIGEN_STATIC_ASSERT((internal::is_same<double,RealScalar>::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY);
238  m_shiftOffset[0] = m_shiftOffset[1] = 0.0;
239  internal::cm_start<StorageIndex>(m_cholmod);
240  }
241 
242  explicit CholmodBase(const MatrixType& matrix)
244  {
245  EIGEN_STATIC_ASSERT((internal::is_same<double,RealScalar>::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY);
246  m_shiftOffset[0] = m_shiftOffset[1] = 0.0;
247  internal::cm_start<StorageIndex>(m_cholmod);
248  compute(matrix);
249  }
250 
252  {
253  if(m_cholmodFactor)
254  internal::cm_free_factor<StorageIndex>(m_cholmodFactor, m_cholmod);
255  internal::cm_finish<StorageIndex>(m_cholmod);
256  }
257 
258  inline StorageIndex cols() const { return internal::convert_index<StorageIndex, Index>(m_cholmodFactor->n); }
259  inline StorageIndex rows() const { return internal::convert_index<StorageIndex, Index>(m_cholmodFactor->n); }
260 
267  {
268  eigen_assert(m_isInitialized && "Decomposition is not initialized.");
269  return m_info;
270  }
271 
273  Derived& compute(const MatrixType& matrix)
274  {
276  factorize(matrix);
277  return derived();
278  }
279 
287  {
288  if(m_cholmodFactor)
289  {
290  internal::cm_free_factor<StorageIndex>(m_cholmodFactor, m_cholmod);
291  m_cholmodFactor = 0;
292  }
293  cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView<UpLo>());
294  m_cholmodFactor = internal::cm_analyze<StorageIndex>(A, m_cholmod);
295 
296  this->m_isInitialized = true;
297  this->m_info = Success;
298  m_analysisIsOk = true;
299  m_factorizationIsOk = false;
300  }
301 
308  void factorize(const MatrixType& matrix)
309  {
310  eigen_assert(m_analysisIsOk && "You must first call analyzePattern()");
311  cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView<UpLo>());
312  internal::cm_factorize_p<StorageIndex>(&A, m_shiftOffset, 0, 0, m_cholmodFactor, m_cholmod);
313 
314  // If the factorization failed, minor is the column at which it did. On success minor == n.
315  this->m_info = (m_cholmodFactor->minor == m_cholmodFactor->n ? Success : NumericalIssue);
316  m_factorizationIsOk = true;
317  }
318 
321  cholmod_common& cholmod() { return m_cholmod; }
322 
323  #ifndef EIGEN_PARSED_BY_DOXYGEN
324 
325  template<typename Rhs,typename Dest>
326  void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const
327  {
328  eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
329  const Index size = m_cholmodFactor->n;
331  eigen_assert(size==b.rows());
332 
333  // Cholmod needs column-major storage without inner-stride, which corresponds to the default behavior of Ref.
335 
336  cholmod_dense b_cd = viewAsCholmod(b_ref);
337  cholmod_dense* x_cd = internal::cm_solve<StorageIndex>(CHOLMOD_A, *m_cholmodFactor, b_cd, m_cholmod);
338  if(!x_cd)
339  {
340  this->m_info = NumericalIssue;
341  return;
342  }
343  // TODO optimize this copy by swapping when possible (be careful with alignment, etc.)
344  // NOTE Actually, the copy can be avoided by calling cholmod_solve2 instead of cholmod_solve
345  dest = Matrix<Scalar,Dest::RowsAtCompileTime,Dest::ColsAtCompileTime>::Map(reinterpret_cast<Scalar*>(x_cd->x),b.rows(),b.cols());
346  internal::cm_free_dense<StorageIndex>(x_cd, m_cholmod);
347  }
348 
350  template<typename RhsDerived, typename DestDerived>
352  {
353  eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
354  const Index size = m_cholmodFactor->n;
356  eigen_assert(size==b.rows());
357 
358  // note: cs stands for Cholmod Sparse
360  cholmod_sparse b_cs = viewAsCholmod(b_ref);
361  cholmod_sparse* x_cs = internal::cm_spsolve<StorageIndex>(CHOLMOD_A, *m_cholmodFactor, b_cs, m_cholmod);
362  if(!x_cs)
363  {
364  this->m_info = NumericalIssue;
365  return;
366  }
367  // TODO optimize this copy by swapping when possible (be careful with alignment, etc.)
368  // NOTE cholmod_spsolve in fact just calls the dense solver for blocks of 4 columns at a time (similar to Eigen's sparse solver)
369  dest.derived() = viewAsEigen<typename DestDerived::Scalar,ColMajor,typename DestDerived::StorageIndex>(*x_cs);
370  internal::cm_free_sparse<StorageIndex>(x_cs, m_cholmod);
371  }
372  #endif // EIGEN_PARSED_BY_DOXYGEN
373 
374 
384  Derived& setShift(const RealScalar& offset)
385  {
386  m_shiftOffset[0] = double(offset);
387  return derived();
388  }
389 
392  {
393  using std::exp;
394  return exp(logDeterminant());
395  }
396 
399  {
400  using std::log;
401  using numext::real;
402  eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
403 
404  RealScalar logDet = 0;
405  Scalar *x = static_cast<Scalar*>(m_cholmodFactor->x);
406  if (m_cholmodFactor->is_super)
407  {
408  // Supernodal factorization stored as a packed list of dense column-major blocs,
409  // as described by the following structure:
410 
411  // super[k] == index of the first column of the j-th super node
412  StorageIndex *super = static_cast<StorageIndex*>(m_cholmodFactor->super);
413  // pi[k] == offset to the description of row indices
414  StorageIndex *pi = static_cast<StorageIndex*>(m_cholmodFactor->pi);
415  // px[k] == offset to the respective dense block
416  StorageIndex *px = static_cast<StorageIndex*>(m_cholmodFactor->px);
417 
418  Index nb_super_nodes = m_cholmodFactor->nsuper;
419  for (Index k=0; k < nb_super_nodes; ++k)
420  {
421  StorageIndex ncols = super[k + 1] - super[k];
422  StorageIndex nrows = pi[k + 1] - pi[k];
423 
424  Map<const Array<Scalar,1,Dynamic>, 0, InnerStride<> > sk(x + px[k], ncols, InnerStride<>(nrows+1));
425  logDet += sk.real().log().sum();
426  }
427  }
428  else
429  {
430  // Simplicial factorization stored as standard CSC matrix.
431  StorageIndex *p = static_cast<StorageIndex*>(m_cholmodFactor->p);
433  for (Index k=0; k<size; ++k)
434  logDet += log(real( x[p[k]] ));
435  }
436  if (m_cholmodFactor->is_ll)
437  logDet *= 2.0;
438  return logDet;
439  };
440 
441  template<typename Stream>
442  void dumpMemory(Stream& /*s*/)
443  {}
444 
445  protected:
446  mutable cholmod_common m_cholmod;
447  cholmod_factor* m_cholmodFactor;
448  double m_shiftOffset[2];
452 };
453 
476 template<typename _MatrixType, int _UpLo = Lower>
477 class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLLT<_MatrixType, _UpLo> >
478 {
480  using Base::m_cholmod;
481 
482  public:
483 
484  typedef _MatrixType MatrixType;
485 
487 
489  {
490  init();
491  this->compute(matrix);
492  }
493 
495  protected:
496  void init()
497  {
498  m_cholmod.final_asis = 0;
499  m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;
500  m_cholmod.final_ll = 1;
501  }
502 };
503 
504 
527 template<typename _MatrixType, int _UpLo = Lower>
528 class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLDLT<_MatrixType, _UpLo> >
529 {
531  using Base::m_cholmod;
532 
533  public:
534 
535  typedef _MatrixType MatrixType;
536 
538 
540  {
541  init();
542  this->compute(matrix);
543  }
544 
546  protected:
547  void init()
548  {
549  m_cholmod.final_asis = 1;
550  m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;
551  }
552 };
553 
576 template<typename _MatrixType, int _UpLo = Lower>
577 class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSupernodalLLT<_MatrixType, _UpLo> >
578 {
580  using Base::m_cholmod;
581 
582  public:
583 
584  typedef _MatrixType MatrixType;
585 
587 
589  {
590  init();
591  this->compute(matrix);
592  }
593 
595  protected:
596  void init()
597  {
598  m_cholmod.final_asis = 1;
599  m_cholmod.supernodal = CHOLMOD_SUPERNODAL;
600  }
601 };
602 
627 template<typename _MatrixType, int _UpLo = Lower>
628 class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecomposition<_MatrixType, _UpLo> >
629 {
631  using Base::m_cholmod;
632 
633  public:
634 
635  typedef _MatrixType MatrixType;
636 
638 
640  {
641  init();
642  this->compute(matrix);
643  }
644 
646 
648  {
649  switch(mode)
650  {
651  case CholmodAuto:
652  m_cholmod.final_asis = 1;
653  m_cholmod.supernodal = CHOLMOD_AUTO;
654  break;
656  m_cholmod.final_asis = 0;
657  m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;
658  m_cholmod.final_ll = 1;
659  break;
661  m_cholmod.final_asis = 1;
662  m_cholmod.supernodal = CHOLMOD_SUPERNODAL;
663  break;
664  case CholmodLDLt:
665  m_cholmod.final_asis = 1;
666  m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;
667  break;
668  default:
669  break;
670  }
671  }
672  protected:
673  void init()
674  {
675  m_cholmod.final_asis = 1;
676  m_cholmod.supernodal = CHOLMOD_AUTO;
677  }
678 };
679 
680 } // end namespace Eigen
681 
682 #endif // EIGEN_CHOLMODSUPPORT_H
Eigen::CholmodBase
The base class for the direct Cholesky factorization of Cholmod.
Definition: CholmodSupport.h:214
Eigen::CholmodBase::m_factorizationIsOk
int m_factorizationIsOk
Definition: CholmodSupport.h:450
Eigen::viewAsEigen
MappedSparseMatrix< Scalar, Flags, StorageIndex > viewAsEigen(cholmod_sparse &cm)
Definition: CholmodSupport.h:158
Eigen::CholmodBase::factorize
void factorize(const MatrixType &matrix)
Definition: CholmodSupport.h:308
Eigen::NumericalIssue
@ NumericalIssue
Definition: Constants.h:444
Eigen::CholmodSimplicialLLT::init
void init()
Definition: CholmodSupport.h:496
Eigen::CholmodDecomposition::Base
CholmodBase< _MatrixType, _UpLo, CholmodDecomposition > Base
Definition: CholmodSupport.h:630
Eigen::CholmodSupernodalLLT::~CholmodSupernodalLLT
~CholmodSupernodalLLT()
Definition: CholmodSupport.h:594
Eigen::internal::cholmod_configure_matrix< std::complex< double > >::run
static void run(CholmodType &mat)
Definition: CholmodSupport.h:29
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
Eigen::SparseMatrix
A versatible sparse matrix representation.
Definition: SparseMatrix.h:96
Eigen::CholmodSimplicialLLT::~CholmodSimplicialLLT
~CholmodSimplicialLLT()
Definition: CholmodSupport.h:494
Eigen::CholmodBase::MaxColsAtCompileTime
@ MaxColsAtCompileTime
Definition: CholmodSupport.h:229
Eigen::CholmodDecomposition::setMode
void setMode(CholmodMode mode)
Definition: CholmodSupport.h:647
Eigen::CholmodBase::CholmodBase
CholmodBase()
Definition: CholmodSupport.h:234
Eigen::CholmodBase::CholmodBase
CholmodBase(const MatrixType &matrix)
Definition: CholmodSupport.h:242
Eigen::CholmodDecomposition::init
void init()
Definition: CholmodSupport.h:673
Eigen::CholmodSimplicialLLT::CholmodSimplicialLLT
CholmodSimplicialLLT()
Definition: CholmodSupport.h:486
Eigen::CholmodBase::_solve_impl
void _solve_impl(const MatrixBase< Rhs > &b, MatrixBase< Dest > &dest) const
Definition: CholmodSupport.h:326
Eigen::InnerStride
Convenience specialization of Stride to specify only an inner stride See class Map for some examples.
Definition: Stride.h:95
b
Scalar * b
Definition: benchVecAdd.cpp:17
Eigen::CholmodBase::~CholmodBase
~CholmodBase()
Definition: CholmodSupport.h:251
eigen_assert
#define eigen_assert(x)
Definition: Macros.h:1037
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::CholmodSupernodalLLT::init
void init()
Definition: CholmodSupport.h:596
Eigen::RowMajorBit
const unsigned int RowMajorBit
Definition: Constants.h:66
B
Definition: test_numpy_dtypes.cpp:299
Eigen::Upper
@ Upper
Definition: Constants.h:211
Eigen::Success
@ Success
Definition: Constants.h:442
real
float real
Definition: datatypes.h:10
Eigen::CholmodSimplicialLDLT::Base
CholmodBase< _MatrixType, _UpLo, CholmodSimplicialLDLT > Base
Definition: CholmodSupport.h:530
Eigen::CholmodSimplicialLDLT::~CholmodSimplicialLDLT
~CholmodSimplicialLDLT()
Definition: CholmodSupport.h:545
log
const EIGEN_DEVICE_FUNC LogReturnType log() const
Definition: ArrayCwiseUnaryOps.h:128
X
#define X
Definition: icosphere.cpp:20
Eigen::CholmodDecomposition::CholmodDecomposition
CholmodDecomposition(const MatrixType &matrix)
Definition: CholmodSupport.h:639
mat
MatrixXf mat
Definition: Tutorial_AdvancedInitialization_CommaTemporary.cpp:1
res
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
Definition: PartialRedux_count.cpp:3
exp
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
Definition: ArrayCwiseUnaryOps.h:97
Eigen::CholmodSimplicialLDLT
A simplicial direct Cholesky (LDLT) factorization and solver based on Cholmod.
Definition: CholmodSupport.h:528
Eigen::CholmodBase::ColsAtCompileTime
@ ColsAtCompileTime
Definition: CholmodSupport.h:228
beta
double beta(double a, double b)
Definition: beta.c:61
Eigen::CholmodBase::Base
SparseSolverBase< Derived > Base
Definition: CholmodSupport.h:217
EIGEN_CHOLMOD_SPECIALIZE1
#define EIGEN_CHOLMOD_SPECIALIZE1(ret, name, t1, a1)
Definition: CholmodSupport.h:173
Eigen::CholmodBase::logDeterminant
Scalar logDeterminant() const
Definition: CholmodSupport.h:398
Eigen::CholmodBase::MatrixType
_MatrixType MatrixType
Definition: CholmodSupport.h:221
Eigen::viewAsCholmod
cholmod_sparse viewAsCholmod(Ref< SparseMatrix< _Scalar, _Options, _StorageIndex > > mat)
Definition: CholmodSupport.h:58
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
Eigen::CholmodDecomposition::MatrixType
_MatrixType MatrixType
Definition: CholmodSupport.h:635
Eigen::CholmodBase::analyzePattern
void analyzePattern(const MatrixType &matrix)
Definition: CholmodSupport.h:286
Eigen::internal::cm_spsolve
cholmod_sparse * cm_spsolve(int sys, cholmod_factor &L, cholmod_sparse &B, cholmod_common &Common)
Definition: CholmodSupport.h:189
Eigen::CholmodBase::cholmod
cholmod_common & cholmod()
Definition: CholmodSupport.h:321
Eigen::internal::cm_factorize_p
int cm_factorize_p(cholmod_sparse *A, double beta[2], _StorageIndex *fset, std::size_t fsize, cholmod_factor *L, cholmod_common &Common)
Definition: CholmodSupport.h:193
A
Definition: test_numpy_dtypes.cpp:298
Eigen::CholmodBase::m_analysisIsOk
int m_analysisIsOk
Definition: CholmodSupport.h:451
EIGEN_UNUSED_VARIABLE
#define EIGEN_UNUSED_VARIABLE(var)
Definition: Macros.h:1076
Eigen::CholmodSupernodalLLT::MatrixType
_MatrixType MatrixType
Definition: CholmodSupport.h:584
Eigen::CholmodBase::CholMatrixType
MatrixType CholMatrixType
Definition: CholmodSupport.h:225
Eigen::CholmodAuto
@ CholmodAuto
Definition: CholmodSupport.h:204
Eigen::internal::cm_solve
cholmod_dense * cm_solve(int sys, cholmod_factor &L, cholmod_dense &B, cholmod_common &Common)
Definition: CholmodSupport.h:186
Eigen::CholmodMode
CholmodMode
Definition: CholmodSupport.h:203
EIGEN_CHOLMOD_SPECIALIZE0
#define EIGEN_CHOLMOD_SPECIALIZE0(ret, name)
Definition: CholmodSupport.h:169
Eigen::internal::cholmod_configure_matrix
Definition: CholmodSupport.h:17
Eigen::CholmodSupernodalLLT::CholmodSupernodalLLT
CholmodSupernodalLLT()
Definition: CholmodSupport.h:586
Eigen::CholmodDecomposition::~CholmodDecomposition
~CholmodDecomposition()
Definition: CholmodSupport.h:645
Eigen::CholmodBase::determinant
Scalar determinant() const
Definition: CholmodSupport.h:391
Eigen::CholmodBase::info
ComputationInfo info() const
Reports whether previous computation was successful.
Definition: CholmodSupport.h:266
Eigen::CholmodSimplicialLDLT::CholmodSimplicialLDLT
CholmodSimplicialLDLT(const MatrixType &matrix)
Definition: CholmodSupport.h:539
L
MatrixXd L
Definition: LLT_example.cpp:6
Eigen::internal::cholmod_configure_matrix< double >::run
static void run(CholmodType &mat)
Definition: CholmodSupport.h:21
Eigen::CholmodBase::m_info
ComputationInfo m_info
Definition: CholmodSupport.h:449
gtsam.examples.DogLegOptimizerExample.run
def run(args)
Definition: DogLegOptimizerExample.py:21
Eigen::CholmodSimplicialLDLT::init
void init()
Definition: CholmodSupport.h:547
Eigen::CholmodSimplicialLDLT::MatrixType
_MatrixType MatrixType
Definition: CholmodSupport.h:535
Eigen::CholmodBase::dumpMemory
void dumpMemory(Stream &)
Definition: CholmodSupport.h:442
Eigen::CholmodSimplicialLDLT::CholmodSimplicialLDLT
CholmodSimplicialLDLT()
Definition: CholmodSupport.h:537
Eigen::Lower
@ Lower
Definition: Constants.h:209
Eigen::CholmodSupernodalLLT
A supernodal Cholesky (LLT) factorization and solver based on Cholmod.
Definition: CholmodSupport.h:577
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
size_t
std::size_t size_t
Definition: wrap/pybind11/include/pybind11/detail/common.h:476
Eigen::CholmodBase::StorageIndex
MatrixType::StorageIndex StorageIndex
Definition: CholmodSupport.h:226
SuiteSparse_long
#define SuiteSparse_long
Definition: SuiteSparse_config.h:62
Eigen::PlainObjectBase< Matrix< _Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >::Map
static ConstMapType Map(const Scalar *data)
Definition: PlainObjectBase.h:644
Eigen::CholmodSimplicialLLT::Base
CholmodBase< _MatrixType, _UpLo, CholmodSimplicialLLT > Base
Definition: CholmodSupport.h:479
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
offset
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate offset
Definition: gnuplot_common_settings.hh:64
Eigen::CholmodBase::m_cholmod
cholmod_common m_cholmod
Definition: CholmodSupport.h:446
Eigen::CholmodSimplicialLLT::CholmodSimplicialLLT
CholmodSimplicialLLT(const MatrixType &matrix)
Definition: CholmodSupport.h:488
Eigen::real
const AutoDiffScalar< DerType > & real(const AutoDiffScalar< DerType > &x)
Definition: AutoDiffScalar.h:576
RealScalar
NumTraits< Scalar >::Real RealScalar
Definition: bench_gemm.cpp:47
Eigen::CholmodBase::Scalar
MatrixType::Scalar Scalar
Definition: CholmodSupport.h:223
Eigen::SparseSolverBase
A base class for sparse solvers.
Definition: SparseSolverBase.h:67
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:281
Eigen::internal::cm_solve< SuiteSparse_long >
cholmod_dense * cm_solve< SuiteSparse_long >(int sys, cholmod_factor &L, cholmod_dense &B, cholmod_common &Common)
Definition: CholmodSupport.h:187
Eigen::CholmodBase::RealScalar
MatrixType::RealScalar RealScalar
Definition: CholmodSupport.h:224
Eigen::internal::traits
Definition: ForwardDeclarations.h:17
EIGEN_STATIC_ASSERT
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
Definition: StaticAssert.h:127
Eigen::SparseSolverBase::derived
Derived & derived()
Definition: SparseSolverBase.h:79
Eigen::SparseVector
a sparse vector class
Definition: SparseUtil.h:54
std
Definition: BFloat16.h:88
Eigen::CholmodBase::rows
StorageIndex rows() const
Definition: CholmodSupport.h:259
p
float * p
Definition: Tutorial_Map_using.cpp:9
Eigen::internal::cm_factorize_p< SuiteSparse_long >
int cm_factorize_p< SuiteSparse_long >(cholmod_sparse *A, double beta[2], SuiteSparse_long *fset, std::size_t fsize, cholmod_factor *L, cholmod_common &Common)
Definition: CholmodSupport.h:195
cm
static const double cm
Definition: TimeOfArrivalExample.cpp:34
Eigen::SparseMatrixBase
Base class of any sparse matrices or sparse expressions.
Definition: ForwardDeclarations.h:301
Eigen::CholmodSimplicialLLT
A simplicial direct Cholesky (LLT) factorization and solver based on Cholmod.
Definition: CholmodSupport.h:477
Eigen::SparseMatrixBase::derived
const Derived & derived() const
Definition: SparseMatrixBase.h:143
Eigen::CholmodBase::UpLo
@ UpLo
Definition: CholmodSupport.h:222
mode
static const DiscreteKey mode(modeKey, 2)
Eigen::internal::is_same
Definition: Meta.h:148
Eigen::CholmodSupernodalLLt
@ CholmodSupernodalLLt
Definition: CholmodSupport.h:204
Eigen::SparseSelfAdjointView
Pseudo expression to manipulate a triangular sparse matrix as a selfadjoint matrix.
Definition: SparseSelfAdjointView.h:43
Eigen::internal::cm_spsolve< SuiteSparse_long >
cholmod_sparse * cm_spsolve< SuiteSparse_long >(int sys, cholmod_factor &L, cholmod_sparse &B, cholmod_common &Common)
Definition: CholmodSupport.h:190
internal
Definition: BandTriangularSolver.h:13
Eigen::MatrixBase
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
Eigen::CholmodSimplicialLLt
@ CholmodSimplicialLLt
Definition: CholmodSupport.h:204
Eigen::CholmodBase::_solve_impl
void _solve_impl(const SparseMatrixBase< RhsDerived > &b, SparseMatrixBase< DestDerived > &dest) const
Definition: CholmodSupport.h:351
Eigen::ComputationInfo
ComputationInfo
Definition: Constants.h:440
Eigen::CholmodBase::compute
Derived & compute(const MatrixType &matrix)
Definition: CholmodSupport.h:273
Eigen::CholmodLDLt
@ CholmodLDLt
Definition: CholmodSupport.h:204
Eigen::CholmodSupernodalLLT::Base
CholmodBase< _MatrixType, _UpLo, CholmodSupernodalLLT > Base
Definition: CholmodSupport.h:579
Eigen::CholmodBase::cols
StorageIndex cols() const
Definition: CholmodSupport.h:258
Eigen::CholmodBase::m_cholmodFactor
cholmod_factor * m_cholmodFactor
Definition: CholmodSupport.h:447
Eigen::CholmodDecomposition
A general Cholesky factorization and solver based on Cholmod.
Definition: CholmodSupport.h:628
Eigen::NumTraits
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
Definition: NumTraits.h:232
Eigen::CholmodSimplicialLLT::MatrixType
_MatrixType MatrixType
Definition: CholmodSupport.h:484
Eigen::MappedSparseMatrix
Sparse matrix.
Definition: MappedSparseMatrix.h:32
Eigen::CholmodBase::m_shiftOffset
double m_shiftOffset[2]
Definition: CholmodSupport.h:448
complex
Definition: datatypes.h:12
Scalar
SCALAR Scalar
Definition: bench_gemm.cpp:46
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74
Eigen::CholmodDecomposition::CholmodDecomposition
CholmodDecomposition()
Definition: CholmodSupport.h:637
Eigen::CholmodSupernodalLLT::CholmodSupernodalLLT
CholmodSupernodalLLT(const MatrixType &matrix)
Definition: CholmodSupport.h:588
Eigen::SparseSolverBase::m_isInitialized
bool m_isInitialized
Definition: SparseSolverBase.h:119
px
RealScalar RealScalar * px
Definition: level1_cplx_impl.h:28
Eigen::CholmodBase::setShift
Derived & setShift(const RealScalar &offset)
Definition: CholmodSupport.h:384


gtsam
Author(s):
autogenerated on Sat Jun 1 2024 03:01:17