7 #ifndef SPARSE_SYM_SHIFT_SOLVE_H 8 #define SPARSE_SYM_SHIFT_SOLVE_H 11 #include <Eigen/SparseCore> 12 #include <Eigen/SparseLU> 24 template <
typename Scalar,
int Uplo = Eigen::Lower,
int Flags = 0,
typename StorageIndex =
int>
48 m_mat(mat), m_n(mat.
rows())
50 if (mat.rows() != mat.cols())
51 throw std::invalid_argument(
"SparseSymShiftSolve: matrix must be square");
68 SparseMatrix
mat = m_mat.template selfadjointView<Uplo>();
69 SparseMatrix identity(m_n, m_n);
70 identity.setIdentity();
71 mat = mat - sigma * identity;
75 throw std::invalid_argument(
"SparseSymShiftSolve: factorization failed with the given shift");
87 MapConstVec
x(x_in, m_n);
89 y.noalias() = m_solver.
solve(x);
95 #endif // SPARSE_SYM_SHIFT_SOLVE_H void set_shift(Scalar sigma)
A versatible sparse matrix representation.
Eigen::Map< const Vector > MapConstVec
A matrix or vector expression mapping an existing array of data.
static const double sigma
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
const Solve< SparseLU< _MatrixType, _OrderingType >, Rhs > solve(const MatrixBase< Rhs > &b) const
ConstGenericSparseMatrix m_mat
const Eigen::Ref< const SparseMatrix > ConstGenericSparseMatrix
ComputationInfo info() const
Reports whether previous computation was successful.
Sparse supernodal LU factorization for general matrices.
SparseSymShiftSolve(ConstGenericSparseMatrix &mat)
void compute(const MatrixType &matrix)
void isSymmetric(bool sym)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Eigen::SparseMatrix< Scalar, Flags, StorageIndex > SparseMatrix
Eigen::Map< Vector > MapVec
void perform_op(const Scalar *x_in, Scalar *y_out) const
Eigen::SparseLU< SparseMatrix > m_solver
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