Public Types | Public Member Functions | Public Attributes | Protected Attributes | Private Types | Private Member Functions | Static Private Member Functions | List of all members
Eigen::BDCSVD< _MatrixType > Class Template Reference

class Bidiagonal Divide and Conquer SVD More...

#include <ForwardDeclarations.h>

Inheritance diagram for Eigen::BDCSVD< _MatrixType >:
Inheritance graph
[legend]

Public Types

enum  {
  RowsAtCompileTime = MatrixType::RowsAtCompileTime, ColsAtCompileTime = MatrixType::ColsAtCompileTime, DiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_DYNAMIC(RowsAtCompileTime, ColsAtCompileTime), MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,
  MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, MaxDiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(MaxRowsAtCompileTime, MaxColsAtCompileTime), MatrixOptions = MatrixType::Options
}
 
typedef Ref< ArrayXrArrayRef
 
typedef Array< Index, 1, DynamicArrayXi
 
typedef Array< RealScalar, Dynamic, 1 > ArrayXr
 
typedef Ref< ArrayXiIndicesRef
 
typedef NumTraits< RealScalar >::Literal Literal
 
typedef _MatrixType MatrixType
 
typedef Base::MatrixUType MatrixUType
 
typedef Base::MatrixVType MatrixVType
 
typedef Matrix< Scalar, Dynamic, Dynamic, ColMajorMatrixX
 
typedef Matrix< RealScalar, Dynamic, Dynamic, ColMajorMatrixXr
 
typedef NumTraits< typename MatrixType::Scalar >::Real RealScalar
 
typedef MatrixType::Scalar Scalar
 
typedef Base::SingularValuesType SingularValuesType
 
typedef Matrix< RealScalar, Dynamic, 1 > VectorType
 
- Public Types inherited from Eigen::SVDBase< BDCSVD< _MatrixType > >
enum  
 
typedef Eigen::Index Index
 
typedef internal::traits< BDCSVD< _MatrixType > >::MatrixType MatrixType
 
typedef Matrix< Scalar, RowsAtCompileTime, RowsAtCompileTime, MatrixOptions, MaxRowsAtCompileTime, MaxRowsAtCompileTimeMatrixUType
 
typedef Matrix< Scalar, ColsAtCompileTime, ColsAtCompileTime, MatrixOptions, MaxColsAtCompileTime, MaxColsAtCompileTimeMatrixVType
 
typedef NumTraits< typename MatrixType::Scalar >::Real RealScalar
 
typedef MatrixType::Scalar Scalar
 
typedef internal::plain_diag_type< MatrixType, RealScalar >::type SingularValuesType
 
typedef Eigen::internal::traits< SVDBase >::StorageIndex StorageIndex
 
- Public Types inherited from Eigen::SolverBase< SVDBase< BDCSVD< _MatrixType > > >
enum  
 
typedef internal::conditional< NumTraits< Scalar >::IsComplex, CwiseUnaryOp< internal::scalar_conjugate_op< Scalar >, ConstTransposeReturnType >, ConstTransposeReturnType >::type AdjointReturnType
 
typedef EigenBase< SVDBase< BDCSVD< _MatrixType > > > Base
 
typedef Scalar CoeffReturnType
 
typedef internal::add_const< Transpose< const SVDBase< BDCSVD< _MatrixType > > > >::type ConstTransposeReturnType
 
typedef internal::traits< SVDBase< BDCSVD< _MatrixType > > >::Scalar Scalar
 
- Public Types inherited from Eigen::EigenBase< Derived >
typedef Eigen::Index Index
 The interface type of indices. More...
 
typedef internal::traits< Derived >::StorageKind StorageKind
 

Public Member Functions

 BDCSVD ()
 Default Constructor. More...
 
 BDCSVD (Index rows, Index cols, unsigned int computationOptions=0)
 Default Constructor with memory preallocation. More...
 
 BDCSVD (const MatrixType &matrix, unsigned int computationOptions=0)
 Constructor performing the decomposition of given matrix. More...
 
BDCSVDcompute (const MatrixType &matrix, unsigned int computationOptions)
 Method performing the decomposition of given matrix using custom options. More...
 
BDCSVDcompute (const MatrixType &matrix)
 Method performing the decomposition of given matrix using current options. More...
 
void setSwitchSize (int s)
 
 ~BDCSVD ()
 
- Public Member Functions inherited from Eigen::SVDBase< BDCSVD< _MatrixType > >
void _solve_impl (const RhsType &rhs, DstType &dst) const
 
void _solve_impl_transposed (const RhsType &rhs, DstType &dst) const
 
Index cols () const
 
bool computeU () const
 
bool computeV () const
 
BDCSVD< _MatrixType > & derived ()
 
const BDCSVD< _MatrixType > & derived () const
 
EIGEN_DEVICE_FUNC ComputationInfo info () const
 Reports whether previous computation was successful. More...
 
const MatrixUTypematrixU () const
 
const MatrixVTypematrixV () const
 
Index nonzeroSingularValues () const
 
Index rank () const
 
Index rows () const
 
BDCSVD< _MatrixType > & setThreshold (const RealScalar &threshold)
 
BDCSVD< _MatrixType > & setThreshold (Default_t)
 
const SingularValuesTypesingularValues () const
 
RealScalar threshold () const
 
- Public Member Functions inherited from Eigen::SolverBase< SVDBase< BDCSVD< _MatrixType > > >
AdjointReturnType adjoint () const
 
const Solve< SVDBase< BDCSVD< _MatrixType > >, Rhs > solve (const MatrixBase< Rhs > &b) const
 
 SolverBase ()
 
ConstTransposeReturnType transpose () const
 
 ~SolverBase ()
 
- Public Member Functions inherited from Eigen::EigenBase< Derived >
template<typename Dest >
EIGEN_DEVICE_FUNC void addTo (Dest &dst) const
 
template<typename Dest >
EIGEN_DEVICE_FUNC void applyThisOnTheLeft (Dest &dst) const
 
template<typename Dest >
EIGEN_DEVICE_FUNC void applyThisOnTheRight (Dest &dst) const
 
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols () const EIGEN_NOEXCEPT
 
EIGEN_DEVICE_FUNC Derived & const_cast_derived () const
 
EIGEN_DEVICE_FUNC const Derived & const_derived () const
 
EIGEN_DEVICE_FUNC Derived & derived ()
 
EIGEN_DEVICE_FUNC const Derived & derived () const
 
template<typename Dest >
EIGEN_DEVICE_FUNC void evalTo (Dest &dst) const
 
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows () const EIGEN_NOEXCEPT
 
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index size () const EIGEN_NOEXCEPT
 
template<typename Dest >
EIGEN_DEVICE_FUNC void subTo (Dest &dst) const
 

Public Attributes

int m_numIters
 

Protected Attributes

int m_algoswap
 
bool m_compU
 
MatrixXr m_computed
 
bool m_compV
 
bool m_isTranspose
 
MatrixXr m_naiveU
 
MatrixXr m_naiveV
 
Index m_nRec
 
ArrayXr m_workspace
 
ArrayXi m_workspaceI
 
- Protected Attributes inherited from Eigen::SVDBase< BDCSVD< _MatrixType > >
Index m_cols
 
unsigned int m_computationOptions
 
bool m_computeFullU
 
bool m_computeFullV
 
bool m_computeThinU
 
bool m_computeThinV
 
Index m_diagSize
 
ComputationInfo m_info
 
bool m_isAllocated
 
bool m_isInitialized
 
MatrixUType m_matrixU
 
MatrixVType m_matrixV
 
Index m_nonzeroSingularValues
 
RealScalar m_prescribedThreshold
 
Index m_rows
 
SingularValuesType m_singularValues
 
bool m_usePrescribedThreshold
 

Private Types

typedef SVDBase< BDCSVDBase
 

Private Member Functions

void allocate (Index rows, Index cols, unsigned int computationOptions)
 
void computeSingVals (const ArrayRef &col0, const ArrayRef &diag, const IndicesRef &perm, VectorType &singVals, ArrayRef shifts, ArrayRef mus)
 
void computeSingVecs (const ArrayRef &zhat, const ArrayRef &diag, const IndicesRef &perm, const VectorType &singVals, const ArrayRef &shifts, const ArrayRef &mus, MatrixXr &U, MatrixXr &V)
 
void computeSVDofM (Index firstCol, Index n, MatrixXr &U, VectorType &singVals, MatrixXr &V)
 
template<typename HouseholderU , typename HouseholderV , typename NaiveU , typename NaiveV >
void copyUV (const HouseholderU &householderU, const HouseholderV &householderV, const NaiveU &naiveU, const NaiveV &naivev)
 
void deflation (Index firstCol, Index lastCol, Index k, Index firstRowW, Index firstColW, Index shift)
 
void deflation43 (Index firstCol, Index shift, Index i, Index size)
 
void deflation44 (Index firstColu, Index firstColm, Index firstRowW, Index firstColW, Index i, Index j, Index size)
 
void divide (Index firstCol, Index lastCol, Index firstRowW, Index firstColW, Index shift)
 
void perturbCol0 (const ArrayRef &col0, const ArrayRef &diag, const IndicesRef &perm, const VectorType &singVals, const ArrayRef &shifts, const ArrayRef &mus, ArrayRef zhat)
 
void structured_update (Block< MatrixXr, Dynamic, Dynamic > A, const MatrixXr &B, Index n1)
 

Static Private Member Functions

static RealScalar secularEq (RealScalar x, const ArrayRef &col0, const ArrayRef &diag, const IndicesRef &perm, const ArrayRef &diagShifted, RealScalar shift)
 

Additional Inherited Members

- Protected Member Functions inherited from Eigen::SVDBase< BDCSVD< _MatrixType > >
void _check_compute_assertions () const
 
void _check_solve_assertion (const Rhs &b) const
 
bool allocate (Index rows, Index cols, unsigned int computationOptions)
 
 SVDBase ()
 Default Constructor. More...
 
- Protected Member Functions inherited from Eigen::SolverBase< SVDBase< BDCSVD< _MatrixType > > >
void _check_solve_assertion (const Rhs &b) const
 
- Static Protected Member Functions inherited from Eigen::SVDBase< BDCSVD< _MatrixType > >
static void check_template_parameters ()
 

Detailed Description

template<typename _MatrixType>
class Eigen::BDCSVD< _MatrixType >

class Bidiagonal Divide and Conquer SVD

Template Parameters
_MatrixTypethe type of the matrix of which we are computing the SVD decomposition

This class first reduces the input matrix to bi-diagonal form using class UpperBidiagonalization, and then performs a divide-and-conquer diagonalization. Small blocks are diagonalized using class JacobiSVD. You can control the switching size with the setSwitchSize() method, default is 16. For small matrice (<16), it is thus preferable to directly use JacobiSVD. For larger ones, BDCSVD is highly recommended and can several order of magnitude faster.

Warning
this algorithm is unlikely to provide accurate result when compiled with unsafe math optimizations. For instance, this concerns Intel's compiler (ICC), which performs such optimization by default unless you compile with the -fp-model precise option. Likewise, the -ffast-math option of GCC or clang will significantly degrade the accuracy.
See also
class JacobiSVD

Definition at line 279 of file ForwardDeclarations.h.

Member Typedef Documentation

◆ ArrayRef

template<typename _MatrixType>
typedef Ref<ArrayXr> Eigen::BDCSVD< _MatrixType >::ArrayRef

Definition at line 106 of file BDCSVD.h.

◆ ArrayXi

template<typename _MatrixType>
typedef Array<Index,1,Dynamic> Eigen::BDCSVD< _MatrixType >::ArrayXi

Definition at line 105 of file BDCSVD.h.

◆ ArrayXr

template<typename _MatrixType>
typedef Array<RealScalar, Dynamic, 1> Eigen::BDCSVD< _MatrixType >::ArrayXr

Definition at line 104 of file BDCSVD.h.

◆ Base

template<typename _MatrixType>
typedef SVDBase<BDCSVD> Eigen::BDCSVD< _MatrixType >::Base
private

Definition at line 75 of file BDCSVD.h.

◆ IndicesRef

template<typename _MatrixType>
typedef Ref<ArrayXi> Eigen::BDCSVD< _MatrixType >::IndicesRef

Definition at line 107 of file BDCSVD.h.

◆ Literal

template<typename _MatrixType>
typedef NumTraits<RealScalar>::Literal Eigen::BDCSVD< _MatrixType >::Literal

Definition at line 86 of file BDCSVD.h.

◆ MatrixType

template<typename _MatrixType>
typedef _MatrixType Eigen::BDCSVD< _MatrixType >::MatrixType

Definition at line 83 of file BDCSVD.h.

◆ MatrixUType

template<typename _MatrixType>
typedef Base::MatrixUType Eigen::BDCSVD< _MatrixType >::MatrixUType

Definition at line 97 of file BDCSVD.h.

◆ MatrixVType

template<typename _MatrixType>
typedef Base::MatrixVType Eigen::BDCSVD< _MatrixType >::MatrixVType

Definition at line 98 of file BDCSVD.h.

◆ MatrixX

template<typename _MatrixType>
typedef Matrix<Scalar, Dynamic, Dynamic, ColMajor> Eigen::BDCSVD< _MatrixType >::MatrixX

Definition at line 101 of file BDCSVD.h.

◆ MatrixXr

template<typename _MatrixType>
typedef Matrix<RealScalar, Dynamic, Dynamic, ColMajor> Eigen::BDCSVD< _MatrixType >::MatrixXr

Definition at line 102 of file BDCSVD.h.

◆ RealScalar

template<typename _MatrixType>
typedef NumTraits<typename MatrixType::Scalar>::Real Eigen::BDCSVD< _MatrixType >::RealScalar

Definition at line 85 of file BDCSVD.h.

◆ Scalar

template<typename _MatrixType>
typedef MatrixType::Scalar Eigen::BDCSVD< _MatrixType >::Scalar

Definition at line 84 of file BDCSVD.h.

◆ SingularValuesType

template<typename _MatrixType>
typedef Base::SingularValuesType Eigen::BDCSVD< _MatrixType >::SingularValuesType

Definition at line 99 of file BDCSVD.h.

◆ VectorType

template<typename _MatrixType>
typedef Matrix<RealScalar, Dynamic, 1> Eigen::BDCSVD< _MatrixType >::VectorType

Definition at line 103 of file BDCSVD.h.

Member Enumeration Documentation

◆ anonymous enum

template<typename _MatrixType>
anonymous enum
Enumerator
RowsAtCompileTime 
ColsAtCompileTime 
DiagSizeAtCompileTime 
MaxRowsAtCompileTime 
MaxColsAtCompileTime 
MaxDiagSizeAtCompileTime 
MatrixOptions 

Definition at line 87 of file BDCSVD.h.

Constructor & Destructor Documentation

◆ BDCSVD() [1/3]

template<typename _MatrixType>
Eigen::BDCSVD< _MatrixType >::BDCSVD ( )
inline

Default Constructor.

The default constructor is useful in cases in which the user intends to perform decompositions via BDCSVD::compute(const MatrixType&).

Definition at line 114 of file BDCSVD.h.

◆ BDCSVD() [2/3]

template<typename _MatrixType>
Eigen::BDCSVD< _MatrixType >::BDCSVD ( Index  rows,
Index  cols,
unsigned int  computationOptions = 0 
)
inline

Default Constructor with memory preallocation.

Like the default constructor but with preallocation of the internal data according to the specified problem size.

See also
BDCSVD()

Definition at line 124 of file BDCSVD.h.

◆ BDCSVD() [3/3]

template<typename _MatrixType>
Eigen::BDCSVD< _MatrixType >::BDCSVD ( const MatrixType matrix,
unsigned int  computationOptions = 0 
)
inline

Constructor performing the decomposition of given matrix.

Parameters
matrixthe matrix to decompose
computationOptionsoptional parameter allowing to specify if you want full or thin U or V unitaries to be computed. By default, none is computed. This is a bit - field, the possible bits are ComputeFullU, ComputeThinU, ComputeFullV, ComputeThinV.

Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not available with the (non - default) FullPivHouseholderQR preconditioner.

Definition at line 140 of file BDCSVD.h.

◆ ~BDCSVD()

template<typename _MatrixType>
Eigen::BDCSVD< _MatrixType >::~BDCSVD ( )
inline

Definition at line 146 of file BDCSVD.h.

Member Function Documentation

◆ allocate()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::allocate ( Eigen::Index  rows,
Eigen::Index  cols,
unsigned int  computationOptions 
)
private

Definition at line 222 of file BDCSVD.h.

◆ compute() [1/2]

template<typename MatrixType >
BDCSVD< MatrixType > & Eigen::BDCSVD< MatrixType >::compute ( const MatrixType matrix,
unsigned int  computationOptions 
)

Method performing the decomposition of given matrix using custom options.

Parameters
matrixthe matrix to decompose
computationOptionsoptional parameter allowing to specify if you want full or thin U or V unitaries to be computed. By default, none is computed. This is a bit - field, the possible bits are ComputeFullU, ComputeThinU, ComputeFullV, ComputeThinV.

Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not available with the (non - default) FullPivHouseholderQR preconditioner.

Definition at line 245 of file BDCSVD.h.

◆ compute() [2/2]

template<typename _MatrixType>
BDCSVD& Eigen::BDCSVD< _MatrixType >::compute ( const MatrixType matrix)
inline

Method performing the decomposition of given matrix using current options.

Parameters
matrixthe matrix to decompose

This method uses the current computationOptions, as already passed to the constructor or to compute(const MatrixType&, unsigned int).

Definition at line 168 of file BDCSVD.h.

◆ computeSingVals()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::computeSingVals ( const ArrayRef col0,
const ArrayRef diag,
const IndicesRef perm,
VectorType singVals,
ArrayRef  shifts,
ArrayRef  mus 
)
private

Definition at line 739 of file BDCSVD.h.

◆ computeSingVecs()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::computeSingVecs ( const ArrayRef zhat,
const ArrayRef diag,
const IndicesRef perm,
const VectorType singVals,
const ArrayRef shifts,
const ArrayRef mus,
MatrixXr U,
MatrixXr V 
)
private

Definition at line 1066 of file BDCSVD.h.

◆ computeSVDofM()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::computeSVDofM ( Eigen::Index  firstCol,
Eigen::Index  n,
MatrixXr U,
VectorType singVals,
MatrixXr V 
)
private

Definition at line 595 of file BDCSVD.h.

◆ copyUV()

template<typename MatrixType >
template<typename HouseholderU , typename HouseholderV , typename NaiveU , typename NaiveV >
void Eigen::BDCSVD< MatrixType >::copyUV ( const HouseholderU &  householderU,
const HouseholderV &  householderV,
const NaiveU &  naiveU,
const NaiveV &  naivev 
)
private

Definition at line 332 of file BDCSVD.h.

◆ deflation()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::deflation ( Eigen::Index  firstCol,
Eigen::Index  lastCol,
Eigen::Index  k,
Eigen::Index  firstRowW,
Eigen::Index  firstColW,
Eigen::Index  shift 
)
private

Definition at line 1180 of file BDCSVD.h.

◆ deflation43()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::deflation43 ( Eigen::Index  firstCol,
Eigen::Index  shift,
Eigen::Index  i,
Eigen::Index  size 
)
private

Definition at line 1111 of file BDCSVD.h.

◆ deflation44()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::deflation44 ( Eigen::Index  firstColu,
Eigen::Index  firstColm,
Eigen::Index  firstRowW,
Eigen::Index  firstColW,
Eigen::Index  i,
Eigen::Index  j,
Eigen::Index  size 
)
private

Definition at line 1140 of file BDCSVD.h.

◆ divide()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::divide ( Eigen::Index  firstCol,
Eigen::Index  lastCol,
Eigen::Index  firstRowW,
Eigen::Index  firstColW,
Eigen::Index  shift 
)
private

Definition at line 411 of file BDCSVD.h.

◆ perturbCol0()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::perturbCol0 ( const ArrayRef col0,
const ArrayRef diag,
const IndicesRef perm,
const VectorType singVals,
const ArrayRef shifts,
const ArrayRef mus,
ArrayRef  zhat 
)
private

Definition at line 986 of file BDCSVD.h.

◆ secularEq()

template<typename MatrixType >
BDCSVD< MatrixType >::RealScalar Eigen::BDCSVD< MatrixType >::secularEq ( RealScalar  x,
const ArrayRef col0,
const ArrayRef diag,
const IndicesRef perm,
const ArrayRef diagShifted,
RealScalar  shift 
)
staticprivate

Definition at line 723 of file BDCSVD.h.

◆ setSwitchSize()

template<typename _MatrixType>
void Eigen::BDCSVD< _MatrixType >::setSwitchSize ( int  s)
inline

Definition at line 173 of file BDCSVD.h.

◆ structured_update()

template<typename MatrixType >
void Eigen::BDCSVD< MatrixType >::structured_update ( Block< MatrixXr, Dynamic, Dynamic A,
const MatrixXr B,
Index  n1 
)
private

Definition at line 360 of file BDCSVD.h.

Member Data Documentation

◆ m_algoswap

template<typename _MatrixType>
int Eigen::BDCSVD< _MatrixType >::m_algoswap
protected

Definition at line 200 of file BDCSVD.h.

◆ m_compU

template<typename _MatrixType>
bool Eigen::BDCSVD< _MatrixType >::m_compU
protected

Definition at line 201 of file BDCSVD.h.

◆ m_computed

template<typename _MatrixType>
MatrixXr Eigen::BDCSVD< _MatrixType >::m_computed
protected

Definition at line 196 of file BDCSVD.h.

◆ m_compV

template<typename _MatrixType>
bool Eigen::BDCSVD< _MatrixType >::m_compV
protected

Definition at line 201 of file BDCSVD.h.

◆ m_isTranspose

template<typename _MatrixType>
bool Eigen::BDCSVD< _MatrixType >::m_isTranspose
protected

Definition at line 201 of file BDCSVD.h.

◆ m_naiveU

template<typename _MatrixType>
MatrixXr Eigen::BDCSVD< _MatrixType >::m_naiveU
protected

Definition at line 195 of file BDCSVD.h.

◆ m_naiveV

template<typename _MatrixType>
MatrixXr Eigen::BDCSVD< _MatrixType >::m_naiveV
protected

Definition at line 195 of file BDCSVD.h.

◆ m_nRec

template<typename _MatrixType>
Index Eigen::BDCSVD< _MatrixType >::m_nRec
protected

Definition at line 197 of file BDCSVD.h.

◆ m_numIters

template<typename _MatrixType>
int Eigen::BDCSVD< _MatrixType >::m_numIters

Definition at line 216 of file BDCSVD.h.

◆ m_workspace

template<typename _MatrixType>
ArrayXr Eigen::BDCSVD< _MatrixType >::m_workspace
protected

Definition at line 198 of file BDCSVD.h.

◆ m_workspaceI

template<typename _MatrixType>
ArrayXi Eigen::BDCSVD< _MatrixType >::m_workspaceI
protected

Definition at line 199 of file BDCSVD.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:41:21