#include <UpperHessenbergQR.h>
Public Member Functions | |
void | compute (ConstGenericMatrix &mat, const Scalar &shift=Scalar(0)) override |
void | matrix_QtHQ (ComplexMatrix &dest) const |
void | matrix_QtHQ (Matrix &dest) const override |
Matrix | matrix_R () const override |
TridiagQR (ConstGenericMatrix &mat, const Scalar &shift=Scalar(0)) | |
TridiagQR (Index size) | |
![]() | |
void | apply_QtY (GenericMatrix Y) const |
void | apply_QtY (Vector &Y) const |
void | apply_QY (GenericMatrix Y) const |
void | apply_QY (Vector &Y) const |
void | apply_YQ (GenericMatrix Y) const |
void | apply_YQt (GenericMatrix Y) const |
virtual void | compute (ConstGenericMatrix &mat, const double &shift=double(0)) |
virtual void | matrix_QtHQ (Matrix &dest) const |
virtual Matrix | matrix_R () const |
UpperHessenbergQR (ConstGenericMatrix &mat, const double &shift=double(0)) | |
UpperHessenbergQR (Index size) | |
virtual | ~UpperHessenbergQR () |
Private Types | |
using | ComplexMatrix = Eigen::Matrix< std::complex< Scalar >, Eigen::Dynamic, Eigen::Dynamic > |
using | ConstGenericMatrix = const Eigen::Ref< const Matrix > |
using | Index = Eigen::Index |
using | Matrix = Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > |
using | Vector = Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > |
Private Attributes | |
Vector | m_R_diag |
Vector | m_R_supd |
Vector | m_R_supd2 |
Vector | m_T_diag |
Vector | m_T_subd |
Additional Inherited Members | |
![]() | |
static void | compute_rotation (const double &x, const double &y, double &r, double &c, double &s) |
static void | stable_scaling (const double &a, const double &b, double &r, double &c, double &s) |
![]() | |
bool | m_computed |
Index | m_n |
Array | m_rot_cos |
Array | m_rot_sin |
double | m_shift |
Perform the QR decomposition of a tridiagonal matrix, a special case of upper Hessenberg matrices.
Scalar | The element type of the matrix. Currently supported types are float , double and long double . |
Definition at line 545 of file UpperHessenbergQR.h.
|
private |
Definition at line 552 of file UpperHessenbergQR.h.
|
private |
Definition at line 551 of file UpperHessenbergQR.h.
|
private |
Definition at line 548 of file UpperHessenbergQR.h.
|
private |
Definition at line 549 of file UpperHessenbergQR.h.
|
private |
Definition at line 550 of file UpperHessenbergQR.h.
|
inline |
Constructor to preallocate memory. Computation can be performed later by calling the compute() method.
Definition at line 571 of file UpperHessenbergQR.h.
|
inline |
Constructor to create an object that performs and stores the QR decomposition of a tridiagonal matrix mat
, with an optional shift: . Here
stands for the matrix
mat
, and is the shift.
mat | Matrix type can be Eigen::Matrix<Scalar, ...> (e.g. Eigen::MatrixXd and Eigen::MatrixXf ), or its mapped version (e.g. Eigen::Map<Eigen::MatrixXd> ). Only the diagonal and subdiagonal elements of the matrix are used. |
Definition at line 586 of file UpperHessenbergQR.h.
|
inlineoverride |
Compute the QR decomposition of a tridiagonal matrix with an optional shift.
mat | Matrix type can be Eigen::Matrix<Scalar, ...> (e.g. Eigen::MatrixXd and Eigen::MatrixXf ), or its mapped version (e.g. Eigen::Map<Eigen::MatrixXd> ). Only the diagonal and subdiagonal elements of the matrix are used. |
Definition at line 601 of file UpperHessenbergQR.h.
|
inline |
The version of matrix_QtHQ() when dest
has a complex value type.
This is used in Hermitian eigen solvers where the result is stored as a complex matrix.
Definition at line 787 of file UpperHessenbergQR.h.
|
inlineoverride |
Overwrite dest
with , where
is the input matrix
mat
, and is the shift. The result is a tridiagonal matrix.
mat | The matrix to be overwritten, whose type should be Eigen::Matrix<Scalar, ...> , depending on the template parameter Scalar defined. |
Definition at line 713 of file UpperHessenbergQR.h.
|
inlineoverride |
Return the matrix in the QR decomposition, which is an upper triangular matrix.
Eigen::Matrix<Scalar, ...>
, depending on the template parameter Scalar
defined. Definition at line 693 of file UpperHessenbergQR.h.
|
private |
Definition at line 562 of file UpperHessenbergQR.h.
|
private |
Definition at line 563 of file UpperHessenbergQR.h.
|
private |
Definition at line 564 of file UpperHessenbergQR.h.
|
private |
Definition at line 560 of file UpperHessenbergQR.h.
|
private |
Definition at line 561 of file UpperHessenbergQR.h.