14 #include <Eigen/Eigenvalues> 15 #include <Eigen/SparseCore> 27 RealScalar scaling = m.cwiseAbs().maxCoeff();
35 VERIFY_IS_APPROX((m.template selfadjointView<Lower>() * eiSymm.eigenvectors())/scaling,
36 (eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal())/scaling);
38 VERIFY_IS_APPROX(m.template selfadjointView<Lower>().eigenvalues(), eiSymm.eigenvalues());
46 if(! eiSymm.eigenvalues().isApprox(eiDirect.
eigenvalues(), eival_eps) )
48 std::cerr <<
"reference eigenvalues: " << eiSymm.eigenvalues().transpose() <<
"\n" 49 <<
"obtained eigenvalues: " << eiDirect.
eigenvalues().transpose() <<
"\n" 50 <<
"diff: " << (eiSymm.eigenvalues()-eiDirect.
eigenvalues()).transpose() <<
"\n" 51 <<
"error (eps): " << (eiSymm.eigenvalues()-eiDirect.
eigenvalues()).norm() / eiSymm.eigenvalues().norm() <<
" (" << eival_eps <<
")\n";
80 RealScalar largerEps = 10*test_precision<RealScalar>();
89 symmA.template triangularView<StrictlyUpper>().
setZero();
90 symmC.template triangularView<StrictlyUpper>().
setZero();
95 symmB.template triangularView<StrictlyUpper>().
setZero();
111 symmB.template selfadjointView<Lower>() * (eiSymmGen.
eigenvectors() * eiSymmGen.
eigenvalues().asDiagonal()), largerEps));
116 VERIFY((symmB.template selfadjointView<Lower>() * (symmC.template selfadjointView<Lower>() * eiSymmGen.
eigenvectors())).isApprox(
122 VERIFY((symmC.template selfadjointView<Lower>() * (symmB.template selfadjointView<Lower>() * eiSymmGen.
eigenvectors())).isApprox(
131 MatrixType id = MatrixType::Identity(rows, cols);
141 eiSymmUninitialized.
compute(symmA,
false);
151 if(rows>1 && cols>1) {
158 VERIFY_IS_APPROX(
MatrixType(symmC.template selfadjointView<Lower>()), tridiag.matrixQ() * tridiag.matrixT() * tridiag.matrixQ().adjoint());
169 if (rows > 1 && rows < 20)
172 symmC(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();
180 eig.compute(a.adjoint() *
a);
197 m << 850.961, 51.966, 0,
207 m << 0.11111111111111114658, 0, 0,
208 0, 0.11111111111111109107, 0,
209 0, 0, 0.11111111111111107719;
218 m1 = m1*m1.transpose();
219 m2 = m1.triangularView<
Upper>();
void selfadjointeigensolver(const MatrixType &m)
EIGEN_DEVICE_FUNC SelfAdjointEigenSolver & computeDirect(const MatrixType &matrix, int options=ComputeEigenvectors)
Computes eigendecomposition of given matrix using a closed-form algorithm.
#define CALL_SUBTEST_12(FUNC)
void svd_fill_random(MatrixType &m, int Option=0)
#define VERIFY_RAISES_ASSERT(a)
#define CALL_SUBTEST_9(FUNC)
#define CALL_SUBTEST_6(FUNC)
#define CALL_SUBTEST_4(FUNC)
void adjoint(const MatrixType &m)
EIGEN_DEVICE_FUNC ComputationInfo info() const
Reports whether previous computation was successful.
#define CALL_SUBTEST_13(FUNC)
#define CALL_SUBTEST_3(FUNC)
EIGEN_DEVICE_FUNC SelfAdjointEigenSolver & compute(const EigenBase< InputType > &matrix, int options=ComputeEigenvectors)
Computes eigendecomposition of given matrix.
#define CALL_SUBTEST_7(FUNC)
void diagonal(const MatrixType &m)
Computes eigenvalues and eigenvectors of selfadjoint matrices.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
Tridiagonal decomposition of a selfadjoint matrix.
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
#define VERIFY_IS_APPROX(a, b)
#define VERIFY_IS_EQUAL(a, b)
#define CALL_SUBTEST_1(FUNC)
EIGEN_DEVICE_FUNC const RealVectorType & eigenvalues() const
Returns the eigenvalues of given matrix.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Computes eigenvalues and eigenvectors of the generalized selfadjoint eigen problem.
SelfAdjointEigenSolver< PlainMatrixType > eig(mat, computeVectors?ComputeEigenvectors:EigenvaluesOnly)
SelfAdjointEigenSolver & computeFromTridiagonal(const RealVectorType &diag, const SubDiagonalType &subdiag, int options=ComputeEigenvectors)
Computes the eigen decomposition from a tridiagonal symmetric matrix.
#define CALL_SUBTEST_8(FUNC)
NumTraits< Scalar >::Real RealScalar
#define VERIFY_IS_MUCH_SMALLER_THAN(a, b)
#define TEST_SET_BUT_UNUSED_VARIABLE(X)
#define CALL_SUBTEST_5(FUNC)
#define CALL_SUBTEST(FUNC)
#define EIGEN_TEST_MAX_SIZE
#define VERIFY_IS_UNITARY(a)
EIGEN_DECLARE_TEST(eigensolver_selfadjoint)
EIGEN_DEVICE_FUNC MatrixType operatorInverseSqrt() const
Computes the inverse square root of the matrix.
GeneralizedSelfAdjointEigenSolver & compute(const MatrixType &matA, const MatrixType &matB, int options=ComputeEigenvectors|Ax_lBx)
Computes generalized eigendecomposition of given matrix pencil.
#define CALL_SUBTEST_2(FUNC)
internal::nested_eval< T, 1 >::type eval(const T &xpr)
EIGEN_DEVICE_FUNC const EigenvectorsType & eigenvectors() const
Returns the eigenvectors of given matrix.
The matrix class, also used for vectors and row-vectors.
EIGEN_DEVICE_FUNC bool isApprox(const Scalar &x, const Scalar &y, const typename NumTraits< Scalar >::Real &precision=NumTraits< Scalar >::dummy_precision())
EIGEN_DEVICE_FUNC MatrixType operatorSqrt() const
Computes the positive-definite square root of the matrix.
void selfadjointeigensolver_essential_check(const MatrixType &m)