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)
280 template<
typename MatrixType>
281 template<
typename HessMatrixType,
typename OrthMatrixType>
330 Vector3s firstHouseholderVector = Vector3s::Zero(), shiftInfo;
333 totalIter = totalIter + 1;
334 if (totalIter > maxIters)
break;
341 if(totalIter <= maxIters)
352 template<
typename MatrixType>
366 template<
typename MatrixType>
382 template<
typename MatrixType>
393 m_matT.coeffRef(iu,iu) += exshift;
394 m_matT.coeffRef(iu-1,iu-1) += exshift;
405 m_matT.rightCols(size-iu+1).applyOnTheLeft(iu-1, iu, rot.
adjoint());
406 m_matT.topRows(iu+1).applyOnTheRight(iu-1, iu, rot);
409 m_matU.applyOnTheRight(iu-1, iu, rot);
417 template<
typename MatrixType>
429 exshift += shiftInfo.
coeff(0);
442 s = s * s + shiftInfo.
coeff(2);
459 template<
typename MatrixType>
465 for (im = iu-2; im >= il; --im)
484 template<
typename MatrixType>
492 for (
Index k = im; k <= iu-2; ++k)
494 bool firstIteration = (k == im);
498 v = firstHouseholderVector;
500 v =
m_matT.template block<3,1>(k,k-1);
504 v.makeHouseholder(ess, tau, beta);
508 if (firstIteration && k > il)
510 else if (!firstIteration)
511 m_matT.coeffRef(k,k-1) = beta;
514 m_matT.block(k, k, 3, size-k).applyHouseholderOnTheLeft(ess, tau, workspace);
515 m_matT.block(0, k, (
std::min)(iu,k+3) + 1, 3).applyHouseholderOnTheRight(ess, tau, workspace);
517 m_matU.block(0, k, size, 3).applyHouseholderOnTheRight(ess, tau, workspace);
524 v.makeHouseholder(ess, tau, beta);
528 m_matT.coeffRef(iu-1, iu-2) = beta;
529 m_matT.block(iu-1, iu-1, 2, size-iu+1).applyHouseholderOnTheLeft(ess, tau, workspace);
530 m_matT.block(0, iu-1, iu+1, 2).applyHouseholderOnTheRight(ess, tau, workspace);
532 m_matU.block(0, iu-1, size, 2).applyHouseholderOnTheRight(ess, tau, workspace);
546 #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
HouseholderSequenceType matrixQ() const
Reconstructs the orthogonal matrix Q in the decomposition.
MatrixHReturnType matrixH() const
Constructs the Hessenberg matrix H in the decomposition.
Index findSmallSubdiagEntry(Index iu)
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.
const MatrixType & matrixU() const
Returns the orthogonal matrix in the Schur decomposition.
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
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. ...
ComputationInfo info() const
Reports whether previous computation was successful.
const MatrixType & matrixT() const
Returns the quasi-triangular matrix in the Schur decomposition.
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)
MatrixType::Scalar Scalar
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.
JacobiRotation adjoint() const
EIGEN_DEVICE_FUNC const Scalar & q
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 Index cols() const
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
RealSchur(Index size=RowsAtCompileTime==Dynamic?1:RowsAtCompileTime)
Default constructor.
RealSchur & setMaxIterations(Index maxIters)
Sets the maximum number of iterations allowed.
EIGEN_DEVICE_FUNC Index rows() const
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)
std::complex< typename NumTraits< Scalar >::Real > ComplexScalar
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 Derived & derived()
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar & coeff(Index rowId, Index colId) const
void makeGivens(const Scalar &p, const Scalar &q, Scalar *r=0)