11 #ifndef TRIDIAG_EIGEN_H 12 #define TRIDIAG_EIGEN_H 15 #include <Eigen/Jacobi> 18 #include "../Util/TypeTraits.h" 22 template <
typename Scalar =
double>
46 RealScalar* subdiag, Index start,
52 RealScalar td = (diag[end - 1] - diag[
end]) *
RealScalar(0.5);
53 RealScalar
e = subdiag[end - 1];
59 RealScalar
mu = diag[
end];
72 RealScalar
x = diag[start] -
mu;
73 RealScalar
z = subdiag[start];
75 for (Index k = start; k <
end; ++k)
80 const RealScalar
s = rot.
s();
81 const RealScalar
c = rot.
c();
84 RealScalar sdk = s * diag[k] + c * subdiag[k];
85 RealScalar dkp1 = s * subdiag[k] + c * diag[k + 1];
87 diag[k] = c * (c * diag[k] - s * subdiag[k]) - s * (c * subdiag[k] - s * diag[k + 1]);
88 diag[k + 1] = s * sdk + c * dkp1;
89 subdiag[k] = c * sdk - s * dkp1;
92 subdiag[k - 1] = c * subdiag[k - 1] - s *
z;
98 z = -s * subdiag[k + 1];
99 subdiag[k + 1] = c * subdiag[k + 1];
104 q.applyOnTheRight(k, k + 1, rot);
110 m_n(0), m_computed(false),
115 m_n(mat.
rows()), m_computed(false),
126 if (m_n != mat.cols())
127 throw std::invalid_argument(
"TridiagEigen: matrix must be square");
130 m_sub_diag.
resize(m_n - 1);
132 m_evecs.setIdentity();
136 mat.diagonal(-1).cwiseAbs().maxCoeff());
138 if (scale < m_near_0)
147 m_main_diag.noalias() = mat.diagonal() /
scale;
148 m_sub_diag.noalias() = mat.diagonal(-1) /
scale;
163 for (Index
i = start;
i <
end;
i++)
164 if (
abs(subdiag[
i]) <= considerAsZero ||
165 abs(subdiag[i]) <= (
abs(diag[i]) +
abs(diag[i + 1])) * precision)
169 while (end > 0 && subdiag[end - 1] ==
Scalar(0))
184 while (start > 0 && subdiag[start - 1] !=
Scalar(0))
191 throw std::runtime_error(
"TridiagEigen: eigen decomposition failed");
194 m_main_diag *=
scale;
202 throw std::logic_error(
"TridiagEigen: need to call compute() first");
211 throw std::logic_error(
"TridiagEigen: need to call compute() first");
219 #endif // TRIDIAG_EIGEN_H
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
const Vector & eigenvalues() const
const Matrix & eigenvectors() const
Matrix diag(const std::vector< Matrix > &Hs)
A matrix or vector expression mapping an existing array of data.
Eigen::Ref< Matrix > GenericMatrix
void compute(ConstGenericMatrix &mat)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
Rotation given by a cosine-sine pair.
iterator iter(handle obj)
const Eigen::Ref< const Matrix > ConstGenericMatrix
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Abs2ReturnType abs2() const
A matrix or vector expression mapping an existing expression.
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
TridiagEigen(ConstGenericMatrix &mat)
const mpreal hypot(const mpreal &x, const mpreal &y, mp_rnd_t rnd_mode=mpreal::get_default_rnd())
static void tridiagonal_qr_step(RealScalar *diag, RealScalar *subdiag, Index start, Index end, Scalar *matrixQ, Index n)
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics scale
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 makeGivens(const Scalar &p, const Scalar &q, Scalar *r=0)