12 #ifndef EIGEN_COMPLEX_EIGEN_SOLVER_H 13 #define EIGEN_COMPLEX_EIGEN_SOLVER_H 125 template<
typename InputType>
212 template<
typename InputType>
258 template<
typename MatrixType>
259 template<
typename InputType>
275 if(computeEigenvectors)
286 template<
typename MatrixType>
295 m_matX = EigenvectorType::Zero(n, n);
296 for(
Index k=n-1 ; k>=0 ; k--)
319 for(
Index k=0 ; k<
n ; k++)
326 template<
typename MatrixType>
338 if(computeEigenvectors)
346 #endif // EIGEN_COMPLEX_EIGEN_SOLVER_H
EIGEN_DEVICE_FUNC internal::add_const_on_value_type< EIGEN_MATHFUNC_RETVAL(real_ref, Scalar) >::type real_ref(const Scalar &x)
static void check_template_parameters()
ComplexSchur< MatrixType > m_schur
ComplexSchur & setMaxIterations(Index maxIters)
Sets the maximum number of iterations allowed.
ComplexEigenSolver(Index size)
Default Constructor with memory preallocation.
ComplexEigenSolver & compute(const EigenBase< InputType > &matrix, bool computeEigenvectors=true)
Computes eigendecomposition of given matrix.
Matrix< ComplexScalar, ColsAtCompileTime, 1, Options &(~RowMajor), MaxColsAtCompileTime, 1 > EigenvalueType
Type for vector of eigenvalues as returned by eigenvalues().
EigenvalueType m_eivalues
Namespace containing all symbols from the Eigen library.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
MatrixType::Scalar Scalar
Scalar type for matrices of type MatrixType.
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T maxi(const T &x, const T &y)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void swap(DenseBase< OtherDerived > &other)
void doComputeEigenvectors(RealScalar matrixnorm)
ComplexSchur & compute(const EigenBase< InputType > &matrix, bool computeU=true)
Computes Schur decomposition of given matrix.
ComputationInfo info() const
Reports whether previous computation was successful.
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
const EigenvalueType & eigenvalues() const
Returns the eigenvalues of given matrix.
Matrix< ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime > EigenvectorType
Type for matrix of eigenvectors as returned by eigenvectors().
NumTraits< Scalar >::Real RealScalar
ComputationInfo info() const
Reports whether previous computation was successful.
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.
ComplexEigenSolver(const EigenBase< InputType > &matrix, bool computeEigenvectors=true)
Constructor; computes eigendecomposition of given matrix.
#define EIGEN_STATIC_ASSERT_NON_INTEGER(TYPE)
const EigenvectorType & eigenvectors() const
Returns the eigenvectors of given matrix.
Index getMaxIterations()
Returns the maximum number of iterations.
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
void swap(GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &a, GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &b)
_MatrixType MatrixType
Synonym for the template parameter _MatrixType.
ComplexEigenSolver()
Default constructor.
Index getMaxIterations()
Returns the maximum number of iterations.
ComplexEigenSolver & setMaxIterations(Index maxIters)
Sets the maximum number of iterations allowed.
const ComplexMatrixType & matrixU() const
Returns the unitary matrix in the Schur decomposition.
void sortEigenvalues(bool computeEigenvectors)
std::complex< RealScalar > ComplexScalar
Complex scalar type for MatrixType.
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Computes eigenvalues and eigenvectors of general complex matrices.
EIGEN_DEVICE_FUNC Derived & derived()
const ComplexMatrixType & matrixT() const
Returns the triangular matrix in the Schur decomposition.