11 #ifndef EIGEN_REAL_SCHUR_H 12 #define EIGEN_REAL_SCHUR_H 103 template<
typename InputType>
169 template<
typename InputType>
189 template<
typename HessMatrixType,
typename OrthMatrixType>
241 void computeShift(Index iu, Index
iter, Scalar& exshift, Vector3s& shiftInfo);
242 void initFrancisQRStep(Index il, Index iu,
const Vector3s& shiftInfo, Index& im, Vector3s& firstHouseholderVector);
243 void performFrancisQRStep(Index il, Index im, Index iu,
bool computeU,
const Vector3s& firstHouseholderVector, Scalar* workspace);
247 template<
typename MatrixType>
248 template<
typename InputType>
259 if(scale<considerAsZero)
285 template<
typename MatrixType>
286 template<
typename HessMatrixType,
typename OrthMatrixType>
339 Vector3s firstHouseholderVector = Vector3s::Zero(), shiftInfo;
342 totalIter = totalIter + 1;
343 if (totalIter > maxIters)
break;
350 if(totalIter <= maxIters)
361 template<
typename MatrixType>
375 template<
typename MatrixType>
394 template<
typename MatrixType>
405 m_matT.coeffRef(iu,iu) += exshift;
406 m_matT.coeffRef(iu-1,iu-1) += exshift;
417 m_matT.rightCols(size-iu+1).applyOnTheLeft(iu-1, iu, rot.
adjoint());
418 m_matT.topRows(iu+1).applyOnTheRight(iu-1, iu, rot);
421 m_matU.applyOnTheRight(iu-1, iu, rot);
429 template<
typename MatrixType>
441 exshift += shiftInfo.
coeff(0);
454 s = s * s + shiftInfo.
coeff(2);
471 template<
typename MatrixType>
477 for (im = iu-2; im >= il; --im)
496 template<
typename MatrixType>
504 for (
Index k = im; k <= iu-2; ++k)
506 bool firstIteration = (k == im);
510 v = firstHouseholderVector;
512 v =
m_matT.template block<3,1>(k,k-1);
516 v.makeHouseholder(ess, tau, beta);
520 if (firstIteration && k > il)
522 else if (!firstIteration)
523 m_matT.coeffRef(k,k-1) = beta;
526 m_matT.block(k, k, 3, size-k).applyHouseholderOnTheLeft(ess, tau, workspace);
527 m_matT.block(0, k, (
std::min)(iu,k+3) + 1, 3).applyHouseholderOnTheRight(ess, tau, workspace);
529 m_matU.block(0, k, size, 3).applyHouseholderOnTheRight(ess, tau, workspace);
536 v.makeHouseholder(ess, tau, beta);
540 m_matT.coeffRef(iu-1, iu-2) = beta;
541 m_matT.block(iu-1, iu-1, 2, size-iu+1).applyHouseholderOnTheLeft(ess, tau, workspace);
542 m_matT.block(0, iu-1, iu+1, 2).applyHouseholderOnTheRight(ess, tau, workspace);
544 m_matU.block(0, iu-1, size, 2).applyHouseholderOnTheRight(ess, tau, workspace);
558 #endif // EIGEN_REAL_SCHUR_H
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
internal::traits< Derived >::Scalar Scalar
Performs a real Schur decomposition of a square matrix.
RealSchur & computeFromHessenberg(const HessMatrixType &matrixH, const OrthMatrixType &matrixQ, bool computeU)
Computes Schur decomposition of a Hessenberg matrix H = Z T Z^T.
Namespace containing all symbols from the Eigen library.
Rotation given by a cosine-sine pair.
iterator iter(handle obj)
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
RealSchur(Index size=RowsAtCompileTime==Dynamic ? 1 :RowsAtCompileTime)
Default constructor.
void computeShift(Index iu, Index iter, Scalar &exshift, Vector3s &shiftInfo)
Index getMaxIterations()
Returns the maximum number of iterations.
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
HessenbergDecomposition< MatrixType > m_hess
HessenbergDecomposition & compute(const EigenBase< InputType > &matrix)
Computes Hessenberg decomposition of given matrix.
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
MatrixHReturnType matrixH() const
Constructs the Hessenberg matrix H in the decomposition.
EIGEN_DEVICE_FUNC void makeGivens(const Scalar &p, const Scalar &q, Scalar *r=0)
MatrixType::Scalar Scalar
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar & coeff(Index rowId, Index colId) const
Matrix< ComplexScalar, ColsAtCompileTime, 1, Options &~RowMajor, MaxColsAtCompileTime, 1 > EigenvalueType
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
static const int m_maxIterationsPerRow
Maximum number of iterations per row.
Array< int, Dynamic, 1 > v
EIGEN_DEVICE_FUNC const Scalar & q
EIGEN_DEVICE_FUNC bool is_same_dense(const T1 &mat1, const T2 &mat2, typename enable_if< possibly_same_dense< T1, T2 >::value >::type *=0)
EIGEN_DEVICE_FUNC Derived & setConstant(Index size, const Scalar &val)
void performFrancisQRStep(Index il, Index im, Index iu, bool computeU, const Vector3s &firstHouseholderVector, Scalar *workspace)
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
EIGEN_DEVICE_FUNC JacobiRotation adjoint() const
const MatrixType & matrixT() const
Returns the quasi-triangular matrix in the Schur decomposition.
Matrix< Scalar, ColsAtCompileTime, 1, Options &~RowMajor, MaxColsAtCompileTime, 1 > ColumnVectorType
Matrix< Scalar, 3, 1 > Vector3s
mp::number< mp::cpp_dec_float< 100 >, mp::et_on > Real
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 void evalTo(DestType &dst) const
Index findSmallSubdiagEntry(Index iu, const Scalar &considerAsZero)
HouseholderSequenceType matrixQ() const
Reconstructs the orthogonal matrix Q in the decomposition.
void initFrancisQRStep(Index il, Index iu, const Vector3s &shiftInfo, Index &im, Vector3s &firstHouseholderVector)
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
void splitOffTwoRows(Index iu, bool computeU, const Scalar &exshift)
Jet< T, N > sqrt(const Jet< T, N > &f)
std::complex< typename NumTraits< Scalar >::Real > ComplexScalar
ComputationInfo info() const
Reports whether previous computation was successful.
ColumnVectorType m_workspaceVector
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
RealSchur(const EigenBase< InputType > &matrix, bool computeU=true)
Constructor; computes real Schur decomposition of given matrix.
EIGEN_DEVICE_FUNC bool abs2(bool x)
EIGEN_DEVICE_FUNC Derived & derived()