Public Types | Public Member Functions | Protected Attributes | List of all members
pinocchio::LanczosDecompositionTpl< _Matrix > Struct Template Reference

Compute the largest eigenvalues and the associated principle eigenvector via power iteration. More...

#include <lanczos-decomposition.hpp>

Public Types

enum  { Options = _Matrix::Options }
 
typedef _Matrix::Scalar Scalar
 
typedef TridiagonalSymmetricMatrixTpl< Scalar, OptionsTridiagonalMatrix
 

Public Member Functions

template<typename MatrixLikeType >
void compute (const MatrixLikeType &A)
 Computes the Lanczos decomposition of the input matrix A. More...
 
template<typename MatrixLikeType >
PlainMatrix computeDecompositionResidual (const MatrixLikeType &A) const
 Computes the residual associated with the decomposition, namely, the quantity $ A Q_s - Q_s T_s $. More...
 
template<typename MatrixLikeType >
 LanczosDecompositionTpl (const MatrixLikeType &mat, const Eigen::DenseIndex decomposition_size)
 Default constructor for the Lanczos decomposition from an input matrix. More...
 
bool operator!= (const LanczosDecompositionTpl &other) const
 
bool operator== (const LanczosDecompositionTpl &other) const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef PINOCCHIO_EIGEN_PLAIN_TYPE (_Matrix) PlainMatrix
 
typedef PINOCCHIO_EIGEN_PLAIN_TYPE (typename PlainMatrix::ColXpr) Vector
 
PlainMatrix & Qs ()
 Returns the orthogonal basis associated with the Lanczos decomposition. More...
 
const PlainMatrix & Qs () const
 Returns the orthogonal basis associated with the Lanczos decomposition. More...
 
Eigen::DenseIndex rank () const
 Returns the rank of the decomposition. More...
 
TridiagonalMatrixTs ()
 Returns the tridiagonal matrix associated with the Lanczos decomposition. More...
 
const TridiagonalMatrixTs () const
 Returns the tridiagonal matrix associated with the Lanczos decomposition. More...
 

Protected Attributes

Vector m_A_times_q
 
PlainMatrix m_Qs
 
Eigen::DenseIndex m_rank
 
TridiagonalMatrix m_Ts
 

Detailed Description

template<typename _Matrix>
struct pinocchio::LanczosDecompositionTpl< _Matrix >

Compute the largest eigenvalues and the associated principle eigenvector via power iteration.

Definition at line 18 of file math/lanczos-decomposition.hpp.

Member Typedef Documentation

◆ Scalar

template<typename _Matrix >
typedef _Matrix::Scalar pinocchio::LanczosDecompositionTpl< _Matrix >::Scalar

Definition at line 24 of file math/lanczos-decomposition.hpp.

◆ TridiagonalMatrix

Definition at line 29 of file math/lanczos-decomposition.hpp.

Member Enumeration Documentation

◆ anonymous enum

template<typename _Matrix >
anonymous enum
Enumerator
Options 

Definition at line 25 of file math/lanczos-decomposition.hpp.

Constructor & Destructor Documentation

◆ LanczosDecompositionTpl()

template<typename _Matrix >
template<typename MatrixLikeType >
pinocchio::LanczosDecompositionTpl< _Matrix >::LanczosDecompositionTpl ( const MatrixLikeType &  mat,
const Eigen::DenseIndex  decomposition_size 
)
inline

Default constructor for the Lanczos decomposition from an input matrix.

Definition at line 33 of file math/lanczos-decomposition.hpp.

Member Function Documentation

◆ compute()

template<typename _Matrix >
template<typename MatrixLikeType >
void pinocchio::LanczosDecompositionTpl< _Matrix >::compute ( const MatrixLikeType &  A)
inline

Computes the Lanczos decomposition of the input matrix A.

Parameters
[in]AThe matrix to decompose

Definition at line 67 of file math/lanczos-decomposition.hpp.

◆ computeDecompositionResidual()

template<typename _Matrix >
template<typename MatrixLikeType >
PlainMatrix pinocchio::LanczosDecompositionTpl< _Matrix >::computeDecompositionResidual ( const MatrixLikeType &  A) const
inline

Computes the residual associated with the decomposition, namely, the quantity $ A Q_s - Q_s T_s $.

Parameters
[in]Athe matrix that have been decomposed.
Returns
The residual of the decomposition

Definition at line 123 of file math/lanczos-decomposition.hpp.

◆ operator!=()

template<typename _Matrix >
bool pinocchio::LanczosDecompositionTpl< _Matrix >::operator!= ( const LanczosDecompositionTpl< _Matrix > &  other) const
inline

Definition at line 56 of file math/lanczos-decomposition.hpp.

◆ operator==()

template<typename _Matrix >
bool pinocchio::LanczosDecompositionTpl< _Matrix >::operator== ( const LanczosDecompositionTpl< _Matrix > &  other) const
inline

Definition at line 49 of file math/lanczos-decomposition.hpp.

◆ PINOCCHIO_EIGEN_PLAIN_TYPE() [1/2]

template<typename _Matrix >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef pinocchio::LanczosDecompositionTpl< _Matrix >::PINOCCHIO_EIGEN_PLAIN_TYPE ( _Matrix  )

◆ PINOCCHIO_EIGEN_PLAIN_TYPE() [2/2]

template<typename _Matrix >
typedef pinocchio::LanczosDecompositionTpl< _Matrix >::PINOCCHIO_EIGEN_PLAIN_TYPE ( typename PlainMatrix::ColXpr  )

◆ Qs() [1/2]

template<typename _Matrix >
PlainMatrix& pinocchio::LanczosDecompositionTpl< _Matrix >::Qs ( )
inline

Returns the orthogonal basis associated with the Lanczos decomposition.

Definition at line 162 of file math/lanczos-decomposition.hpp.

◆ Qs() [2/2]

template<typename _Matrix >
const PlainMatrix& pinocchio::LanczosDecompositionTpl< _Matrix >::Qs ( ) const
inline

Returns the orthogonal basis associated with the Lanczos decomposition.

Definition at line 157 of file math/lanczos-decomposition.hpp.

◆ rank()

template<typename _Matrix >
Eigen::DenseIndex pinocchio::LanczosDecompositionTpl< _Matrix >::rank ( ) const
inline

Returns the rank of the decomposition.

Definition at line 168 of file math/lanczos-decomposition.hpp.

◆ Ts() [1/2]

template<typename _Matrix >
TridiagonalMatrix& pinocchio::LanczosDecompositionTpl< _Matrix >::Ts ( )
inline

Returns the tridiagonal matrix associated with the Lanczos decomposition.

Definition at line 151 of file math/lanczos-decomposition.hpp.

◆ Ts() [2/2]

template<typename _Matrix >
const TridiagonalMatrix& pinocchio::LanczosDecompositionTpl< _Matrix >::Ts ( ) const
inline

Returns the tridiagonal matrix associated with the Lanczos decomposition.

Definition at line 146 of file math/lanczos-decomposition.hpp.

Member Data Documentation

◆ m_A_times_q

template<typename _Matrix >
Vector pinocchio::LanczosDecompositionTpl< _Matrix >::m_A_times_q
mutableprotected

Definition at line 176 of file math/lanczos-decomposition.hpp.

◆ m_Qs

template<typename _Matrix >
PlainMatrix pinocchio::LanczosDecompositionTpl< _Matrix >::m_Qs
protected

Definition at line 174 of file math/lanczos-decomposition.hpp.

◆ m_rank

template<typename _Matrix >
Eigen::DenseIndex pinocchio::LanczosDecompositionTpl< _Matrix >::m_rank
protected

Definition at line 177 of file math/lanczos-decomposition.hpp.

◆ m_Ts

template<typename _Matrix >
TridiagonalMatrix pinocchio::LanczosDecompositionTpl< _Matrix >::m_Ts
protected

Definition at line 175 of file math/lanczos-decomposition.hpp.


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


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:52