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