7 #ifndef SYM_EIGS_BASE_H 8 #define SYM_EIGS_BASE_H 91 Matrix
Q = Matrix::Identity(m_ncv, m_ncv);
116 Array thresh = tol * m_ritz_val.head(m_nev).array().abs().max(m_eps23);
117 Array resid = m_ritz_est.head(m_nev).array().abs() * m_fac.
f_norm();
119 m_ritz_conv = (resid < thresh);
121 return m_ritz_conv.cast<Index>().sum();
129 Index nev_new =
m_nev;
130 for (Index
i = m_nev;
i <
m_ncv;
i++)
131 if (
abs(m_ritz_est[
i]) < m_near_0)
135 nev_new +=
std::min(nconv, (m_ncv - nev_new) / 2);
136 if (nev_new == 1 && m_ncv >= 6)
138 else if (nev_new == 1 && m_ncv > 2)
141 if (nev_new > m_ncv - 1)
152 const Matrix& evecs = decomp.eigenvectors();
154 SortEigenvalue<Scalar, SelectionRule> sorting(evals.data(), evals.size());
155 std::vector<int>
ind = sorting.index();
167 std::vector<int> ind_copy(ind);
173 ind[
i] = ind_copy[
i / 2];
175 ind[
i] = ind_copy[m_ncv - 1 -
i / 2];
182 m_ritz_val[
i] = evals[ind[
i]];
183 m_ritz_est[
i] = evecs(m_ncv - 1, ind[
i]);
187 m_ritz_vec.col(
i).noalias() = evecs.col(ind[
i]);
197 SortEigenvalue<Scalar, LARGEST_ALGE> sorting(m_ritz_val.
data(),
m_nev);
198 std::vector<int>
ind = sorting.index();
206 SortEigenvalue<Scalar, LARGEST_MAGN> sorting(m_ritz_val.
data(),
m_nev);
207 ind = sorting.index();
212 SortEigenvalue<Scalar, SMALLEST_ALGE> sorting(m_ritz_val.
data(),
m_nev);
213 ind = sorting.index();
218 SortEigenvalue<Scalar, SMALLEST_MAGN> sorting(m_ritz_val.
data(),
m_nev);
219 ind = sorting.index();
223 throw std::invalid_argument(
"unsupported sorting rule");
226 Vector new_ritz_val(m_ncv);
227 Matrix new_ritz_vec(m_ncv, m_nev);
228 BoolArray new_ritz_conv(m_nev);
232 new_ritz_val[
i] = m_ritz_val[ind[
i]];
233 new_ritz_vec.col(
i).noalias() = m_ritz_vec.col(ind[
i]);
234 new_ritz_conv[
i] = m_ritz_conv[ind[
i]];
237 m_ritz_val.
swap(new_ritz_val);
238 m_ritz_vec.
swap(new_ritz_vec);
239 m_ritz_conv.
swap(new_ritz_conv);
245 SymEigsBase(OpType* op, BOpType* Bop, Index nev, Index ncv) :
249 m_ncv(ncv > m_n ? m_n : ncv),
258 if (nev < 1 || nev > m_n - 1)
259 throw std::invalid_argument(
"nev must satisfy 1 <= nev <= n - 1, n is the size of matrix");
261 if (ncv <= nev || ncv > m_n)
262 throw std::invalid_argument(
"ncv must satisfy nev < ncv <= n, n is the size of matrix");
285 m_ritz_vec.
resize(m_ncv, m_nev);
287 m_ritz_conv.
resize(m_nev);
298 MapConstVec
v0(init_resid, m_n);
299 m_fac.
init(v0, m_nmatop);
311 SimpleRandom<Scalar>
rng(0);
312 Vector init_resid = rng.random_vec(m_n);
340 Index
i, nconv = 0, nev_adj;
341 for (i = 0; i < maxit; i++)
384 const Index nconv = m_ritz_conv.cast<Index>().sum();
395 res[
j] = m_ritz_val[
i];
414 const Index nconv = m_ritz_conv.cast<Index>().sum();
416 Matrix
res(m_n, nvec);
421 Matrix ritz_vec_conv(m_ncv, nvec);
423 for (Index
i = 0;
i < m_nev && j < nvec;
i++)
427 ritz_vec_conv.col(j).noalias() = m_ritz_vec.col(i);
432 res.noalias() = m_fac.
matrix_V() * ritz_vec_conv;
448 #endif // SYM_EIGS_BASE_H
ArnoldiOp< Scalar, OpType, BOpType > ArnoldiOpType
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
Vector eigenvalues() const
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
Index num_converged(Scalar tol)
A matrix or vector expression mapping an existing array of data.
void compute(ConstGenericMatrix &mat, const Scalar &shift=Scalar(0))
const Vector & eigenvalues() const
Eigen::Array< Scalar, Eigen::Dynamic, 1 > Array
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void swap(DenseBase< OtherDerived > &other)
const Matrix & matrix_V() const
Computation was successful.
void init(MapConstVec &v0, Index &op_counter)
Index num_operations() const
Select eigenvalues with smallest algebraic value. Only for symmetric eigen solvers.
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
virtual void sort_ritzpair(int sort_rule)
Eigen::Map< Vector > MapVec
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
virtual Matrix eigenvectors() const
void compress_H(const TridiagQR< Scalar > &decomp)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Index num_iterations() const
const Matrix & matrix_H() const
Eigen::Map< Matrix > MapMat
Index nev_adjusted(Index nconv)
void compress_V(const Matrix &Q)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Index compute(Index maxit=1000, Scalar tol=1e-10, int sort_rule=LARGEST_ALGE)
Eigen::Array< bool, Eigen::Dynamic, 1 > BoolArray
EIGEN_DEVICE_FUNC internal::pow_impl< ScalarX, ScalarY >::result_type pow(const ScalarX &x, const ScalarY &y)
Eigen::Map< const Vector > MapConstVec
void init(const Scalar *init_resid)
The quaternion class used to represent 3D orientations and rotations.
virtual Matrix eigenvectors(Index nvec) const
void apply_YQ(GenericMatrix Y) const
void factorize_from(Index from_k, Index to_m, Index &op_counter)
Lanczos< Scalar, ArnoldiOpType > LanczosFac