SimplicialCholesky.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-2012 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_SIMPLICIAL_CHOLESKY_H
11 #define EIGEN_SIMPLICIAL_CHOLESKY_H
12 
13 namespace Eigen {
14 
18 };
19 
20 namespace internal {
21  template<typename CholMatrixType, typename InputMatrixType>
23  typedef CholMatrixType const * ConstCholMatrixPtr;
24  static void run(const InputMatrixType& input, ConstCholMatrixPtr &pmat, CholMatrixType &tmp)
25  {
26  tmp = input;
27  pmat = &tmp;
28  }
29  };
30 
31  template<typename MatrixType>
33  typedef MatrixType const * ConstMatrixPtr;
34  static void run(const MatrixType& input, ConstMatrixPtr &pmat, MatrixType &/*tmp*/)
35  {
36  pmat = &input;
37  }
38  };
39 } // end namespace internal
40 
54 template<typename Derived>
56 {
58  using Base::m_isInitialized;
59 
60  public:
64  typedef typename MatrixType::Scalar Scalar;
66  typedef typename MatrixType::StorageIndex StorageIndex;
68  typedef CholMatrixType const * ConstCholMatrixPtr;
71 
72  enum {
73  ColsAtCompileTime = MatrixType::ColsAtCompileTime,
74  MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
75  };
76 
77  public:
78 
79  using Base::derived;
80 
83  : m_info(Success), m_shiftOffset(0), m_shiftScale(1)
84  {}
85 
86  explicit SimplicialCholeskyBase(const MatrixType& matrix)
87  : m_info(Success), m_shiftOffset(0), m_shiftScale(1)
88  {
89  derived().compute(matrix);
90  }
91 
93  {
94  }
95 
96  Derived& derived() { return *static_cast<Derived*>(this); }
97  const Derived& derived() const { return *static_cast<const Derived*>(this); }
98 
99  inline Index cols() const { return m_matrix.cols(); }
100  inline Index rows() const { return m_matrix.rows(); }
101 
108  {
109  eigen_assert(m_isInitialized && "Decomposition is not initialized.");
110  return m_info;
111  }
112 
116  { return m_P; }
117 
121  { return m_Pinv; }
122 
132  Derived& setShift(const RealScalar& offset, const RealScalar& scale = 1)
133  {
134  m_shiftOffset = offset;
135  m_shiftScale = scale;
136  return derived();
137  }
138 
139 #ifndef EIGEN_PARSED_BY_DOXYGEN
140 
141  template<typename Stream>
142  void dumpMemory(Stream& s)
143  {
144  int total = 0;
145  s << " L: " << ((total+=(m_matrix.cols()+1) * sizeof(int) + m_matrix.nonZeros()*(sizeof(int)+sizeof(Scalar))) >> 20) << "Mb" << "\n";
146  s << " diag: " << ((total+=m_diag.size() * sizeof(Scalar)) >> 20) << "Mb" << "\n";
147  s << " tree: " << ((total+=m_parent.size() * sizeof(int)) >> 20) << "Mb" << "\n";
148  s << " nonzeros: " << ((total+=m_nonZerosPerCol.size() * sizeof(int)) >> 20) << "Mb" << "\n";
149  s << " perm: " << ((total+=m_P.size() * sizeof(int)) >> 20) << "Mb" << "\n";
150  s << " perm^-1: " << ((total+=m_Pinv.size() * sizeof(int)) >> 20) << "Mb" << "\n";
151  s << " TOTAL: " << (total>> 20) << "Mb" << "\n";
152  }
153 
155  template<typename Rhs,typename Dest>
156  void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const
157  {
158  eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
159  eigen_assert(m_matrix.rows()==b.rows());
160 
161  if(m_info!=Success)
162  return;
163 
164  if(m_P.size()>0)
165  dest = m_P * b;
166  else
167  dest = b;
168 
169  if(m_matrix.nonZeros()>0) // otherwise L==I
170  derived().matrixL().solveInPlace(dest);
171 
172  if(m_diag.size()>0)
173  dest = m_diag.asDiagonal().inverse() * dest;
174 
175  if (m_matrix.nonZeros()>0) // otherwise U==I
176  derived().matrixU().solveInPlace(dest);
177 
178  if(m_P.size()>0)
179  dest = m_Pinv * dest;
180  }
181 
182  template<typename Rhs,typename Dest>
184  {
186  }
187 
188 #endif // EIGEN_PARSED_BY_DOXYGEN
189 
190  protected:
191 
193  template<bool DoLDLT>
194  void compute(const MatrixType& matrix)
195  {
196  eigen_assert(matrix.rows()==matrix.cols());
197  Index size = matrix.cols();
198  CholMatrixType tmp(size,size);
199  ConstCholMatrixPtr pmat;
200  ordering(matrix, pmat, tmp);
201  analyzePattern_preordered(*pmat, DoLDLT);
202  factorize_preordered<DoLDLT>(*pmat);
203  }
204 
205  template<bool DoLDLT>
206  void factorize(const MatrixType& a)
207  {
208  eigen_assert(a.rows()==a.cols());
209  Index size = a.cols();
210  CholMatrixType tmp(size,size);
211  ConstCholMatrixPtr pmat;
212 
213  if(m_P.size()==0 && (UpLo&Upper)==Upper)
214  {
215  // If there is no ordering, try to directly use the input matrix without any copy
217  }
218  else
219  {
220  tmp.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().twistedBy(m_P);
221  pmat = &tmp;
222  }
223 
224  factorize_preordered<DoLDLT>(*pmat);
225  }
226 
227  template<bool DoLDLT>
228  void factorize_preordered(const CholMatrixType& a);
229 
230  void analyzePattern(const MatrixType& a, bool doLDLT)
231  {
232  eigen_assert(a.rows()==a.cols());
233  Index size = a.cols();
234  CholMatrixType tmp(size,size);
235  ConstCholMatrixPtr pmat;
236  ordering(a, pmat, tmp);
237  analyzePattern_preordered(*pmat,doLDLT);
238  }
239  void analyzePattern_preordered(const CholMatrixType& a, bool doLDLT);
240 
241  void ordering(const MatrixType& a, ConstCholMatrixPtr &pmat, CholMatrixType& ap);
242 
244  struct keep_diag {
245  inline bool operator() (const Index& row, const Index& col, const Scalar&) const
246  {
247  return row!=col;
248  }
249  };
250 
254 
255  CholMatrixType m_matrix;
256  VectorType m_diag; // the diagonal coefficients (LDLT mode)
257  VectorI m_parent; // elimination tree
261 
262  RealScalar m_shiftOffset;
263  RealScalar m_shiftScale;
264 };
265 
266 template<typename _MatrixType, int _UpLo = Lower, typename _Ordering = AMDOrdering<typename _MatrixType::StorageIndex> > class SimplicialLLT;
267 template<typename _MatrixType, int _UpLo = Lower, typename _Ordering = AMDOrdering<typename _MatrixType::StorageIndex> > class SimplicialLDLT;
268 template<typename _MatrixType, int _UpLo = Lower, typename _Ordering = AMDOrdering<typename _MatrixType::StorageIndex> > class SimplicialCholesky;
269 
270 namespace internal {
271 
272 template<typename _MatrixType, int _UpLo, typename _Ordering> struct traits<SimplicialLLT<_MatrixType,_UpLo,_Ordering> >
273 {
274  typedef _MatrixType MatrixType;
275  typedef _Ordering OrderingType;
276  enum { UpLo = _UpLo };
277  typedef typename MatrixType::Scalar Scalar;
278  typedef typename MatrixType::StorageIndex StorageIndex;
282  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); }
283  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); }
284 };
285 
286 template<typename _MatrixType,int _UpLo, typename _Ordering> struct traits<SimplicialLDLT<_MatrixType,_UpLo,_Ordering> >
287 {
288  typedef _MatrixType MatrixType;
289  typedef _Ordering OrderingType;
290  enum { UpLo = _UpLo };
291  typedef typename MatrixType::Scalar Scalar;
292  typedef typename MatrixType::StorageIndex StorageIndex;
296  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); }
297  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); }
298 };
299 
300 template<typename _MatrixType, int _UpLo, typename _Ordering> struct traits<SimplicialCholesky<_MatrixType,_UpLo,_Ordering> >
301 {
302  typedef _MatrixType MatrixType;
303  typedef _Ordering OrderingType;
304  enum { UpLo = _UpLo };
305 };
306 
307 }
308 
329 template<typename _MatrixType, int _UpLo, typename _Ordering>
330  class SimplicialLLT : public SimplicialCholeskyBase<SimplicialLLT<_MatrixType,_UpLo,_Ordering> >
331 {
332 public:
333  typedef _MatrixType MatrixType;
334  enum { UpLo = _UpLo };
336  typedef typename MatrixType::Scalar Scalar;
338  typedef typename MatrixType::StorageIndex StorageIndex;
342  typedef typename Traits::MatrixL MatrixL;
343  typedef typename Traits::MatrixU MatrixU;
344 public:
346  SimplicialLLT() : Base() {}
348  explicit SimplicialLLT(const MatrixType& matrix)
349  : Base(matrix) {}
350 
352  inline const MatrixL matrixL() const {
353  eigen_assert(Base::m_factorizationIsOk && "Simplicial LLT not factorized");
354  return Traits::getL(Base::m_matrix);
355  }
356 
358  inline const MatrixU matrixU() const {
359  eigen_assert(Base::m_factorizationIsOk && "Simplicial LLT not factorized");
360  return Traits::getU(Base::m_matrix);
361  }
362 
364  SimplicialLLT& compute(const MatrixType& matrix)
365  {
366  Base::template compute<false>(matrix);
367  return *this;
368  }
369 
376  void analyzePattern(const MatrixType& a)
377  {
378  Base::analyzePattern(a, false);
379  }
380 
387  void factorize(const MatrixType& a)
388  {
389  Base::template factorize<false>(a);
390  }
391 
393  Scalar determinant() const
394  {
395  Scalar detL = Base::m_matrix.diagonal().prod();
396  return numext::abs2(detL);
397  }
398 };
399 
420 template<typename _MatrixType, int _UpLo, typename _Ordering>
421  class SimplicialLDLT : public SimplicialCholeskyBase<SimplicialLDLT<_MatrixType,_UpLo,_Ordering> >
422 {
423 public:
424  typedef _MatrixType MatrixType;
425  enum { UpLo = _UpLo };
427  typedef typename MatrixType::Scalar Scalar;
429  typedef typename MatrixType::StorageIndex StorageIndex;
433  typedef typename Traits::MatrixL MatrixL;
434  typedef typename Traits::MatrixU MatrixU;
435 public:
437  SimplicialLDLT() : Base() {}
438 
440  explicit SimplicialLDLT(const MatrixType& matrix)
441  : Base(matrix) {}
442 
444  inline const VectorType vectorD() const {
445  eigen_assert(Base::m_factorizationIsOk && "Simplicial LDLT not factorized");
446  return Base::m_diag;
447  }
449  inline const MatrixL matrixL() const {
450  eigen_assert(Base::m_factorizationIsOk && "Simplicial LDLT not factorized");
451  return Traits::getL(Base::m_matrix);
452  }
453 
455  inline const MatrixU matrixU() const {
456  eigen_assert(Base::m_factorizationIsOk && "Simplicial LDLT not factorized");
457  return Traits::getU(Base::m_matrix);
458  }
459 
461  SimplicialLDLT& compute(const MatrixType& matrix)
462  {
463  Base::template compute<true>(matrix);
464  return *this;
465  }
466 
473  void analyzePattern(const MatrixType& a)
474  {
475  Base::analyzePattern(a, true);
476  }
477 
484  void factorize(const MatrixType& a)
485  {
486  Base::template factorize<true>(a);
487  }
488 
490  Scalar determinant() const
491  {
492  return Base::m_diag.prod();
493  }
494 };
495 
502 template<typename _MatrixType, int _UpLo, typename _Ordering>
503  class SimplicialCholesky : public SimplicialCholeskyBase<SimplicialCholesky<_MatrixType,_UpLo,_Ordering> >
504 {
505 public:
506  typedef _MatrixType MatrixType;
507  enum { UpLo = _UpLo };
509  typedef typename MatrixType::Scalar Scalar;
511  typedef typename MatrixType::StorageIndex StorageIndex;
517  public:
518  SimplicialCholesky() : Base(), m_LDLT(true) {}
519 
520  explicit SimplicialCholesky(const MatrixType& matrix)
521  : Base(), m_LDLT(true)
522  {
523  compute(matrix);
524  }
525 
527  {
528  switch(mode)
529  {
531  m_LDLT = false;
532  break;
534  m_LDLT = true;
535  break;
536  default:
537  break;
538  }
539 
540  return *this;
541  }
542 
543  inline const VectorType vectorD() const {
544  eigen_assert(Base::m_factorizationIsOk && "Simplicial Cholesky not factorized");
545  return Base::m_diag;
546  }
547  inline const CholMatrixType rawMatrix() const {
548  eigen_assert(Base::m_factorizationIsOk && "Simplicial Cholesky not factorized");
549  return Base::m_matrix;
550  }
551 
553  SimplicialCholesky& compute(const MatrixType& matrix)
554  {
555  if(m_LDLT)
556  Base::template compute<true>(matrix);
557  else
558  Base::template compute<false>(matrix);
559  return *this;
560  }
561 
568  void analyzePattern(const MatrixType& a)
569  {
570  Base::analyzePattern(a, m_LDLT);
571  }
572 
579  void factorize(const MatrixType& a)
580  {
581  if(m_LDLT)
582  Base::template factorize<true>(a);
583  else
584  Base::template factorize<false>(a);
585  }
586 
588  template<typename Rhs,typename Dest>
589  void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const
590  {
591  eigen_assert(Base::m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
592  eigen_assert(Base::m_matrix.rows()==b.rows());
593 
594  if(Base::m_info!=Success)
595  return;
596 
597  if(Base::m_P.size()>0)
598  dest = Base::m_P * b;
599  else
600  dest = b;
601 
602  if(Base::m_matrix.nonZeros()>0) // otherwise L==I
603  {
604  if(m_LDLT)
605  LDLTTraits::getL(Base::m_matrix).solveInPlace(dest);
606  else
607  LLTTraits::getL(Base::m_matrix).solveInPlace(dest);
608  }
609 
610  if(Base::m_diag.size()>0)
611  dest = Base::m_diag.asDiagonal().inverse() * dest;
612 
613  if (Base::m_matrix.nonZeros()>0) // otherwise I==I
614  {
615  if(m_LDLT)
616  LDLTTraits::getU(Base::m_matrix).solveInPlace(dest);
617  else
618  LLTTraits::getU(Base::m_matrix).solveInPlace(dest);
619  }
620 
621  if(Base::m_P.size()>0)
622  dest = Base::m_Pinv * dest;
623  }
624 
626  template<typename Rhs,typename Dest>
628  {
630  }
631 
632  Scalar determinant() const
633  {
634  if(m_LDLT)
635  {
636  return Base::m_diag.prod();
637  }
638  else
639  {
640  Scalar detL = Diagonal<const CholMatrixType>(Base::m_matrix).prod();
641  return numext::abs2(detL);
642  }
643  }
644 
645  protected:
646  bool m_LDLT;
647 };
648 
649 template<typename Derived>
651 {
652  eigen_assert(a.rows()==a.cols());
653  const Index size = a.rows();
654  pmat = &ap;
655  // Note that ordering methods compute the inverse permutation
657  {
658  {
660  C = a.template selfadjointView<UpLo>();
661 
663  ordering(C,m_Pinv);
664  }
665 
666  if(m_Pinv.size()>0) m_P = m_Pinv.inverse();
667  else m_P.resize(0);
668 
669  ap.resize(size,size);
670  ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().twistedBy(m_P);
671  }
672  else
673  {
674  m_Pinv.resize(0);
675  m_P.resize(0);
676  if(int(UpLo)==int(Lower) || MatrixType::IsRowMajor)
677  {
678  // we have to transpose the lower part to to the upper one
679  ap.resize(size,size);
680  ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>();
681  }
682  else
684  }
685 }
686 
687 } // end namespace Eigen
688 
689 #endif // EIGEN_SIMPLICIAL_CHOLESKY_H
MatrixType::StorageIndex StorageIndex
Matrix3f m
internal::traits< SimplicialLDLT > Traits
const MatrixL matrixL() const
MatrixType::Scalar Scalar
SCALAR Scalar
Definition: bench_gemm.cpp:33
internal::traits< SimplicialCholesky > Traits
static void run(const InputMatrixType &input, ConstCholMatrixPtr &pmat, CholMatrixType &tmp)
void _solve_impl(const SparseMatrixBase< Rhs > &b, SparseMatrixBase< Dest > &dest) const
internal::traits< SimplicialLDLT< MatrixType, UpLo > > LDLTTraits
PermutationMatrix< Dynamic, Dynamic, StorageIndex > m_P
PermutationMatrix< Dynamic, Dynamic, StorageIndex > m_Pinv
Scalar * b
Definition: benchVecAdd.cpp:17
return int(ret)+1
Derived & setShift(const RealScalar &offset, const RealScalar &scale=1)
SimplicialCholeskyBase< SimplicialCholesky > Base
SimplicialLLT & compute(const MatrixType &matrix)
static enum @843 ordering
MatrixType::RealScalar RealScalar
SparseMatrix< Scalar, ColMajor, Index > CholMatrixType
void resize(Index rows, Index cols)
Definition: SparseMatrix.h:621
A base class for sparse solvers.
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
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
void _solve_impl(const MatrixBase< Rhs > &b, MatrixBase< Dest > &dest) const
SimplicialCholeskyBase< SimplicialLLT > Base
MatrixXf MatrixType
SimplicialCholeskyBase(const MatrixType &matrix)
TriangularView< const typename CholMatrixType::AdjointReturnType, Eigen::UnitUpper > MatrixU
A direct sparse LDLT Cholesky factorizations without square root.
SimplicialLDLT & compute(const MatrixType &matrix)
void factorize(const MatrixType &a)
Matrix< StorageIndex, Dynamic, 1 > VectorI
enable_if< Rhs::ColsAtCompileTime!=1 &&Dest::ColsAtCompileTime!=1 >::type solve_sparse_through_dense_panels(const Decomposition &dec, const Rhs &rhs, Dest &dest)
Array33i a
MatrixType::RealScalar RealScalar
void _solve_impl(const SparseMatrixBase< Rhs > &b, SparseMatrixBase< Dest > &dest) const
MatrixType::Scalar Scalar
void analyzePattern(const MatrixType &a)
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
const Derived & derived() const
void compute(const MatrixType &matrix)
Base class of any sparse matrices or sparse expressions.
Scalar determinant() const
const PermutationMatrix< Dynamic, Dynamic, StorageIndex > & permutationP() const
void factorize(const MatrixType &a)
m row(1)
SparseMatrix< Scalar, ColMajor, StorageIndex > CholMatrixType
static void run(const MatrixType &input, ConstMatrixPtr &pmat, MatrixType &)
A base class for direct sparse Cholesky factorizations.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:33
TriangularView< const CholMatrixType, Eigen::UnitLower > MatrixL
#define eigen_assert(x)
Definition: Macros.h:579
MatrixType::StorageIndex StorageIndex
internal::traits< Derived >::OrderingType OrderingType
SimplicialLLT(const MatrixType &matrix)
const MatrixL matrixL() const
RealScalar s
SimplicialCholeskyBase< SimplicialLDLT > Base
void analyzePattern(const MatrixType &a, bool doLDLT)
const CholMatrixType rawMatrix() const
TriangularView< const typename CholMatrixType::AdjointReturnType, Eigen::Upper > MatrixU
const MatrixU matrixU() const
Matrix< Scalar, Dynamic, 1 > VectorType
void factorize(const MatrixType &a)
CholMatrixType const * ConstCholMatrixPtr
ComputationInfo info() const
Reports whether previous computation was successful.
NumTraits< Scalar >::Real RealScalar
Definition: bench_gemm.cpp:34
const MatrixU matrixU() const
MatrixType::RealScalar RealScalar
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Abs2ReturnType abs2() const
SparseSymmetricPermutationProduct< Derived, Upper|Lower > twistedBy(const PermutationMatrix< Dynamic, Dynamic, StorageIndex > &perm) const
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
const PermutationMatrix< Dynamic, Dynamic, StorageIndex > & permutationPinv() const
MatrixType::StorageIndex StorageIndex
TriangularView< const CholMatrixType, Eigen::Lower > MatrixL
internal::traits< SimplicialLLT< MatrixType, UpLo > > LLTTraits
SparseMatrix< Scalar, ColMajor, StorageIndex > CholMatrixType
SimplicialLDLT(const MatrixType &matrix)
Scalar determinant() const
void factorize(const MatrixType &a)
internal::traits< Derived >::MatrixType MatrixType
Expression of a triangular part in a matrix.
m col(1)
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 scale
SimplicialCholesky(const MatrixType &matrix)
MatrixType::StorageIndex StorageIndex
void analyzePattern(const MatrixType &a)
Expression of a diagonal/subdiagonal/superdiagonal in a matrix.
Definition: Diagonal.h:63
Matrix< Scalar, Dynamic, 1 > VectorType
A direct sparse LLT Cholesky factorizations.
EIGEN_DONT_INLINE void compute(Solver &solver, const MatrixType &A)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
EIGEN_DEVICE_FUNC const DiagonalWrapper< const Derived > asDiagonal() const
SimplicialCholesky & setMode(SimplicialCholeskyMode mode)
internal::traits< SimplicialLLT > Traits
MatrixType::RealScalar RealScalar
Matrix< Scalar, Dynamic, 1 > VectorType
ComputationInfo
Definition: Constants.h:430
SparseMatrix< Scalar, ColMajor, StorageIndex > CholMatrixType
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
const VectorType vectorD() const
Matrix< Scalar, Dynamic, 1 > VectorType
SparseSolverBase< Derived > Base
void ordering(const MatrixType &a, ConstCholMatrixPtr &pmat, CholMatrixType &ap)
SimplicialCholesky & compute(const MatrixType &matrix)
const Product< Lhs, Rhs > prod(const Lhs &lhs, const Rhs &rhs)
Definition: evaluators.cpp:8
void analyzePattern(const MatrixType &a)
void _solve_impl(const MatrixBase< Rhs > &b, MatrixBase< Dest > &dest) const
const VectorType vectorD() const


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:07