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>

Public Member Functions

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

Static Protected Member Functions

static void compute_rotation (const Scalar &x, const Scalar &y, Scalar &r, Scalar &c, Scalar &s)
 
static void stable_scaling (const Scalar &a, const Scalar &b, 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

using Array = Eigen::Array< Scalar, Eigen::Dynamic, 1 >
 
using ConstGenericMatrix = const Eigen::Ref< const Matrix >
 
using GenericMatrix = Eigen::Ref< Matrix >
 
using Index = Eigen::Index
 
using Matrix = Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic >
 
using RowVector = Eigen::Matrix< Scalar, 1, Eigen::Dynamic >
 
using Vector = Eigen::Matrix< Scalar, Eigen::Dynamic, 1 >
 

Private Attributes

Matrix m_mat_R
 

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 45 of file UpperHessenbergQR.h.

Member Typedef Documentation

◆ Array

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

Definition at line 52 of file UpperHessenbergQR.h.

◆ ConstGenericMatrix

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

Definition at line 55 of file UpperHessenbergQR.h.

◆ GenericMatrix

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

Definition at line 54 of file UpperHessenbergQR.h.

◆ Index

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

Definition at line 48 of file UpperHessenbergQR.h.

◆ Matrix

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

Definition at line 49 of file UpperHessenbergQR.h.

◆ RowVector

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

Definition at line 51 of file UpperHessenbergQR.h.

◆ Vector

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

Definition at line 50 of file UpperHessenbergQR.h.

Constructor & Destructor Documentation

◆ UpperHessenbergQR() [1/2]

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 178 of file UpperHessenbergQR.h.

◆ UpperHessenbergQR() [2/2]

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 subdiagonal elements of the matrix are used.

Definition at line 198 of file UpperHessenbergQR.h.

◆ ~UpperHessenbergQR()

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

Virtual destructor.

Definition at line 211 of file UpperHessenbergQR.h.

Member Function Documentation

◆ apply_QtY() [1/2]

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 438 of file UpperHessenbergQR.h.

◆ apply_QtY() [2/2]

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 379 of file UpperHessenbergQR.h.

◆ apply_QY() [1/2]

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 408 of file UpperHessenbergQR.h.

◆ apply_QY() [2/2]

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 352 of file UpperHessenbergQR.h.

◆ apply_YQ()

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 469 of file UpperHessenbergQR.h.

◆ apply_YQt()

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 515 of file UpperHessenbergQR.h.

◆ compute()

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

Compute the QR decomposition 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 subdiagonal elements of the matrix are used.

Definition at line 223 of file UpperHessenbergQR.h.

◆ compute_rotation()

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 132 of file UpperHessenbergQR.h.

◆ matrix_QtHQ()

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.

Definition at line 305 of file UpperHessenbergQR.h.

◆ matrix_R()

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.

Definition at line 290 of file UpperHessenbergQR.h.

◆ stable_scaling()

template<typename Scalar = double>
static void Spectra::UpperHessenbergQR< Scalar >::stable_scaling ( const Scalar a,
const Scalar b,
Scalar r,
Scalar c,
Scalar s 
)
inlinestaticprotected

Definition at line 70 of file UpperHessenbergQR.h.

Member Data Documentation

◆ m_computed

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

Definition at line 67 of file UpperHessenbergQR.h.

◆ m_mat_R

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

Definition at line 57 of file UpperHessenbergQR.h.

◆ m_n

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

Definition at line 60 of file UpperHessenbergQR.h.

◆ m_rot_cos

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

Definition at line 65 of file UpperHessenbergQR.h.

◆ m_rot_sin

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

Definition at line 66 of file UpperHessenbergQR.h.

◆ m_shift

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

Definition at line 64 of file UpperHessenbergQR.h.


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


gtsam
Author(s):
autogenerated on Fri Mar 28 2025 03:16:39