Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
Spectra::BKLDLT< Scalar > Class Template Reference

#include <BKLDLT.h>

Public Member Functions

 BKLDLT ()
 
 BKLDLT (ConstGenericMatrix &mat, int uplo=Eigen::Lower, const Scalar &shift=Scalar(0))
 
void compute (ConstGenericMatrix &mat, int uplo=Eigen::Lower, const Scalar &shift=Scalar(0))
 
int info () const
 
Vector solve (ConstGenericVector &b) const
 
void solve_inplace (GenericVector b) const
 

Private Types

typedef const Eigen::Ref< const MatrixConstGenericMatrix
 
typedef const Eigen::Ref< const VectorConstGenericVector
 
typedef Eigen::Ref< MatrixGenericMatrix
 
typedef Eigen::Ref< VectorGenericVector
 
typedef Eigen::Index Index
 
typedef Eigen::Matrix< Index, Eigen::Dynamic, 1 > IntVector
 
typedef Eigen::Map< const VectorMapConstVec
 
typedef Eigen::Map< VectorMapVec
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::DynamicMatrix
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
 

Private Member Functions

Scalarcoeff (Index i, Index j)
 
const Scalarcoeff (Index i, Index j) const
 
Scalarcol_pointer (Index k)
 
void compress_permutation ()
 
void compute_pointer ()
 
void copy_data (ConstGenericMatrix &mat, int uplo, const Scalar &shift)
 
Scalardiag_coeff (Index i)
 
const Scalardiag_coeff (Index i) const
 
Scalar find_lambda (Index k, Index &r)
 
Scalar find_sigma (Index k, Index r, Index &p)
 
int gaussian_elimination_1x1 (Index k)
 
int gaussian_elimination_2x2 (Index k)
 
void interchange_rows (Index r1, Index r2, Index c1, Index c2)
 
void inverse_inplace_2x2 (Scalar &e11, Scalar &e21, Scalar &e22) const
 
bool permutate_mat (Index k, const Scalar &alpha)
 
void pivoting_1x1 (Index k, Index r)
 
void pivoting_2x2 (Index k, Index r, Index p)
 

Private Attributes

std::vector< Scalar * > m_colptr
 
bool m_computed
 
Vector m_data
 
int m_info
 
Index m_n
 
IntVector m_perm
 
std::vector< std::pair< Index, Index > > m_permc
 

Detailed Description

template<typename Scalar = double>
class Spectra::BKLDLT< Scalar >

Definition at line 27 of file BKLDLT.h.

Member Typedef Documentation

template<typename Scalar = double>
typedef const Eigen::Ref<const Matrix> Spectra::BKLDLT< Scalar >::ConstGenericMatrix
private

Definition at line 39 of file BKLDLT.h.

template<typename Scalar = double>
typedef const Eigen::Ref<const Vector> Spectra::BKLDLT< Scalar >::ConstGenericVector
private

Definition at line 40 of file BKLDLT.h.

template<typename Scalar = double>
typedef Eigen::Ref<Matrix> Spectra::BKLDLT< Scalar >::GenericMatrix
private

Definition at line 38 of file BKLDLT.h.

template<typename Scalar = double>
typedef Eigen::Ref<Vector> Spectra::BKLDLT< Scalar >::GenericVector
private

Definition at line 37 of file BKLDLT.h.

template<typename Scalar = double>
typedef Eigen::Index Spectra::BKLDLT< Scalar >::Index
private

Definition at line 30 of file BKLDLT.h.

template<typename Scalar = double>
typedef Eigen::Matrix<Index, Eigen::Dynamic, 1> Spectra::BKLDLT< Scalar >::IntVector
private

Definition at line 36 of file BKLDLT.h.

template<typename Scalar = double>
typedef Eigen::Map<const Vector> Spectra::BKLDLT< Scalar >::MapConstVec
private

Definition at line 34 of file BKLDLT.h.

template<typename Scalar = double>
typedef Eigen::Map<Vector> Spectra::BKLDLT< Scalar >::MapVec
private

Definition at line 33 of file BKLDLT.h.

template<typename Scalar = double>
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> Spectra::BKLDLT< Scalar >::Matrix
private

Definition at line 31 of file BKLDLT.h.

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

Definition at line 32 of file BKLDLT.h.

Constructor & Destructor Documentation

template<typename Scalar = double>
Spectra::BKLDLT< Scalar >::BKLDLT ( )
inline

Definition at line 375 of file BKLDLT.h.

template<typename Scalar = double>
Spectra::BKLDLT< Scalar >::BKLDLT ( ConstGenericMatrix mat,
int  uplo = Eigen::Lower,
const Scalar shift = Scalar(0) 
)
inline

Definition at line 380 of file BKLDLT.h.

Member Function Documentation

template<typename Scalar = double>
Scalar& Spectra::BKLDLT< Scalar >::coeff ( Index  i,
Index  j 
)
inlineprivate

Definition at line 55 of file BKLDLT.h.

template<typename Scalar = double>
const Scalar& Spectra::BKLDLT< Scalar >::coeff ( Index  i,
Index  j 
) const
inlineprivate

Definition at line 56 of file BKLDLT.h.

template<typename Scalar = double>
Scalar* Spectra::BKLDLT< Scalar >::col_pointer ( Index  k)
inlineprivate

Definition at line 53 of file BKLDLT.h.

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::compress_permutation ( )
inlineprivate

Definition at line 103 of file BKLDLT.h.

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::compute ( ConstGenericMatrix mat,
int  uplo = Eigen::Lower,
const Scalar shift = Scalar(0) 
)
inline

Definition at line 386 of file BKLDLT.h.

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::compute_pointer ( )
inlineprivate

Definition at line 62 of file BKLDLT.h.

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::copy_data ( ConstGenericMatrix mat,
int  uplo,
const Scalar shift 
)
inlineprivate

Definition at line 76 of file BKLDLT.h.

template<typename Scalar = double>
Scalar& Spectra::BKLDLT< Scalar >::diag_coeff ( Index  i)
inlineprivate

Definition at line 58 of file BKLDLT.h.

template<typename Scalar = double>
const Scalar& Spectra::BKLDLT< Scalar >::diag_coeff ( Index  i) const
inlineprivate

Definition at line 59 of file BKLDLT.h.

template<typename Scalar = double>
Scalar Spectra::BKLDLT< Scalar >::find_lambda ( Index  k,
Index r 
)
inlineprivate

Definition at line 176 of file BKLDLT.h.

template<typename Scalar = double>
Scalar Spectra::BKLDLT< Scalar >::find_sigma ( Index  k,
Index  r,
Index p 
)
inlineprivate

Definition at line 203 of file BKLDLT.h.

template<typename Scalar = double>
int Spectra::BKLDLT< Scalar >::gaussian_elimination_1x1 ( Index  k)
inlineprivate

Definition at line 313 of file BKLDLT.h.

template<typename Scalar = double>
int Spectra::BKLDLT< Scalar >::gaussian_elimination_2x2 ( Index  k)
inlineprivate

Definition at line 339 of file BKLDLT.h.

template<typename Scalar = double>
int Spectra::BKLDLT< Scalar >::info ( ) const
inline

Definition at line 525 of file BKLDLT.h.

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::interchange_rows ( Index  r1,
Index  r2,
Index  c1,
Index  c2 
)
inlineprivate

Definition at line 161 of file BKLDLT.h.

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::inverse_inplace_2x2 ( Scalar e11,
Scalar e21,
Scalar e22 
) const
inlineprivate

Definition at line 301 of file BKLDLT.h.

template<typename Scalar = double>
bool Spectra::BKLDLT< Scalar >::permutate_mat ( Index  k,
const Scalar alpha 
)
inlineprivate

Definition at line 229 of file BKLDLT.h.

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::pivoting_1x1 ( Index  k,
Index  r 
)
inlineprivate

Definition at line 117 of file BKLDLT.h.

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::pivoting_2x2 ( Index  k,
Index  r,
Index  p 
)
inlineprivate

Definition at line 145 of file BKLDLT.h.

template<typename Scalar = double>
Vector Spectra::BKLDLT< Scalar >::solve ( ConstGenericVector b) const
inline

Definition at line 518 of file BKLDLT.h.

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::solve_inplace ( GenericVector  b) const
inline

Definition at line 440 of file BKLDLT.h.

Member Data Documentation

template<typename Scalar = double>
std::vector<Scalar*> Spectra::BKLDLT< Scalar >::m_colptr
private

Definition at line 44 of file BKLDLT.h.

template<typename Scalar = double>
bool Spectra::BKLDLT< Scalar >::m_computed
private

Definition at line 48 of file BKLDLT.h.

template<typename Scalar = double>
Vector Spectra::BKLDLT< Scalar >::m_data
private

Definition at line 43 of file BKLDLT.h.

template<typename Scalar = double>
int Spectra::BKLDLT< Scalar >::m_info
private

Definition at line 49 of file BKLDLT.h.

template<typename Scalar = double>
Index Spectra::BKLDLT< Scalar >::m_n
private

Definition at line 42 of file BKLDLT.h.

template<typename Scalar = double>
IntVector Spectra::BKLDLT< Scalar >::m_perm
private

Definition at line 45 of file BKLDLT.h.

template<typename Scalar = double>
std::vector<std::pair<Index, Index> > Spectra::BKLDLT< Scalar >::m_permc
private

Definition at line 46 of file BKLDLT.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:59:20