Public Member Functions | Private Types | Private Attributes | List of all members
Spectra::TridiagQR< Scalar > Class Template Reference

#include <UpperHessenbergQR.h>

Inheritance diagram for Spectra::TridiagQR< Scalar >:
Inheritance graph
[legend]

Public Member Functions

void compute (ConstGenericMatrix &mat, const Scalar &shift=Scalar(0))
 
void matrix_QtHQ (Matrix &dest) const
 
Matrix matrix_R () const
 
 TridiagQR (Index size)
 
 TridiagQR (ConstGenericMatrix &mat, const Scalar &shift=Scalar(0))
 
- Public Member Functions inherited from Spectra::UpperHessenbergQR< Scalar >
void apply_QtY (Vector &Y) const
 
void apply_QtY (GenericMatrix Y) const
 
void apply_QY (Vector &Y) const
 
void apply_QY (GenericMatrix Y) const
 
void apply_YQ (GenericMatrix Y) const
 
void apply_YQt (GenericMatrix Y) const
 
 UpperHessenbergQR (Index size)
 
 UpperHessenbergQR (ConstGenericMatrix &mat, const Scalar &shift=Scalar(0))
 
virtual ~UpperHessenbergQR ()
 

Private Types

typedef const Eigen::Ref< const MatrixConstGenericMatrix
 
typedef Matrix::Index Index
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::DynamicMatrix
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
 

Private Attributes

Vector m_T_diag
 
Vector m_T_lsub
 
Vector m_T_usub
 
Vector m_T_usub2
 

Additional Inherited Members

- Static Protected Member Functions inherited from Spectra::UpperHessenbergQR< Scalar >
static void compute_rotation (const Scalar &x, const Scalar &y, Scalar &r, Scalar &c, Scalar &s)
 
- Protected Attributes inherited from Spectra::UpperHessenbergQR< Scalar >
bool m_computed
 
Index m_n
 
Array m_rot_cos
 
Array m_rot_sin
 
Scalar m_shift
 

Detailed Description

template<typename Scalar = double>
class Spectra::TridiagQR< Scalar >

Perform the QR decomposition of a tridiagonal matrix, a special case of upper Hessenberg matrices.

Template Parameters
ScalarThe element type of the matrix. Currently supported types are float, double and long double.

Definition at line 475 of file UpperHessenbergQR.h.

Member Typedef Documentation

template<typename Scalar = double>
typedef const Eigen::Ref<const Matrix> Spectra::TridiagQR< Scalar >::ConstGenericMatrix
private

Definition at line 480 of file UpperHessenbergQR.h.

template<typename Scalar = double>
typedef Matrix::Index Spectra::TridiagQR< Scalar >::Index
private

Definition at line 482 of file UpperHessenbergQR.h.

template<typename Scalar = double>
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> Spectra::TridiagQR< Scalar >::Matrix
private

Definition at line 478 of file UpperHessenbergQR.h.

template<typename Scalar = double>
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1> Spectra::TridiagQR< Scalar >::Vector
private

Definition at line 479 of file UpperHessenbergQR.h.

Constructor & Destructor Documentation

template<typename Scalar = double>
Spectra::TridiagQR< Scalar >::TridiagQR ( Index  size)
inline

Constructor to preallocate memory. Computation can be performed later by calling the compute() method.

Definition at line 494 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Spectra::TridiagQR< Scalar >::TridiagQR ( ConstGenericMatrix mat,
const Scalar shift = Scalar(0) 
)
inline

Constructor to create an object that performs and stores the QR decomposition of an upper Hessenberg matrix mat, with an optional shift: $H-sI=QR$. Here $H$ stands for the matrix mat, and $s$ is the shift.

Parameters
matMatrix 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 major- and sub- diagonal parts of the matrix are used.

Definition at line 510 of file UpperHessenbergQR.h.

Member Function Documentation

template<typename Scalar = double>
void Spectra::TridiagQR< Scalar >::compute ( ConstGenericMatrix mat,
const Scalar shift = Scalar(0) 
)
inlinevirtual

Conduct the QR factorization of a tridiagonal matrix with an optional shift.

Parameters
matMatrix 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 major- and sub- diagonal parts of the matrix are used.

Reimplemented from Spectra::UpperHessenbergQR< Scalar >.

Definition at line 526 of file UpperHessenbergQR.h.

template<typename Scalar = double>
void Spectra::TridiagQR< Scalar >::matrix_QtHQ ( Matrix dest) const
inlinevirtual

Overwrite dest with $Q'HQ = RQ + sI$, where $H$ is the input matrix mat, and $s$ is the shift. The result is a tridiagonal matrix.

Parameters
matThe matrix to be overwritten, whose type should be Eigen::Matrix<Scalar, ...>, depending on the template parameter Scalar defined.

Reimplemented from Spectra::UpperHessenbergQR< Scalar >.

Definition at line 623 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Matrix Spectra::TridiagQR< Scalar >::matrix_R ( ) const
inlinevirtual

Return the $R$ matrix in the QR decomposition, which is an upper triangular matrix.

Returns
Returned matrix type will be Eigen::Matrix<Scalar, ...>, depending on the template parameter Scalar defined.

Reimplemented from Spectra::UpperHessenbergQR< Scalar >.

Definition at line 603 of file UpperHessenbergQR.h.

Member Data Documentation

template<typename Scalar = double>
Vector Spectra::TridiagQR< Scalar >::m_T_diag
private

Definition at line 484 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Vector Spectra::TridiagQR< Scalar >::m_T_lsub
private

Definition at line 485 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Vector Spectra::TridiagQR< Scalar >::m_T_usub
private

Definition at line 486 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Vector Spectra::TridiagQR< Scalar >::m_T_usub2
private

Definition at line 487 of file UpperHessenbergQR.h.


The documentation for this class was generated from the following file:


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:59:21