13 #include <Eigen/Eigenvalues> 15 template<
typename EigType,
typename MatType>
20 typedef typename std::complex<RealScalar>
Complex;
23 VERIFY_IS_APPROX(a * eig.pseudoEigenvectors(), eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix());
25 eig.eigenvectors() * eig.eigenvalues().asDiagonal());
26 VERIFY_IS_APPROX(eig.eigenvectors().colwise().norm(), RealVectorType::Ones(n).transpose());
40 typedef typename std::complex<RealScalar>
Complex;
71 MatrixType id = MatrixType::Identity(rows, cols);
74 if (rows > 2 && rows < 20)
77 a(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();
85 eig.compute(a.adjoint() *
a);
106 MatrixType a = MatrixType::Random(m.rows(),m.cols());
113 template<
typename CoeffType>
117 Index n = coeffs.size()-1;
120 res.row(0) = -coeffs.tail(n) / coeffs(0);
135 double scale = 1e-200;
155 VectorXd coeffs(5); coeffs << 1, -3, -175, -225, 2250;
162 VectorXd coeffs(5); coeffs << 6.154671e-15, -1.003870e-10, -9.819570e-01, 3.995715e+03, 2.211511e+08;
169 typedef std::complex<double>
Complex;
170 MatrixXcd ac = C.cast<Complex>();
172 VectorXd sv = ac.jacobiSvd().singularValues();
182 MatrixXd A_bug1557(3,3);
183 A_bug1557 << 0, 0, 0, 1, 0, 0.5887907064808635127, 0, 1, 0;
191 MatrixXf A_bug1174(n,n);
192 A_bug1174 << 262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,
193 262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,
194 262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,
195 262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,
196 0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,
197 0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,
198 0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,
199 0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,
200 0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,
201 0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,
202 0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,
203 0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0;
MatrixType pseudoEigenvalueMatrix() const
Returns the block-diagonal matrix in the pseudo-eigendecomposition.
#define VERIFY_RAISES_ASSERT(a)
const MatrixType & pseudoEigenvectors() const
Returns the pseudo-eigenvectors of given matrix.
#define CALL_SUBTEST_4(FUNC)
EIGEN_DEVICE_FUNC Matrix< _Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setZero(Index size)
EigenSolver & compute(const EigenBase< InputType > &matrix, bool computeEigenvectors=true)
Computes eigendecomposition of given matrix.
#define VERIFY_IS_NOT_EQUAL(a, b)
void eigensolver_verify_assert(const MatrixType &m)
Performs a real Schur decomposition of a square matrix.
#define CALL_SUBTEST_3(FUNC)
BiCGSTAB< SparseMatrix< double > > solver
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
Index getMaxIterations()
Returns the maximum number of iterations.
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
EIGEN_DEVICE_FUNC Matrix< _Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setOnes(Index size)
std::complex< RealScalar > Complex
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
#define VERIFY_IS_APPROX(a, b)
#define VERIFY_IS_EQUAL(a, b)
#define CALL_SUBTEST_1(FUNC)
ComputationInfo info() const
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
EIGEN_DECLARE_TEST(eigensolver_generic)
SelfAdjointEigenSolver< PlainMatrixType > eig(mat, computeVectors?ComputeEigenvectors:EigenvaluesOnly)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EigenSolver & setMaxIterations(Index maxIters)
Sets the maximum number of iterations allowed.
NumTraits< Scalar >::Real RealScalar
#define VERIFY_IS_MUCH_SMALLER_THAN(a, b)
Matrix< Scalar, Dynamic, Dynamic > C
EigenvectorsType eigenvectors() const
Returns the eigenvectors of given matrix.
#define TEST_SET_BUT_UNUSED_VARIABLE(X)
#define CALL_SUBTEST_5(FUNC)
#define CALL_SUBTEST(FUNC)
Matrix< typename CoeffType::Scalar, Dynamic, Dynamic > make_companion(const CoeffType &coeffs)
#define EIGEN_TEST_MAX_SIZE
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
#define CALL_SUBTEST_2(FUNC)
internal::nested_eval< T, 1 >::type eval(const T &xpr)
Jet< T, N > sqrt(const Jet< T, N > &f)
const EigenvalueType & eigenvalues() const
Returns the eigenvalues of given matrix.
Computes eigenvalues and eigenvectors of general matrices.
The matrix class, also used for vectors and row-vectors.
void check_eigensolver_for_given_mat(const EigType &eig, const MatType &a)
void eigensolver(const MatrixType &m)
void eigensolver_generic_extra()