Public Types | Public Member Functions | Protected Types | Protected Attributes | Private Member Functions | List of all members
Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType > Class Template Reference

Modified Incomplete Cholesky with dual threshold. More...

#include <IncompleteCholesky.h>

Inheritance diagram for Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >:
Inheritance graph
[legend]

Public Types

enum  { UpLo = _UpLo }
 
enum  { ColsAtCompileTime = Dynamic, MaxColsAtCompileTime = Dynamic }
 
typedef SparseMatrix< Scalar, ColMajor, StorageIndexFactorType
 
typedef _OrderingType OrderingType
 
typedef OrderingType::PermutationType PermutationType
 
typedef NumTraits< Scalar >::Real RealScalar
 
typedef PermutationType::StorageIndex StorageIndex
 
typedef Matrix< StorageIndex, Dynamic, 1 > VectorIx
 
typedef std::vector< std::list< StorageIndex > > VectorList
 
typedef Matrix< RealScalar, Dynamic, 1 > VectorRx
 
typedef Matrix< Scalar, Dynamic, 1 > VectorSx
 

Public Member Functions

template<typename Rhs , typename Dest >
void _solve_impl (const Rhs &b, Dest &x) const
 
template<typename MatrixType >
void analyzePattern (const MatrixType &mat)
 Computes the fill reducing permutation vector using the sparsity pattern of mat. More...
 
EIGEN_CONSTEXPR Index cols () const EIGEN_NOEXCEPT
 
template<typename MatrixType >
void compute (const MatrixType &mat)
 
template<typename _MatrixType >
void factorize (const _MatrixType &mat)
 
template<typename MatrixType >
void factorize (const MatrixType &mat)
 Performs the numerical factorization of the input matrix mat. More...
 
 IncompleteCholesky ()
 
template<typename MatrixType >
 IncompleteCholesky (const MatrixType &matrix)
 
ComputationInfo info () const
 Reports whether previous computation was successful. More...
 
const FactorTypematrixL () const
 
const PermutationTypepermutationP () const
 
EIGEN_CONSTEXPR Index rows () const EIGEN_NOEXCEPT
 
const VectorRxscalingS () const
 
void setInitialShift (RealScalar shift)
 Set the initial shift parameter $ \sigma $. More...
 
- Public Member Functions inherited from Eigen::SparseSolverBase< IncompleteCholesky< Scalar, Lower, AMDOrdering< int > > >
void _solve_impl (const SparseMatrixBase< Rhs > &b, SparseMatrixBase< Dest > &dest) const
 
IncompleteCholesky< Scalar, Lower, AMDOrdering< int > > & derived ()
 
const IncompleteCholesky< Scalar, Lower, AMDOrdering< int > > & derived () const
 
const Solve< IncompleteCholesky< Scalar, Lower, AMDOrdering< int > >, Rhs > solve (const MatrixBase< Rhs > &b) const
 
const Solve< IncompleteCholesky< Scalar, Lower, AMDOrdering< int > >, Rhs > solve (const SparseMatrixBase< Rhs > &b) const
 
 SparseSolverBase ()
 
 ~SparseSolverBase ()
 

Protected Types

typedef SparseSolverBase< IncompleteCholesky< Scalar, _UpLo, _OrderingType > > Base
 

Protected Attributes

bool m_analysisIsOk
 
bool m_factorizationIsOk
 
ComputationInfo m_info
 
RealScalar m_initialShift
 
bool m_isInitialized
 
FactorType m_L
 
PermutationType m_perm
 
VectorRx m_scale
 
- Protected Attributes inherited from Eigen::SparseSolverBase< IncompleteCholesky< Scalar, Lower, AMDOrdering< int > > >
bool m_isInitialized
 

Private Member Functions

void updateList (Ref< const VectorIx > colPtr, Ref< VectorIx > rowIdx, Ref< VectorSx > vals, const Index &col, const Index &jk, VectorIx &firstElt, VectorList &listCol)
 

Detailed Description

template<typename Scalar, int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
class Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >

Modified Incomplete Cholesky with dual threshold.

References : C-J. Lin and J. J. Moré, Incomplete Cholesky Factorizations with Limited memory, SIAM J. Sci. Comput. 21(1), pp. 24-45, 1999

Template Parameters
Scalarthe scalar type of the input matrices
_UpLoThe triangular part that will be used for the computations. It can be Lower or Upper. Default is Lower.
_OrderingTypeThe ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<int>, unless EIGEN_MPL2_ONLY is defined, in which case the default is NaturalOrdering<int>.

\implsparsesolverconcept

It performs the following incomplete factorization: $ S P A P' S \approx L L' $ where L is a lower triangular factor, S is a diagonal scaling matrix, and P is a fill-in reducing permutation as computed by the ordering method.

Shifting strategy: Let $ B = S P A P' S $ be the scaled matrix on which the factorization is carried out, and $ \beta $ be the minimum value of the diagonal. If $ \beta > 0 $ then, the factorization is directly performed on the matrix B. Otherwise, the factorization is performed on the shifted matrix $ B + (\sigma+|\beta| I $ where $ \sigma $ is the initial shift value as returned and set by setInitialShift() method. The default value is $ \sigma = 10^{-3} $. If the factorization fails, then the shift in doubled until it succeed or a maximum of ten attempts. If it still fails, as returned by the info() method, then you can either increase the initial shift, or better use another preconditioning technique.

Definition at line 45 of file IncompleteCholesky.h.

Member Typedef Documentation

◆ Base

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef SparseSolverBase<IncompleteCholesky<Scalar,_UpLo,_OrderingType> > Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::Base
protected

Definition at line 48 of file IncompleteCholesky.h.

◆ FactorType

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef SparseMatrix<Scalar,ColMajor,StorageIndex> Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::FactorType

Definition at line 55 of file IncompleteCholesky.h.

◆ OrderingType

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef _OrderingType Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::OrderingType

Definition at line 52 of file IncompleteCholesky.h.

◆ PermutationType

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef OrderingType::PermutationType Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::PermutationType

Definition at line 53 of file IncompleteCholesky.h.

◆ RealScalar

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef NumTraits<Scalar>::Real Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::RealScalar

Definition at line 51 of file IncompleteCholesky.h.

◆ StorageIndex

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef PermutationType::StorageIndex Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::StorageIndex

Definition at line 54 of file IncompleteCholesky.h.

◆ VectorIx

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef Matrix<StorageIndex,Dynamic, 1> Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::VectorIx

Definition at line 58 of file IncompleteCholesky.h.

◆ VectorList

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef std::vector<std::list<StorageIndex> > Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::VectorList

Definition at line 59 of file IncompleteCholesky.h.

◆ VectorRx

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef Matrix<RealScalar,Dynamic,1> Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::VectorRx

Definition at line 57 of file IncompleteCholesky.h.

◆ VectorSx

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
typedef Matrix<Scalar,Dynamic,1> Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::VectorSx

Definition at line 56 of file IncompleteCholesky.h.

Member Enumeration Documentation

◆ anonymous enum

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
anonymous enum
Enumerator
UpLo 

Definition at line 60 of file IncompleteCholesky.h.

◆ anonymous enum

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
anonymous enum
Enumerator
ColsAtCompileTime 
MaxColsAtCompileTime 

Definition at line 61 of file IncompleteCholesky.h.

Constructor & Destructor Documentation

◆ IncompleteCholesky() [1/2]

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::IncompleteCholesky ( )
inline

Default constructor leaving the object in a partly non-initialized stage.

You must call compute() or the pair analyzePattern()/factorize() to make it valid.

See also
IncompleteCholesky(const MatrixType&)

Definition at line 73 of file IncompleteCholesky.h.

◆ IncompleteCholesky() [2/2]

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
template<typename MatrixType >
Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::IncompleteCholesky ( const MatrixType matrix)
inline

Constructor computing the incomplete factorization for the given matrix matrix.

Definition at line 78 of file IncompleteCholesky.h.

Member Function Documentation

◆ _solve_impl()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
template<typename Rhs , typename Dest >
void Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::_solve_impl ( const Rhs &  b,
Dest &  x 
) const
inline

Definition at line 149 of file IncompleteCholesky.h.

◆ analyzePattern()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
template<typename MatrixType >
void Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::analyzePattern ( const MatrixType mat)
inline

Computes the fill reducing permutation vector using the sparsity pattern of mat.

Definition at line 111 of file IncompleteCholesky.h.

◆ cols()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
EIGEN_CONSTEXPR Index Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::cols ( ) const
inline
Returns
number of columns of the factored matrix

Definition at line 87 of file IncompleteCholesky.h.

◆ compute()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
template<typename MatrixType >
void Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::compute ( const MatrixType mat)
inline

Computes or re-computes the incomplete Cholesky factorization of the input matrix mat

It is a shortcut for a sequential call to the analyzePattern() and factorize() methods.

See also
analyzePattern(), factorize()

Definition at line 141 of file IncompleteCholesky.h.

◆ factorize() [1/2]

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
template<typename _MatrixType >
void Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::factorize ( const _MatrixType &  mat)

Definition at line 190 of file IncompleteCholesky.h.

◆ factorize() [2/2]

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
template<typename MatrixType >
void Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::factorize ( const MatrixType mat)

Performs the numerical factorization of the input matrix mat.

The method analyzePattern() or compute() must have been called beforehand with a matrix having the same pattern.

See also
compute(), analyzePattern()

◆ info()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
ComputationInfo Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::info ( ) const
inline

Reports whether previous computation was successful.

It triggers an assertion if *this has not been initialized through the respective constructor, or a call to compute() or analyzePattern().

Returns
Success if computation was successful, NumericalIssue if the matrix appears to be negative.

Definition at line 98 of file IncompleteCholesky.h.

◆ matrixL()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
const FactorType& Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::matrixL ( ) const
inline
Returns
the sparse lower triangular factor L

Definition at line 163 of file IncompleteCholesky.h.

◆ permutationP()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
const PermutationType& Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::permutationP ( ) const
inline
Returns
the fill-in reducing permutation P (can be empty for a natural ordering)

Definition at line 169 of file IncompleteCholesky.h.

◆ rows()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
EIGEN_CONSTEXPR Index Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::rows ( ) const
inline
Returns
number of rows of the factored matrix

Definition at line 84 of file IncompleteCholesky.h.

◆ scalingS()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
const VectorRx& Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::scalingS ( ) const
inline
Returns
a vector representing the scaling factor S

Definition at line 166 of file IncompleteCholesky.h.

◆ setInitialShift()

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
void Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::setInitialShift ( RealScalar  shift)
inline

Set the initial shift parameter $ \sigma $.

Definition at line 106 of file IncompleteCholesky.h.

◆ updateList()

template<typename Scalar , int _UpLo, typename OrderingType >
void Eigen::IncompleteCholesky< Scalar, _UpLo, OrderingType >::updateList ( Ref< const VectorIx colPtr,
Ref< VectorIx rowIdx,
Ref< VectorSx vals,
const Index col,
const Index jk,
VectorIx firstElt,
VectorList listCol 
)
inlineprivate

Definition at line 373 of file IncompleteCholesky.h.

Member Data Documentation

◆ m_analysisIsOk

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
bool Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::m_analysisIsOk
protected

Definition at line 175 of file IncompleteCholesky.h.

◆ m_factorizationIsOk

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
bool Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::m_factorizationIsOk
protected

Definition at line 176 of file IncompleteCholesky.h.

◆ m_info

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
ComputationInfo Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::m_info
protected

Definition at line 177 of file IncompleteCholesky.h.

◆ m_initialShift

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
RealScalar Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::m_initialShift
protected

Definition at line 174 of file IncompleteCholesky.h.

◆ m_isInitialized

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
bool Eigen::SparseSolverBase< Derived >::m_isInitialized
mutableprotected

Definition at line 119 of file SparseSolverBase.h.

◆ m_L

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
FactorType Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::m_L
protected

Definition at line 172 of file IncompleteCholesky.h.

◆ m_perm

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
PermutationType Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::m_perm
protected

Definition at line 178 of file IncompleteCholesky.h.

◆ m_scale

template<typename Scalar , int _UpLo = Lower, typename _OrderingType = AMDOrdering<int>>
VectorRx Eigen::IncompleteCholesky< Scalar, _UpLo, _OrderingType >::m_scale
protected

Definition at line 173 of file IncompleteCholesky.h.


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


gtsam
Author(s):
autogenerated on Wed May 15 2024 15:28:10