Go to the documentation of this file.
10 #ifndef EIGEN_CHOLMODSUPPORT_H
11 #define EIGEN_CHOLMODSUPPORT_H
20 template<
typename CholmodType>
22 mat.xtype = CHOLMOD_REAL;
23 mat.dtype = CHOLMOD_DOUBLE;
28 template<
typename CholmodType>
30 mat.xtype = CHOLMOD_COMPLEX;
31 mat.dtype = CHOLMOD_DOUBLE;
57 template<
typename _Scalar,
int _Options,
typename _StorageIndex>
61 res.nzmax =
mat.nonZeros();
64 res.p =
mat.outerIndexPtr();
65 res.i =
mat.innerIndexPtr();
69 if(
mat.isCompressed())
77 res.nz =
mat.innerNonZeroPtr();
85 res.itype = CHOLMOD_INT;
89 res.itype = CHOLMOD_LONG;
104 template<
typename _Scalar,
int _Options,
typename _Index>
111 template<
typename _Scalar,
int _Options,
typename _Index>
120 template<
typename _Scalar,
int _Options,
typename _Index,
unsigned int UpLo>
136 template<
typename Derived>
146 res.d = Derived::IsVectorAtCompileTime ?
mat.derived().size() :
mat.derived().outerStride();
147 res.x = (
void*)(
mat.derived().data());
157 template<
typename Scalar,
int Flags,
typename StorageIndex>
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) );
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); }
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); }
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); }
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); }
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); }
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); }
197 #undef EIGEN_CHOLMOD_SPECIALIZE0
198 #undef EIGEN_CHOLMOD_SPECIALIZE1
213 template<
typename _MatrixType,
int _UpLo,
typename Derived>
239 internal::cm_start<StorageIndex>(
m_cholmod);
247 internal::cm_start<StorageIndex>(
m_cholmod);
255 internal::cm_finish<StorageIndex>(
m_cholmod);
323 #ifndef EIGEN_PARSED_BY_DOXYGEN
325 template<
typename Rhs,
typename Dest>
328 eigen_assert(
m_factorizationIsOk &&
"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
346 internal::cm_free_dense<StorageIndex>(x_cd,
m_cholmod);
350 template<
typename RhsDerived,
typename DestDerived>
353 eigen_assert(
m_factorizationIsOk &&
"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
369 dest.
derived() = viewAsEigen<typename DestDerived::Scalar,ColMajor,typename DestDerived::StorageIndex>(*x_cs);
370 internal::cm_free_sparse<StorageIndex>(x_cs,
m_cholmod);
372 #endif // EIGEN_PARSED_BY_DOXYGEN
402 eigen_assert(
m_factorizationIsOk &&
"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()");
419 for (
Index k=0; k < nb_super_nodes; ++k)
425 logDet += sk.real().log().sum();
441 template<
typename Stream>
476 template<
typename _MatrixType,
int _UpLo = Lower>
499 m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;
527 template<
typename _MatrixType,
int _UpLo = Lower>
550 m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;
576 template<
typename _MatrixType,
int _UpLo = Lower>
599 m_cholmod.supernodal = CHOLMOD_SUPERNODAL;
627 template<
typename _MatrixType,
int _UpLo = Lower>
657 m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;
662 m_cholmod.supernodal = CHOLMOD_SUPERNODAL;
666 m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;
682 #endif // EIGEN_CHOLMODSUPPORT_H
The base class for the direct Cholesky factorization of Cholmod.
MappedSparseMatrix< Scalar, Flags, StorageIndex > viewAsEigen(cholmod_sparse &cm)
void factorize(const MatrixType &matrix)
CholmodBase< _MatrixType, _UpLo, CholmodDecomposition > Base
Namespace containing all symbols from the Eigen library.
A versatible sparse matrix representation.
void setMode(CholmodMode mode)
CholmodBase(const MatrixType &matrix)
void _solve_impl(const MatrixBase< Rhs > &b, MatrixBase< Dest > &dest) const
Convenience specialization of Stride to specify only an inner stride See class Map for some examples.
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
const unsigned int RowMajorBit
CholmodBase< _MatrixType, _UpLo, CholmodSimplicialLDLT > Base
const EIGEN_DEVICE_FUNC LogReturnType log() const
CholmodDecomposition(const MatrixType &matrix)
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
A simplicial direct Cholesky (LDLT) factorization and solver based on Cholmod.
double beta(double a, double b)
SparseSolverBase< Derived > Base
#define EIGEN_CHOLMOD_SPECIALIZE1(ret, name, t1, a1)
Scalar logDeterminant() const
cholmod_sparse viewAsCholmod(Ref< SparseMatrix< _Scalar, _Options, _StorageIndex > > mat)
void analyzePattern(const MatrixType &matrix)
cholmod_sparse * cm_spsolve(int sys, cholmod_factor &L, cholmod_sparse &B, cholmod_common &Common)
cholmod_common & cholmod()
int cm_factorize_p(cholmod_sparse *A, double beta[2], _StorageIndex *fset, std::size_t fsize, cholmod_factor *L, cholmod_common &Common)
#define EIGEN_UNUSED_VARIABLE(var)
MatrixType CholMatrixType
cholmod_dense * cm_solve(int sys, cholmod_factor &L, cholmod_dense &B, cholmod_common &Common)
static const DiscreteKey mode(modeKey, 2)
#define EIGEN_CHOLMOD_SPECIALIZE0(ret, name)
Scalar determinant() const
ComputationInfo info() const
Reports whether previous computation was successful.
CholmodSimplicialLDLT(const MatrixType &matrix)
void dumpMemory(Stream &)
A supernodal Cholesky (LLT) factorization and solver based on Cholmod.
A matrix or vector expression mapping an existing array of data.
MatrixType::StorageIndex StorageIndex
static ConstMapType Map(const Scalar *data)
CholmodBase< _MatrixType, _UpLo, CholmodSimplicialLLT > Base
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
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
CholmodSimplicialLLT(const MatrixType &matrix)
const AutoDiffScalar< DerType > & real(const AutoDiffScalar< DerType > &x)
NumTraits< Scalar >::Real RealScalar
MatrixType::Scalar Scalar
A base class for sparse solvers.
A matrix or vector expression mapping an existing expression.
cholmod_dense * cm_solve< SuiteSparse_long >(int sys, cholmod_factor &L, cholmod_dense &B, cholmod_common &Common)
MatrixType::RealScalar RealScalar
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
StorageIndex rows() const
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)
Base class of any sparse matrices or sparse expressions.
A simplicial direct Cholesky (LLT) factorization and solver based on Cholmod.
const Derived & derived() const
Pseudo expression to manipulate a triangular sparse matrix as a selfadjoint matrix.
cholmod_sparse * cm_spsolve< SuiteSparse_long >(int sys, cholmod_factor &L, cholmod_sparse &B, cholmod_common &Common)
Base class for all dense matrices, vectors, and expressions.
void _solve_impl(const SparseMatrixBase< RhsDerived > &b, SparseMatrixBase< DestDerived > &dest) const
Derived & compute(const MatrixType &matrix)
CholmodBase< _MatrixType, _UpLo, CholmodSupernodalLLT > Base
StorageIndex cols() const
cholmod_factor * m_cholmodFactor
A general Cholesky factorization and solver based on Cholmod.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
CholmodSupernodalLLT(const MatrixType &matrix)
RealScalar RealScalar * px
Derived & setShift(const RealScalar &offset)
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:32:06