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
84 m_factorizationIsOk(false),
85 m_analysisIsOk(false),
92 m_factorizationIsOk(false),
93 m_analysisIsOk(false),
97 derived().compute(matrix);
104 Derived&
derived() {
return *
static_cast<Derived*
>(
this); }
105 const Derived&
derived()
const {
return *
static_cast<const Derived*
>(
this); }
117 eigen_assert(m_isInitialized &&
"Decomposition is not initialized.");
143 m_shiftScale =
scale;
147 #ifndef EIGEN_PARSED_BY_DOXYGEN 149 template<
typename Stream>
153 s <<
" L: " << ((total+=(m_matrix.cols()+1) *
sizeof(
int) + m_matrix.nonZeros()*(
sizeof(
int)+
sizeof(Scalar))) >> 20) <<
"Mb" <<
"\n";
154 s <<
" diag: " << ((total+=m_diag.size() *
sizeof(
Scalar)) >> 20) <<
"Mb" <<
"\n";
155 s <<
" tree: " << ((total+=m_parent.size() *
sizeof(
int)) >> 20) <<
"Mb" <<
"\n";
156 s <<
" nonzeros: " << ((total+=m_nonZerosPerCol.size() *
sizeof(
int)) >> 20) <<
"Mb" <<
"\n";
157 s <<
" perm: " << ((total+=m_P.size() *
sizeof(
int)) >> 20) <<
"Mb" <<
"\n";
158 s <<
" perm^-1: " << ((total+=m_Pinv.size() *
sizeof(
int)) >> 20) <<
"Mb" <<
"\n";
159 s <<
" TOTAL: " << (total>> 20) <<
"Mb" <<
"\n";
163 template<
typename Rhs,
typename Dest>
166 eigen_assert(m_factorizationIsOk &&
"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
177 if(m_matrix.nonZeros()>0)
178 derived().matrixL().solveInPlace(dest);
183 if (m_matrix.nonZeros()>0)
184 derived().matrixU().solveInPlace(dest);
187 dest = m_Pinv * dest;
190 template<
typename Rhs,
typename Dest>
196 #endif // EIGEN_PARSED_BY_DOXYGEN 201 template<
bool DoLDLT>
206 CholMatrixType tmp(size,size);
207 ConstCholMatrixPtr pmat;
209 analyzePattern_preordered(*pmat, DoLDLT);
210 factorize_preordered<DoLDLT>(*pmat);
213 template<
bool DoLDLT>
218 CholMatrixType tmp(size,size);
219 ConstCholMatrixPtr pmat;
228 tmp.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().
twistedBy(m_P);
232 factorize_preordered<DoLDLT>(*pmat);
235 template<
bool DoLDLT>
236 void factorize_preordered(
const CholMatrixType&
a);
242 CholMatrixType tmp(size,size);
243 ConstCholMatrixPtr pmat;
245 analyzePattern_preordered(*pmat,doLDLT);
247 void analyzePattern_preordered(
const CholMatrixType& a,
bool doLDLT);
249 void ordering(
const MatrixType& a, ConstCholMatrixPtr &pmat, CholMatrixType& ap);
274 template<
typename _MatrixType,
int _UpLo = Lower,
typename _Ordering = AMDOrdering<
typename _MatrixType::StorageIndex> >
class SimplicialLLT;
275 template<
typename _MatrixType,
int _UpLo = Lower,
typename _Ordering = AMDOrdering<
typename _MatrixType::StorageIndex> >
class SimplicialLDLT;
276 template<
typename _MatrixType,
int _UpLo = Lower,
typename _Ordering = AMDOrdering<
typename _MatrixType::StorageIndex> >
class SimplicialCholesky;
280 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
struct traits<
SimplicialLLT<_MatrixType,_UpLo,_Ordering> >
284 enum { UpLo = _UpLo };
290 static inline MatrixL
getL(
const CholMatrixType&
m) {
return MatrixL(m); }
291 static inline MatrixU
getU(
const CholMatrixType&
m) {
return MatrixU(m.
adjoint()); }
294 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
struct traits<
SimplicialLDLT<_MatrixType,_UpLo,_Ordering> >
298 enum { UpLo = _UpLo };
304 static inline MatrixL
getL(
const CholMatrixType&
m) {
return MatrixL(m); }
305 static inline MatrixU
getU(
const CholMatrixType&
m) {
return MatrixU(m.
adjoint()); }
312 enum { UpLo = _UpLo };
337 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
342 enum { UpLo = _UpLo };
361 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LLT not factorized");
362 return Traits::getL(Base::m_matrix);
367 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LLT not factorized");
368 return Traits::getU(Base::m_matrix);
374 Base::template compute<false>(
matrix);
386 Base::analyzePattern(a,
false);
397 Base::template factorize<false>(
a);
403 Scalar detL = Base::m_matrix.diagonal().prod();
428 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
433 enum { UpLo = _UpLo };
453 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LDLT not factorized");
458 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LDLT not factorized");
459 return Traits::getL(Base::m_matrix);
464 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial LDLT not factorized");
465 return Traits::getU(Base::m_matrix);
471 Base::template compute<true>(
matrix);
483 Base::analyzePattern(a,
true);
494 Base::template factorize<true>(
a);
500 return Base::m_diag.prod();
510 template<
typename _MatrixType,
int _UpLo,
typename _Ordering>
515 enum { UpLo = _UpLo };
529 : Base(), m_LDLT(true)
552 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial Cholesky not factorized");
556 eigen_assert(Base::m_factorizationIsOk &&
"Simplicial Cholesky not factorized");
557 return Base::m_matrix;
564 Base::template compute<true>(
matrix);
566 Base::template compute<false>(
matrix);
578 Base::analyzePattern(a, m_LDLT);
590 Base::template factorize<true>(
a);
592 Base::template factorize<false>(
a);
596 template<
typename Rhs,
typename Dest>
599 eigen_assert(Base::m_factorizationIsOk &&
"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
605 if(Base::m_P.
size()>0)
606 dest = Base::m_P * b;
610 if(Base::m_matrix.nonZeros()>0)
613 LDLTTraits::getL(Base::m_matrix).solveInPlace(dest);
615 LLTTraits::getL(Base::m_matrix).solveInPlace(dest);
618 if(Base::m_diag.
size()>0)
619 dest = Base::m_diag.
real().asDiagonal().inverse() * dest;
621 if (Base::m_matrix.nonZeros()>0)
624 LDLTTraits::getU(Base::m_matrix).solveInPlace(dest);
626 LLTTraits::getU(Base::m_matrix).solveInPlace(dest);
629 if(Base::m_P.
size()>0)
630 dest = Base::m_Pinv * dest;
634 template<
typename Rhs,
typename Dest>
644 return Base::m_diag.prod();
657 template<
typename Derived>
668 C = a.template selfadjointView<UpLo>();
674 if(m_Pinv.size()>0) m_P = m_Pinv.inverse();
678 ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().
twistedBy(m_P);
684 if(
int(UpLo)==
int(
Lower) || MatrixType::IsRowMajor)
688 ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>();
697 #endif // EIGEN_SIMPLICIAL_CHOLESKY_H
MatrixType::StorageIndex StorageIndex
void _solve_impl(const SparseMatrixBase< Rhs > &b, SparseMatrixBase< Dest > &dest) const
internal::traits< SimplicialLDLT > Traits
Scalar determinant() const
MatrixType::Scalar Scalar
const MatrixU matrixU() const
internal::traits< SimplicialCholesky > Traits
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
const Derived & derived() const
Derived & setShift(const RealScalar &offset, const RealScalar &scale=1)
SimplicialCholeskyBase< SimplicialCholesky > Base
SimplicialLLT & compute(const MatrixType &matrix)
const MatrixU matrixU() const
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.
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)
static enum @1107 ordering
EIGEN_DEVICE_FUNC RealReturnType real() const
Scalar determinant() const
const MatrixL matrixL() const
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
MatrixType::Scalar Scalar
void _solve_impl(const MatrixBase< Rhs > &b, MatrixBase< Dest > &dest) const
void analyzePattern(const MatrixType &a)
MatrixType::Scalar Scalar
void compute(const MatrixType &matrix)
const VectorType vectorD() const
Base class of any sparse matrices or sparse expressions.
static MatrixL getL(const CholMatrixType &m)
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
const CholMatrixType rawMatrix() const
SimplicialLLT(const MatrixType &matrix)
SimplicialCholeskyBase< SimplicialLDLT > Base
void analyzePattern(const MatrixType &a, bool doLDLT)
TriangularView< const typename CholMatrixType::AdjointReturnType, Eigen::Upper > MatrixU
Matrix< Scalar, Dynamic, 1 > VectorType
void factorize(const MatrixType &a)
CholMatrixType const * ConstCholMatrixPtr
const AdjointReturnType adjoint() const
NumTraits< Scalar >::Real RealScalar
MatrixType::RealScalar RealScalar
MatrixType::StorageIndex StorageIndex
Matrix< Scalar, Dynamic, Dynamic > C
MatrixType::StorageIndex StorageIndex
EIGEN_DEVICE_FUNC const DiagonalWrapper< const Derived > asDiagonal() const
EIGEN_CONSTEXPR Index size(const T &x)
TriangularView< const CholMatrixType, Eigen::Lower > MatrixL
internal::traits< SimplicialLLT< MatrixType, UpLo > > LLTTraits
ComputationInfo info() const
Reports whether previous computation was successful.
const PermutationMatrix< Dynamic, Dynamic, StorageIndex > & permutationPinv() const
static MatrixU getU(const CholMatrixType &m)
const PermutationMatrix< Dynamic, Dynamic, StorageIndex > & permutationP() const
SparseMatrix< Scalar, ColMajor, StorageIndex > CholMatrixType
SimplicialLDLT(const MatrixType &matrix)
void factorize(const MatrixType &a)
internal::traits< Derived >::MatrixType MatrixType
const VectorType vectorD() const
Expression of a triangular part in a matrix.
void _solve_impl(const MatrixBase< Rhs > &b, MatrixBase< Dest > &dest) const
SparseSymmetricPermutationProduct< Derived, Upper|Lower > twistedBy(const PermutationMatrix< Dynamic, Dynamic, StorageIndex > &perm) const
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
Scalar determinant() const
void analyzePattern(const MatrixType &a)
Expression of a diagonal/subdiagonal/superdiagonal in a matrix.
static MatrixU getU(const CholMatrixType &m)
Matrix< Scalar, Dynamic, 1 > VectorType
static const DiscreteKey mode(modeKey, 2)
static MatrixL getL(const CholMatrixType &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)
SimplicialCholesky & setMode(SimplicialCholeskyMode mode)
internal::traits< SimplicialLLT > Traits
MatrixType::RealScalar RealScalar
Matrix< Scalar, Dynamic, 1 > VectorType
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
SparseMatrix< Scalar, ColMajor, StorageIndex > CholMatrixType
EIGEN_DEVICE_FUNC bool abs2(bool x)
Base class for all dense matrices, vectors, and expressions.
const MatrixL matrixL() 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)