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, Options > | TridiagonalMatrix |
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 . 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... | |
TridiagonalMatrix & | Ts () |
Returns the tridiagonal matrix associated with the Lanczos decomposition. More... | |
const TridiagonalMatrix & | Ts () 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 |
Compute the largest eigenvalues and the associated principle eigenvector via power iteration.
Definition at line 18 of file math/lanczos-decomposition.hpp.
typedef _Matrix::Scalar pinocchio::LanczosDecompositionTpl< _Matrix >::Scalar |
Definition at line 24 of file math/lanczos-decomposition.hpp.
typedef TridiagonalSymmetricMatrixTpl<Scalar, Options> pinocchio::LanczosDecompositionTpl< _Matrix >::TridiagonalMatrix |
Definition at line 29 of file math/lanczos-decomposition.hpp.
anonymous enum |
Enumerator | |
---|---|
Options |
Definition at line 25 of file math/lanczos-decomposition.hpp.
|
inline |
Default constructor for the Lanczos decomposition from an input matrix.
Definition at line 33 of file math/lanczos-decomposition.hpp.
|
inline |
Computes the Lanczos decomposition of the input matrix A.
[in] | A | The matrix to decompose |
Definition at line 67 of file math/lanczos-decomposition.hpp.
|
inline |
Computes the residual associated with the decomposition, namely, the quantity .
[in] | A | the matrix that have been decomposed. |
Definition at line 123 of file math/lanczos-decomposition.hpp.
|
inline |
Definition at line 56 of file math/lanczos-decomposition.hpp.
|
inline |
Definition at line 49 of file math/lanczos-decomposition.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef pinocchio::LanczosDecompositionTpl< _Matrix >::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | _Matrix | ) |
typedef pinocchio::LanczosDecompositionTpl< _Matrix >::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | typename PlainMatrix::ColXpr | ) |
|
inline |
Returns the orthogonal basis associated with the Lanczos decomposition.
Definition at line 162 of file math/lanczos-decomposition.hpp.
|
inline |
Returns the orthogonal basis associated with the Lanczos decomposition.
Definition at line 157 of file math/lanczos-decomposition.hpp.
|
inline |
Returns the rank of the decomposition.
Definition at line 168 of file math/lanczos-decomposition.hpp.
|
inline |
Returns the tridiagonal matrix associated with the Lanczos decomposition.
Definition at line 151 of file math/lanczos-decomposition.hpp.
|
inline |
Returns the tridiagonal matrix associated with the Lanczos decomposition.
Definition at line 146 of file math/lanczos-decomposition.hpp.
|
mutableprotected |
Definition at line 176 of file math/lanczos-decomposition.hpp.
|
protected |
Definition at line 174 of file math/lanczos-decomposition.hpp.
|
protected |
Definition at line 177 of file math/lanczos-decomposition.hpp.
|
protected |
Definition at line 175 of file math/lanczos-decomposition.hpp.