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

#include <UpperHessenbergQR.h>

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

Public Member Functions

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
 
virtual void compute (ConstGenericMatrix &mat, const Scalar &shift=Scalar(0))
 
virtual void matrix_QtHQ (Matrix &dest) const
 
virtual Matrix matrix_R () const
 
 UpperHessenbergQR (Index size)
 
 UpperHessenbergQR (ConstGenericMatrix &mat, const Scalar &shift=Scalar(0))
 
virtual ~UpperHessenbergQR ()
 

Static Protected Member Functions

static void compute_rotation (const Scalar &x, const Scalar &y, Scalar &r, Scalar &c, Scalar &s)
 

Protected Attributes

bool m_computed
 
Index m_n
 
Array m_rot_cos
 
Array m_rot_sin
 
Scalar m_shift
 

Private Types

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

Private Attributes

Matrix m_mat_T
 

Detailed Description

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

Perform the QR decomposition of an upper Hessenberg matrix.

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

Definition at line 43 of file UpperHessenbergQR.h.

Member Typedef Documentation

template<typename Scalar = double>
typedef Eigen::Array<Scalar, Eigen::Dynamic, 1> Spectra::UpperHessenbergQR< Scalar >::Array
private

Definition at line 50 of file UpperHessenbergQR.h.

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

Definition at line 53 of file UpperHessenbergQR.h.

template<typename Scalar = double>
typedef Eigen::Ref<Matrix> Spectra::UpperHessenbergQR< Scalar >::GenericMatrix
private

Definition at line 52 of file UpperHessenbergQR.h.

template<typename Scalar = double>
typedef Eigen::Index Spectra::UpperHessenbergQR< Scalar >::Index
private

Definition at line 46 of file UpperHessenbergQR.h.

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

Definition at line 47 of file UpperHessenbergQR.h.

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

Definition at line 49 of file UpperHessenbergQR.h.

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

Definition at line 48 of file UpperHessenbergQR.h.

Constructor & Destructor Documentation

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

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

Definition at line 109 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Spectra::UpperHessenbergQR< Scalar >::UpperHessenbergQR ( 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 upper triangular and the lower subdiagonal parts of the matrix are used.

Definition at line 128 of file UpperHessenbergQR.h.

template<typename Scalar = double>
virtual Spectra::UpperHessenbergQR< Scalar >::~UpperHessenbergQR ( )
inlinevirtual

Virtual destructor.

Definition at line 141 of file UpperHessenbergQR.h.

Member Function Documentation

template<typename Scalar = double>
void Spectra::UpperHessenbergQR< Scalar >::apply_QtY ( Vector Y) const
inline

Apply the $Q$ matrix to a vector $y$.

Parameters
YA vector that will be overwritten by the matrix product $Q'y$.

Vector type can be Eigen::Vector<Scalar, ...>, depending on the template parameter Scalar defined.

Definition at line 309 of file UpperHessenbergQR.h.

template<typename Scalar = double>
void Spectra::UpperHessenbergQR< Scalar >::apply_QtY ( GenericMatrix  Y) const
inline

Apply the $Q$ matrix to another matrix $Y$.

Parameters
YA matrix that will be overwritten by the matrix product $Q'Y$.

Matrix type can be Eigen::Matrix<Scalar, ...> (e.g. Eigen::MatrixXd and Eigen::MatrixXf), or its mapped version (e.g. Eigen::Map<Eigen::MatrixXd>).

Definition at line 368 of file UpperHessenbergQR.h.

template<typename Scalar = double>
void Spectra::UpperHessenbergQR< Scalar >::apply_QY ( Vector Y) const
inline

Apply the $Q$ matrix to a vector $y$.

Parameters
YA vector that will be overwritten by the matrix product $Qy$.

Vector type can be Eigen::Vector<Scalar, ...>, depending on the template parameter Scalar defined.

Definition at line 282 of file UpperHessenbergQR.h.

template<typename Scalar = double>
void Spectra::UpperHessenbergQR< Scalar >::apply_QY ( GenericMatrix  Y) const
inline

Apply the $Q$ matrix to another matrix $Y$.

Parameters
YA matrix that will be overwritten by the matrix product $QY$.

Matrix type can be Eigen::Matrix<Scalar, ...> (e.g. Eigen::MatrixXd and Eigen::MatrixXf), or its mapped version (e.g. Eigen::Map<Eigen::MatrixXd>).

Definition at line 338 of file UpperHessenbergQR.h.

template<typename Scalar = double>
void Spectra::UpperHessenbergQR< Scalar >::apply_YQ ( GenericMatrix  Y) const
inline

Apply the $Q$ matrix to another matrix $Y$.

Parameters
YA matrix that will be overwritten by the matrix product $YQ$.

Matrix type can be Eigen::Matrix<Scalar, ...> (e.g. Eigen::MatrixXd and Eigen::MatrixXf), or its mapped version (e.g. Eigen::Map<Eigen::MatrixXd>).

Definition at line 399 of file UpperHessenbergQR.h.

template<typename Scalar = double>
void Spectra::UpperHessenbergQR< Scalar >::apply_YQt ( GenericMatrix  Y) const
inline

Apply the $Q$ matrix to another matrix $Y$.

Parameters
YA matrix that will be overwritten by the matrix product $YQ'$.

Matrix type can be Eigen::Matrix<Scalar, ...> (e.g. Eigen::MatrixXd and Eigen::MatrixXf), or its mapped version (e.g. Eigen::Map<Eigen::MatrixXd>).

Definition at line 445 of file UpperHessenbergQR.h.

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

Conduct the QR factorization of an upper Hessenberg 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 upper triangular and the lower subdiagonal parts of the matrix are used.

Reimplemented in Spectra::TridiagQR< Scalar >.

Definition at line 153 of file UpperHessenbergQR.h.

template<typename Scalar = double>
static void Spectra::UpperHessenbergQR< Scalar >::compute_rotation ( const Scalar x,
const Scalar y,
Scalar r,
Scalar c,
Scalar s 
)
inlinestaticprotected

Definition at line 70 of file UpperHessenbergQR.h.

template<typename Scalar = double>
virtual void Spectra::UpperHessenbergQR< 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 an upper Hessenberg matrix.

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

Reimplemented in Spectra::TridiagQR< Scalar >.

Definition at line 235 of file UpperHessenbergQR.h.

template<typename Scalar = double>
virtual Matrix Spectra::UpperHessenbergQR< 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 in Spectra::TridiagQR< Scalar >.

Definition at line 220 of file UpperHessenbergQR.h.

Member Data Documentation

template<typename Scalar = double>
bool Spectra::UpperHessenbergQR< Scalar >::m_computed
protected

Definition at line 65 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Matrix Spectra::UpperHessenbergQR< Scalar >::m_mat_T
private

Definition at line 55 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Index Spectra::UpperHessenbergQR< Scalar >::m_n
protected

Definition at line 58 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Array Spectra::UpperHessenbergQR< Scalar >::m_rot_cos
protected

Definition at line 63 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Array Spectra::UpperHessenbergQR< Scalar >::m_rot_sin
protected

Definition at line 64 of file UpperHessenbergQR.h.

template<typename Scalar = double>
Scalar Spectra::UpperHessenbergQR< Scalar >::m_shift
protected

Definition at line 62 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