13 #include <Eigen/Eigenvalues> 18 bool match = diffs.diagonal().sum() <=
tol;
19 if(match ||
col==diffs.cols())
26 std::vector<std::pair<Index,Index> > transpositions;
30 if(diffs.col(
col).segment(
col,n-
i).minCoeff(&best_index) >
tol)
35 diffs.row(
col).swap(diffs.row(best_index));
37 diffs.row(
col).swap(diffs.row(best_index));
40 diffs.row(n-(
i-
col)-1).swap(diffs.row(best_index));
41 transpositions.push_back(std::pair<Index,Index>(n-(
i-
col)-1,best_index));
44 for(
Index k=transpositions.size()-1; k>=0; --k)
45 diffs.row(transpositions[k].first).swap(diffs.row(transpositions[k].second));
54 template<
typename VectorType>
62 VERIFY(vec1.rows() == vec2.rows());
65 RealScalar
tol = test_precision<RealScalar>()*test_precision<RealScalar>()*
numext::maxi(vec1.squaredNorm(),vec2.squaredNorm());
92 VERIFY_IS_APPROX(a * ei1.eigenvectors(), ei1.eigenvectors() * ei1.eigenvalues().asDiagonal());
103 ei2.setMaxIterations(1).compute(a);
117 MatrixType id = MatrixType::Identity(rows, cols);
120 if (rows > 1 && rows < 20)
123 a(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();
131 eig.compute(a.adjoint() *
a);
150 MatrixType a = MatrixType::Random(m.rows(),m.cols());
#define VERIFY_RAISES_ASSERT(a)
bool match(const T &xpr, std::string ref, std::string str_xpr="")
#define CALL_SUBTEST_4(FUNC)
static const Eigen::internal::all_t all
#define CALL_SUBTEST_3(FUNC)
ComplexEigenSolver & compute(const EigenBase< InputType > &matrix, bool computeEigenvectors=true)
Computes eigendecomposition of given matrix.
void verify_is_approx_upto_permutation(const VectorType &vec1, const VectorType &vec2)
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T maxi(const T &x, const T &y)
void eigensolver(const MatrixType &m)
const EigenvalueType & eigenvalues() const
Returns the eigenvalues of given matrix.
#define VERIFY_IS_APPROX(a, b)
#define VERIFY_IS_EQUAL(a, b)
#define CALL_SUBTEST_1(FUNC)
ComputationInfo info() const
Reports whether previous computation was successful.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
bool find_pivot(typename MatrixType::Scalar tol, MatrixType &diffs, Index col=0)
SelfAdjointEigenSolver< PlainMatrixType > eig(mat, computeVectors?ComputeEigenvectors:EigenvaluesOnly)
const EigenvectorType & eigenvectors() const
Returns the eigenvectors of given matrix.
NumTraits< Scalar >::Real RealScalar
void eigensolver_verify_assert(const MatrixType &m)
#define VERIFY_IS_MUCH_SMALLER_THAN(a, b)
#define TEST_SET_BUT_UNUSED_VARIABLE(X)
#define CALL_SUBTEST_5(FUNC)
EIGEN_DECLARE_TEST(eigensolver_complex)
#define EIGEN_TEST_MAX_SIZE
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseAbs2ReturnType cwiseAbs2() const
ComplexEigenSolver & setMaxIterations(Index maxIters)
Sets the maximum number of iterations allowed.
#define CALL_SUBTEST_2(FUNC)
internal::nested_eval< T, 1 >::type eval(const T &xpr)
The matrix class, also used for vectors and row-vectors.
Performs a complex Schur decomposition of a real or complex square matrix.
Computes eigenvalues and eigenvectors of general complex matrices.