10 #ifndef EIGEN_SIMPLICIAL_CHOLESKY_H 11 #define EIGEN_SIMPLICIAL_CHOLESKY_H 21 template<
typename CholMatrixType,
typename InputMatrixType>
24 static void run(
const InputMatrixType& input, ConstCholMatrixPtr &pmat, CholMatrixType &tmp)
31 template<
typename MatrixType>
54 template<
typename Derived>
58 using Base::m_isInitialized;
73 ColsAtCompileTime = MatrixType::ColsAtCompileTime,
74 MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
83 : m_info(
Success), m_shiftOffset(0), m_shiftScale(1)
87 : m_info(
Success), m_shiftOffset(0), m_shiftScale(1)
89 derived().compute(matrix);
96 Derived&
derived() {
return *
static_cast<Derived*
>(
this); }
97 const Derived&
derived()
const {
return *
static_cast<const Derived*
>(
this); }
99 inline Index cols()
const {
return m_matrix.cols(); }
109 eigen_assert(m_isInitialized &&
"Decomposition is not initialized.");
135 m_shiftScale =
scale;
139 #ifndef EIGEN_PARSED_BY_DOXYGEN 141 template<
typename Stream>
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";
155 template<
typename Rhs,
typename Dest>
158 eigen_assert(m_factorizationIsOk &&
"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
169 if(m_matrix.nonZeros()>0)
170 derived().matrixL().solveInPlace(dest);
175 if (m_matrix.nonZeros()>0)
176 derived().matrixU().solveInPlace(dest);
179 dest = m_Pinv * dest;
182 template<
typename Rhs,
typename Dest>
188 #endif // EIGEN_PARSED_BY_DOXYGEN 193 template<
bool DoLDLT>
198 CholMatrixType tmp(size,size);
199 ConstCholMatrixPtr pmat;
201 analyzePattern_preordered(*pmat, DoLDLT);
202 factorize_preordered<DoLDLT>(*pmat);
205 template<
bool DoLDLT>
210 CholMatrixType tmp(size,size);
211 ConstCholMatrixPtr pmat;
220 tmp.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().
twistedBy(m_P);
224 factorize_preordered<DoLDLT>(*pmat);
227 template<
bool DoLDLT>
228 void factorize_preordered(
const CholMatrixType&
a);
234 CholMatrixType tmp(size,size);
235 ConstCholMatrixPtr pmat;
237 analyzePattern_preordered(*pmat,doLDLT);
239 void analyzePattern_preordered(
const CholMatrixType& a,
bool doLDLT);
241 void ordering(
const MatrixType& a, ConstCholMatrixPtr &pmat, CholMatrixType& ap);
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;
272 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
struct traits<
SimplicialLLT<_MatrixType,_UpLo,_Ordering> >
276 enum { UpLo = _UpLo };
282 static inline MatrixL
getL(
const MatrixType&
m) {
return MatrixL(m); }
283 static inline MatrixU
getU(
const MatrixType&
m) {
return MatrixU(m.adjoint()); }
286 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
struct traits<
SimplicialLDLT<_MatrixType,_UpLo,_Ordering> >
290 enum { UpLo = _UpLo };
296 static inline MatrixL
getL(
const MatrixType&
m) {
return MatrixL(m); }
297 static inline MatrixU
getU(
const MatrixType&
m) {
return MatrixU(m.adjoint()); }
304 enum { UpLo = _UpLo };
329 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
334 enum { UpLo = _UpLo };
353 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LLT not factorized");
354 return Traits::getL(Base::m_matrix);
359 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LLT not factorized");
360 return Traits::getU(Base::m_matrix);
366 Base::template compute<false>(
matrix);
378 Base::analyzePattern(a,
false);
389 Base::template factorize<false>(
a);
395 Scalar detL = Base::m_matrix.diagonal().prod();
420 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
425 enum { UpLo = _UpLo };
445 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LDLT not factorized");
450 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LDLT not factorized");
451 return Traits::getL(Base::m_matrix);
456 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LDLT not factorized");
457 return Traits::getU(Base::m_matrix);
463 Base::template compute<true>(
matrix);
475 Base::analyzePattern(a,
true);
486 Base::template factorize<true>(
a);
492 return Base::m_diag.prod();
502 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
507 enum { UpLo = _UpLo };
521 : Base(), m_LDLT(true)
544 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial Cholesky not factorized");
548 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial Cholesky not factorized");
549 return Base::m_matrix;
556 Base::template compute<true>(
matrix);
558 Base::template compute<false>(
matrix);
570 Base::analyzePattern(a, m_LDLT);
582 Base::template factorize<true>(
a);
584 Base::template factorize<false>(
a);
588 template<
typename Rhs,
typename Dest>
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()");
597 if(Base::m_P.
size()>0)
598 dest = Base::m_P * b;
602 if(Base::m_matrix.nonZeros()>0)
605 LDLTTraits::getL(Base::m_matrix).solveInPlace(dest);
607 LLTTraits::getL(Base::m_matrix).solveInPlace(dest);
610 if(Base::m_diag.
size()>0)
611 dest = Base::m_diag.
asDiagonal().inverse() * dest;
613 if (Base::m_matrix.nonZeros()>0)
616 LDLTTraits::getU(Base::m_matrix).solveInPlace(dest);
618 LLTTraits::getU(Base::m_matrix).solveInPlace(dest);
621 if(Base::m_P.
size()>0)
622 dest = Base::m_Pinv * dest;
626 template<
typename Rhs,
typename Dest>
636 return Base::m_diag.prod();
649 template<
typename Derived>
660 C = a.template selfadjointView<UpLo>();
666 if(m_Pinv.size()>0) m_P = m_Pinv.inverse();
670 ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().
twistedBy(m_P);
676 if(
int(UpLo)==
int(
Lower) || MatrixType::IsRowMajor)
680 ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>();
689 #endif // EIGEN_SIMPLICIAL_CHOLESKY_H
MatrixType::StorageIndex StorageIndex
internal::traits< SimplicialLDLT > Traits
const MatrixL matrixL() const
MatrixType::Scalar Scalar
static MatrixL getL(const MatrixType &m)
internal::traits< SimplicialCholesky > Traits
Scalar determinant() const
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
static MatrixL getL(const MatrixType &m)
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)
A base class for sparse solvers.
MatrixType::Scalar Scalar
MatrixType::Scalar Scalar
~SimplicialCholeskyBase()
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.
void _solve_impl(const MatrixBase< Rhs > &b, MatrixBase< Dest > &dest) const
SparseMatrix< Scalar, ColMajor, StorageIndex > CholMatrixType
SimplicialCholeskyBase< SimplicialLLT > Base
SimplicialCholeskyBase(const MatrixType &matrix)
TriangularView< const typename CholMatrixType::AdjointReturnType, Eigen::UnitUpper > MatrixU
A direct sparse LDLT Cholesky factorizations without square root.
MatrixType::Scalar Scalar
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)
MatrixType::RealScalar RealScalar
void _solve_impl(const SparseMatrixBase< Rhs > &b, SparseMatrixBase< Dest > &dest) const
MatrixType::Scalar Scalar
void analyzePattern(const MatrixType &a)
MatrixType::Scalar Scalar
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)
SparseMatrix< Scalar, ColMajor, StorageIndex > CholMatrixType
A base class for direct sparse Cholesky factorizations.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
TriangularView< const CholMatrixType, Eigen::UnitLower > MatrixL
MatrixType::StorageIndex StorageIndex
MatrixType::StorageIndex StorageIndex
internal::traits< Derived >::OrderingType OrderingType
SimplicialLLT(const MatrixType &matrix)
const MatrixL matrixL() const
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
const MatrixU matrixU() const
MatrixType::RealScalar RealScalar
MatrixType::StorageIndex StorageIndex
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
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)
static MatrixU getU(const MatrixType &m)
internal::traits< Derived >::MatrixType MatrixType
Expression of a triangular part in a matrix.
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)
SparseMatrix< Scalar, ColMajor, StorageIndex > CholMatrixType
MatrixType::StorageIndex StorageIndex
void analyzePattern(const MatrixType &a)
Expression of a diagonal/subdiagonal/superdiagonal in a matrix.
Matrix< Scalar, Dynamic, 1 > VectorType
static MatrixU getU(const MatrixType &m)
void dumpMemory(Stream &s)
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
SparseMatrix< Scalar, ColMajor, StorageIndex > CholMatrixType
Base class for all dense matrices, vectors, and expressions.
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)
void analyzePattern(const MatrixType &a)
void _solve_impl(const MatrixBase< Rhs > &b, MatrixBase< Dest > &dest) const
const VectorType vectorD() const