11 #ifndef EIGEN_EIGENSOLVER_H 12 #define EIGEN_EIGENSOLVER_H 146 template<
typename InputType>
277 template<
typename InputType>
323 template<
typename MatrixType>
344 template<
typename MatrixType>
357 matV.col(
j) =
m_eivec.col(
j).template cast<ComplexScalar>();
358 matV.col(
j).normalize();
368 matV.col(
j).normalize();
369 matV.col(
j+1).normalize();
376 template<
typename MatrixType>
377 template<
typename InputType>
396 if (computeEigenvectors)
402 while (i < matrix.
cols())
425 Scalar maxval = numext::maxi<Scalar>(
abs(p),numext::maxi<Scalar>(
abs(t0),
abs(t1)));
429 z = maxval *
sqrt(
abs(p0 * p0 + t0 * t1));
446 if (computeEigenvectors)
457 template<
typename MatrixType>
485 Scalar lastr(0), lastw(0);
507 m_matT.coeffRef(
i,
n) = -r / (eps * norm);
514 Scalar t = (x * lastr - lastw * r) / denom;
517 m_matT.coeffRef(
i+1,
n) = (-r - w *
t) / x;
519 m_matT.coeffRef(
i+1,
n) = (-lastr - y *
t) / lastw;
524 if ((eps * t) * t >
Scalar(1))
529 else if (q <
Scalar(0) &&
n > 0)
531 Scalar lastra(0), lastsa(0), lastw(0);
597 if ((eps * t) * t >
Scalar(1))
608 eigen_assert(0 &&
"Internal bug in EigenSolver (INF or NaN has not been detected)");
622 #endif // EIGEN_EIGENSOLVER_H
MatrixType pseudoEigenvalueMatrix() const
Returns the block-diagonal matrix in the pseudo-eigendecomposition.
const MatrixType & pseudoEigenvectors() const
Returns the pseudo-eigenvectors of given matrix.
Matrix< ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime > EigenvectorsType
Type for matrix of eigenvectors as returned by eigenvectors().
EIGEN_DEVICE_FUNC bool isMuchSmallerThan(const Scalar &x, const OtherScalar &y, const typename NumTraits< Scalar >::Real &precision=NumTraits< Scalar >::dummy_precision())
EigenSolver & compute(const EigenBase< InputType > &matrix, bool computeEigenvectors=true)
Computes eigendecomposition of given matrix.
EigenSolver(Index size)
Default constructor with memory preallocation.
Namespace containing all symbols from the Eigen library.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
Index getMaxIterations()
Returns the maximum number of iterations.
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
RealSchur< MatrixType > m_realSchur
Index getMaxIterations()
Returns the maximum number of iterations.
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
EigenSolver(const EigenBase< InputType > &matrix, bool computeEigenvectors=true)
Constructor; computes eigendecomposition of given matrix.
Matrix< Scalar, ColsAtCompileTime, 1, Options &~RowMajor, MaxColsAtCompileTime, 1 > ColumnVectorType
static const Line3 l(Rot3(), 1, 1)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
NumTraits< Scalar >::Real RealScalar
ComputationInfo info() const
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar & coeff(Index rowId, Index colId) const
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool() isfinite(const Eigen::bfloat16 &h)
#define EIGEN_STATIC_ASSERT_NON_INTEGER(TYPE)
EIGEN_DEVICE_FUNC const Scalar & q
RealSchur & compute(const EigenBase< InputType > &matrix, bool computeU=true)
Computes Schur decomposition of given matrix.
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
EigenSolver & setMaxIterations(Index maxIters)
Sets the maximum number of iterations allowed.
std::complex< RealScalar > ComplexScalar
Complex scalar type for MatrixType.
const MatrixType & matrixT() const
Returns the quasi-triangular matrix in the Schur decomposition.
_MatrixType MatrixType
Synonym for the template parameter _MatrixType.
EigenvectorsType eigenvectors() const
Returns the eigenvectors of given matrix.
EigenSolver()
Default constructor.
const MatrixType & matrixU() const
Returns the orthogonal matrix in the Schur decomposition.
RealSchur & setMaxIterations(Index maxIters)
Sets the maximum number of iterations allowed.
EIGEN_DEVICE_FUNC const ImagReturnType imag() const
void doComputeEigenvectors()
MatrixType::Scalar Scalar
Scalar type for matrices of type MatrixType.
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.
ComputationInfo info() const
Reports whether previous computation was successful.
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
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
EigenvalueType m_eivalues
EIGEN_DEVICE_FUNC Derived & derived()
Matrix< ComplexScalar, ColsAtCompileTime, 1, Options &~RowMajor, MaxColsAtCompileTime, 1 > EigenvalueType
Type for vector of eigenvalues as returned by eigenvalues().
static void check_template_parameters()