10 #ifndef EIGEN_KLUSUPPORT_H 11 #define EIGEN_KLUSUPPORT_H 34 inline int klu_solve(klu_symbolic *Symbolic, klu_numeric *Numeric,
Index ldim,
Index nrhs,
double B [ ], klu_common *Common,
double) {
35 return klu_solve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), B, Common);
38 inline int klu_solve(klu_symbolic *Symbolic, klu_numeric *Numeric,
Index ldim,
Index nrhs, std::complex<double>
B[], klu_common *Common, std::complex<double>) {
39 return klu_z_solve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), &
numext::real_ref(B[0]), Common);
42 inline int klu_tsolve(klu_symbolic *Symbolic, klu_numeric *Numeric,
Index ldim,
Index nrhs,
double B[], klu_common *Common,
double) {
43 return klu_tsolve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), B, Common);
46 inline int klu_tsolve(klu_symbolic *Symbolic, klu_numeric *Numeric,
Index ldim,
Index nrhs, std::complex<double>
B[], klu_common *Common, std::complex<double>) {
47 return klu_z_tsolve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), &
numext::real_ref(B[0]), 0, Common);
50 inline klu_numeric*
klu_factor(
int Ap [ ],
int Ai [ ],
double Ax [ ], klu_symbolic *Symbolic, klu_common *Common,
double) {
51 return klu_factor(Ap, Ai, Ax, Symbolic, Common);
54 inline klu_numeric*
klu_factor(
int Ap[],
int Ai[], std::complex<double> Ax[], klu_symbolic *Symbolic, klu_common *Common, std::complex<double>) {
59 template<
typename _MatrixType>
90 template<
typename InputMatrixType>
117 #if 0 // not implemented yet 118 inline const LUMatrixType& matrixL()
const 124 inline const LUMatrixType& matrixU()
const 130 inline const IntColVectorType& permutationP()
const 136 inline const IntRowVectorType& permutationQ()
const 146 template<
typename InputMatrixType>
151 grab(matrix.derived());
162 template<
typename InputMatrixType>
168 grab(matrix.derived());
200 template<
typename InputMatrixType>
207 grab(matrix.derived());
213 template<
typename BDerived,
typename XDerived>
216 #if 0 // not implemented yet 219 void extractData()
const;
241 const_cast<StorageIndex*>(
mp_matrix.outerIndexPtr()), const_cast<StorageIndex*>(
mp_matrix.innerIndexPtr()),
263 template<
typename MatrixDerived>
280 #if 0 // not implemented yet 281 mutable LUMatrixType m_l;
282 mutable LUMatrixType m_u;
283 mutable IntColVectorType m_p;
284 mutable IntRowVectorType m_q;
302 #if 0 // not implemented yet 303 template<
typename MatrixType>
308 eigen_assert(
false &&
"KLU: extractData Not Yet Implemented");
315 m_l.resize(rows,(
std::min)(rows,cols));
316 m_l.resizeNonZeros(lnz);
318 m_u.resize((
std::min)(rows,cols),cols);
319 m_u.resizeNonZeros(unz);
326 m_u.outerIndexPtr(), m_u.innerIndexPtr(), m_u.valuePtr(),
327 m_p.data(), m_q.data(), 0, 0, 0,
m_numeric);
333 template<
typename MatrixType>
336 eigen_assert(
false &&
"KLU: extractData Not Yet Implemented");
341 template<
typename MatrixType>
342 template<
typename BDerived,
typename XDerived>
345 Index rhsCols = b.cols();
347 eigen_assert(
m_factorizationIsOk &&
"The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()");
358 #endif // EIGEN_KLUSUPPORT_H Matrix< Scalar, Dynamic, 1 > Vector
int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, double)
MatrixType::StorageIndex StorageIndex
EIGEN_DEVICE_FUNC internal::add_const_on_value_type< EIGEN_MATHFUNC_RETVAL(real_ref, Scalar) >::type real_ref(const Scalar &x)
Matrix< int, 1, MatrixType::ColsAtCompileTime > IntRowVectorType
klu_symbolic * m_symbolic
void factorize(const InputMatrixType &matrix)
klu_numeric * klu_factor(int Ap [], int Ai [], double Ax [], klu_symbolic *Symbolic, klu_common *Common, double)
void analyzePattern(const InputMatrixType &matrix)
void determinant(const MatrixType &m)
A base class for sparse solvers.
Namespace containing all symbols from the Eigen library.
void compute(const InputMatrixType &matrix)
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
const unsigned int RowMajorBit
Ref< const KLUMatrixType, StandardCompressedFormat > KLUMatrixRef
bool m_extractedDataAreDirty
void _solve_impl(const SparseMatrixBase< Rhs > &b, SparseMatrixBase< Dest > &dest) const
SparseMatrix< Scalar, ColMajor, int > KLUMatrixType
int klu_tsolve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, double B[], klu_common *Common, double)
bool _solve_impl(const MatrixBase< BDerived > &b, MatrixBase< XDerived > &x) const
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
void grab(const EigenBase< MatrixDerived > &A)
KLU(const InputMatrixType &matrix)
NumTraits< Scalar >::Real RealScalar
void grab(const KLUMatrixRef &A)
SparseMatrix< Scalar > LUMatrixType
ComputationInfo info() const
Reports whether previous computation was successful.
MatrixType::RealScalar RealScalar
const klu_common & kluCommon() const
int umfpack_get_numeric(int Lp[], int Lj[], double Lx[], int Up[], int Ui[], double Ux[], int P[], int Q[], double Dx[], int *do_recip, double Rs[], void *Numeric)
void analyzePattern_impl()
MatrixType::Scalar Scalar
EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
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 x
EIGEN_DEVICE_FUNC Derived & derived()
Base class for all dense matrices, vectors, and expressions.
SparseSolverBase< KLU< _MatrixType > > Base
int klu_solve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, double B [], klu_common *Common, double)
A sparse LU factorization and solver based on KLU.
Matrix< int, MatrixType::RowsAtCompileTime, 1 > IntColVectorType