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 ()
 
template<typename Derived >
 BKLDLT (const Eigen::MatrixBase< Derived > &mat, int uplo=Eigen::Lower, const RealScalar &shift=RealScalar(0))
 
template<typename Derived >
void compute (const Eigen::MatrixBase< Derived > &mat, int uplo=Eigen::Lower, const RealScalar &shift=RealScalar(0))
 
CompInfo info () const
 
Vector solve (ConstGenericVector &b) const
 
void solve_inplace (GenericVector b) const
 

Private Types

using ConstGenericVector = const Eigen::Ref< const Vector >
 
using GenericVector = Eigen::Ref< Vector >
 
using Index = Eigen::Index
 
using IntVector = Eigen::Matrix< Index, Eigen::Dynamic, 1 >
 
using MapConstVec = Eigen::Map< const Vector >
 
using MapVec = Eigen::Map< Vector >
 
using RealScalar = typename Eigen::NumTraits< Scalar >::Real
 
using Vector = Eigen::Matrix< Scalar, Eigen::Dynamic, 1 >
 

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 ()
 
template<typename Derived >
void copy_data (const Eigen::MatrixBase< Derived > &mat, int uplo, const RealScalar &shift)
 
Scalardiag_coeff (Index i)
 
const Scalardiag_coeff (Index i) const
 
RealScalar find_lambda (Index k, Index &r)
 
RealScalar find_sigma (Index k, Index r, Index &p)
 
CompInfo gaussian_elimination_1x1 (Index k)
 
CompInfo 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 RealScalar &alpha)
 
void pivoting_1x1 (Index k, Index r)
 
void pivoting_2x2 (Index k, Index r, Index p)
 
void solve_inplace_2x2 (const Scalar &e11, const Scalar &e21, const Scalar &e22, Scalar &b1, Scalar &b2) const
 
void solve_left_2x2 (const Scalar &e11, const Scalar &e21, const Scalar &e22, const MapVec &c1, const MapVec &c2, Eigen::Matrix< Scalar, Eigen::Dynamic, 2 > &x) const
 

Private Attributes

std::vector< Scalar * > m_colptr
 
bool m_computed
 
Vector m_data
 
CompInfo 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 65 of file BKLDLT.h.

Member Typedef Documentation

◆ ConstGenericVector

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

Definition at line 76 of file BKLDLT.h.

◆ GenericVector

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

Definition at line 75 of file BKLDLT.h.

◆ Index

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

Definition at line 70 of file BKLDLT.h.

◆ IntVector

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

Definition at line 74 of file BKLDLT.h.

◆ MapConstVec

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

Definition at line 73 of file BKLDLT.h.

◆ MapVec

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

Definition at line 72 of file BKLDLT.h.

◆ RealScalar

template<typename Scalar = double>
using Spectra::BKLDLT< Scalar >::RealScalar = typename Eigen::NumTraits<Scalar>::Real
private

Definition at line 69 of file BKLDLT.h.

◆ Vector

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

Definition at line 71 of file BKLDLT.h.

Constructor & Destructor Documentation

◆ BKLDLT() [1/2]

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

Definition at line 533 of file BKLDLT.h.

◆ BKLDLT() [2/2]

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

Definition at line 539 of file BKLDLT.h.

Member Function Documentation

◆ coeff() [1/2]

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

Definition at line 91 of file BKLDLT.h.

◆ coeff() [2/2]

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

Definition at line 92 of file BKLDLT.h.

◆ col_pointer()

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

Definition at line 89 of file BKLDLT.h.

◆ compress_permutation()

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

Definition at line 149 of file BKLDLT.h.

◆ compute()

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

Definition at line 546 of file BKLDLT.h.

◆ compute_pointer()

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

Definition at line 98 of file BKLDLT.h.

◆ copy_data()

template<typename Scalar = double>
template<typename Derived >
void Spectra::BKLDLT< Scalar >::copy_data ( const Eigen::MatrixBase< Derived > &  mat,
int  uplo,
const RealScalar shift 
)
inlineprivate

Definition at line 113 of file BKLDLT.h.

◆ diag_coeff() [1/2]

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

Definition at line 94 of file BKLDLT.h.

◆ diag_coeff() [2/2]

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

Definition at line 95 of file BKLDLT.h.

◆ find_lambda()

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

Definition at line 240 of file BKLDLT.h.

◆ find_sigma()

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

Definition at line 267 of file BKLDLT.h.

◆ gaussian_elimination_1x1()

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

Definition at line 450 of file BKLDLT.h.

◆ gaussian_elimination_2x2()

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

Definition at line 482 of file BKLDLT.h.

◆ info()

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

Definition at line 699 of file BKLDLT.h.

◆ interchange_rows()

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

Definition at line 225 of file BKLDLT.h.

◆ inverse_inplace_2x2()

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

Definition at line 366 of file BKLDLT.h.

◆ permutate_mat()

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

Definition at line 293 of file BKLDLT.h.

◆ pivoting_1x1()

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

Definition at line 163 of file BKLDLT.h.

◆ pivoting_2x2()

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

Definition at line 209 of file BKLDLT.h.

◆ solve()

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

Definition at line 692 of file BKLDLT.h.

◆ solve_inplace()

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

Definition at line 602 of file BKLDLT.h.

◆ solve_inplace_2x2()

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

Definition at line 382 of file BKLDLT.h.

◆ solve_left_2x2()

template<typename Scalar = double>
void Spectra::BKLDLT< Scalar >::solve_left_2x2 ( const Scalar e11,
const Scalar e21,
const Scalar e22,
const MapVec c1,
const MapVec c2,
Eigen::Matrix< Scalar, Eigen::Dynamic, 2 > &  x 
) const
inlineprivate

Definition at line 417 of file BKLDLT.h.

Member Data Documentation

◆ m_colptr

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

Definition at line 80 of file BKLDLT.h.

◆ m_computed

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

Definition at line 84 of file BKLDLT.h.

◆ m_data

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

Definition at line 79 of file BKLDLT.h.

◆ m_info

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

Definition at line 85 of file BKLDLT.h.

◆ m_n

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

Definition at line 78 of file BKLDLT.h.

◆ m_perm

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

Definition at line 81 of file BKLDLT.h.

◆ m_permc

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

Definition at line 82 of file BKLDLT.h.


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


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:15:49