7 #ifndef SPARSE_CHOLESKY_H 8 #define SPARSE_CHOLESKY_H 11 #include <Eigen/SparseCore> 12 #include <Eigen/SparseCholesky> 14 #include "../Util/CompInfo.h" 26 template <
typename Scalar,
int Uplo = Eigen::Lower,
int Flags = 0,
typename StorageIndex =
int>
52 if (mat.rows() != mat.cols())
53 throw std::invalid_argument(
"SparseCholesky: matrix must be square");
85 MapConstVec
x(x_in, m_n);
88 m_decomp.
matrixL().solveInPlace(y);
100 MapConstVec
x(x_in, m_n);
101 MapVec
y(y_out, m_n);
102 y.noalias() = m_decomp.
matrixU().solve(x);
109 #endif // SPARSE_CHOLESKY_H
const MatrixU matrixU() const
Eigen::SparseMatrix< Scalar, Flags, StorageIndex > SparseMatrix
void lower_triangular_solve(const Scalar *x_in, Scalar *y_out) const
A versatible sparse matrix representation.
SimplicialLLT & compute(const MatrixType &matrix)
A matrix or vector expression mapping an existing array of data.
void upper_triangular_solve(const Scalar *x_in, Scalar *y_out) const
const Eigen::Ref< const SparseMatrix > ConstGenericSparseMatrix
Computation was successful.
Eigen::Map< const Vector > MapConstVec
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
SparseCholesky(ConstGenericSparseMatrix &mat)
Eigen::SimplicialLLT< SparseMatrix, Uplo > m_decomp
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
ComputationInfo info() const
Reports whether previous computation was successful.
const PermutationMatrix< Dynamic, Dynamic, StorageIndex > & permutationPinv() const
const PermutationMatrix< Dynamic, Dynamic, StorageIndex > & permutationP() const
Eigen::Map< Vector > MapVec
A direct sparse LLT Cholesky factorizations.
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 MatrixL matrixL() const