Public Types | Public Member Functions | Private Types | Private Attributes | List of all members
Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB > Class Template Reference

#include <SymShiftInvert.h>

Public Types

using Scalar = Scalar_
 

Public Member Functions

Index cols () const
 
void perform_op (const Scalar *x_in, Scalar *y_out) const
 
Index rows () const
 
void set_shift (const Scalar &sigma)
 
template<typename DerivedA , typename DerivedB >
 SymShiftInvert (const Eigen::EigenBase< DerivedA > &A, const Eigen::EigenBase< DerivedB > &B)
 

Private Types

using ASparse = std::is_same< TypeA, Eigen::Sparse >
 
using BSparse = std::is_same< TypeB, Eigen::Sparse >
 
using ConstGenericMatrixA = const Eigen::Ref< const MatrixA >
 
using ConstGenericMatrixB = const Eigen::Ref< const MatrixB >
 
using DenseType = typename std::conditional< ASparse::value, MatrixB, MatrixA >::type
 
using DenseTypeA = Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, FlagsA >
 
using DenseTypeB = Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, FlagsB >
 
using FacType = typename std::conditional< ASparse::value &&BSparse::value, Eigen::SparseLU< ResType >, BKLDLT< Scalar > >::type
 
using Index = Eigen::Index
 
using MapConstVec = Eigen::Map< const Vector >
 
using MapVec = Eigen::Map< Vector >
 
using MatrixA = typename std::conditional< ASparse::value, SparseTypeA, DenseTypeA >::type
 
using MatrixB = typename std::conditional< BSparse::value, SparseTypeB, DenseTypeB >::type
 
using ResType = typename std::conditional< ASparse::value &&BSparse::value, MatrixA, DenseType >::type
 
using SparseTypeA = Eigen::SparseMatrix< Scalar, FlagsA, StorageIndexA >
 
using SparseTypeB = Eigen::SparseMatrix< Scalar, FlagsB, StorageIndexB >
 
using Vector = Eigen::Matrix< Scalar, Eigen::Dynamic, 1 >
 

Private Attributes

ConstGenericMatrixA m_matA
 
ConstGenericMatrixB m_matB
 
const Index m_n
 
FacType m_solver
 

Detailed Description

template<typename Scalar_, typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
class Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >

This class defines matrix operations required by the generalized eigen solver in the shift-and-invert mode. Given two symmetric matrices $A$ and $B$, it solves the linear equation $y=(A-\sigma B)^{-1}x$, where $\sigma$ is a real shift. Each of $A$ and $B$ can be a dense or sparse matrix.

This class is intended to be used with the SymGEigsShiftSolver generalized eigen solver.

Template Parameters
Scalar_The element type of the matrices. Currently supported types are float, double, and long double.
TypeAThe type of the $A$ matrix, indicating whether $A$ is dense or sparse. Possible values are Eigen::Dense and Eigen::Sparse.
TypeBThe type of the $B$ matrix, indicating whether $B$ is dense or sparse. Possible values are Eigen::Dense and Eigen::Sparse.
UploAWhether the lower or upper triangular part of $A$ should be used. Possible values are Eigen::Lower and Eigen::Upper.
UploBWhether the lower or upper triangular part of $B$ should be used. Possible values are Eigen::Lower and Eigen::Upper.
FlagsAAdditional flags for the matrix class of $A$. Possible values are Eigen::ColMajor and Eigen::RowMajor.
FlagsBAdditional flags for the matrix class of $B$. Possible values are Eigen::ColMajor and Eigen::RowMajor.
StorageIndexAThe storage index type of the $A$ matrix, only used when $A$ is a sparse matrix.
StorageIndexBThe storage index type of the $B$ matrix, only used when $B$ is a sparse matrix.

Definition at line 127 of file SymShiftInvert.h.

Member Typedef Documentation

◆ ASparse

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::ASparse = std::is_same<TypeA, Eigen::Sparse>
private

Definition at line 142 of file SymShiftInvert.h.

◆ BSparse

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::BSparse = std::is_same<TypeB, Eigen::Sparse>
private

Definition at line 150 of file SymShiftInvert.h.

◆ ConstGenericMatrixA

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::ConstGenericMatrixA = const Eigen::Ref<const MatrixA>
private

Definition at line 172 of file SymShiftInvert.h.

◆ ConstGenericMatrixB

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::ConstGenericMatrixB = const Eigen::Ref<const MatrixB>
private

Definition at line 173 of file SymShiftInvert.h.

◆ DenseType

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::DenseType = typename std::conditional<ASparse::value, MatrixB, MatrixA>::type
private

Definition at line 160 of file SymShiftInvert.h.

◆ DenseTypeA

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::DenseTypeA = Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, FlagsA>
private

Definition at line 139 of file SymShiftInvert.h.

◆ DenseTypeB

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::DenseTypeB = Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, FlagsB>
private

Definition at line 147 of file SymShiftInvert.h.

◆ FacType

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::FacType = typename std::conditional< ASparse::value && BSparse::value, Eigen::SparseLU<ResType>, BKLDLT<Scalar> >::type
private

Definition at line 170 of file SymShiftInvert.h.

◆ Index

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::Index = Eigen::Index
private

Definition at line 136 of file SymShiftInvert.h.

◆ MapConstVec

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::MapConstVec = Eigen::Map<const Vector>
private

Definition at line 155 of file SymShiftInvert.h.

◆ MapVec

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::MapVec = Eigen::Map<Vector>
private

Definition at line 156 of file SymShiftInvert.h.

◆ MatrixA

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::MatrixA = typename std::conditional<ASparse::value, SparseTypeA, DenseTypeA>::type
private

Definition at line 144 of file SymShiftInvert.h.

◆ MatrixB

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::MatrixB = typename std::conditional<BSparse::value, SparseTypeB, DenseTypeB>::type
private

Definition at line 152 of file SymShiftInvert.h.

◆ ResType

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::ResType = typename std::conditional<ASparse::value && BSparse::value, MatrixA, DenseType>::type
private

Definition at line 163 of file SymShiftInvert.h.

◆ Scalar

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::Scalar = Scalar_

Element type of the matrix.

Definition at line 133 of file SymShiftInvert.h.

◆ SparseTypeA

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::SparseTypeA = Eigen::SparseMatrix<Scalar, FlagsA, StorageIndexA>
private

Definition at line 140 of file SymShiftInvert.h.

◆ SparseTypeB

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::SparseTypeB = Eigen::SparseMatrix<Scalar, FlagsB, StorageIndexB>
private

Definition at line 148 of file SymShiftInvert.h.

◆ Vector

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
using Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::Vector = Eigen::Matrix<Scalar, Eigen::Dynamic, 1>
private

Definition at line 154 of file SymShiftInvert.h.

Constructor & Destructor Documentation

◆ SymShiftInvert()

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
template<typename DerivedA , typename DerivedB >
Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::SymShiftInvert ( const Eigen::EigenBase< DerivedA > &  A,
const Eigen::EigenBase< DerivedB > &  B 
)
inline

Constructor to create the matrix operation object.

Parameters
AA dense or sparse matrix object, whose type can be Eigen::Matrix<...>, Eigen::SparseMatrix<...>, Eigen::Map<Eigen::Matrix<...>>, Eigen::Map<Eigen::SparseMatrix<...>>, Eigen::Ref<Eigen::Matrix<...>>, Eigen::Ref<Eigen::SparseMatrix<...>>, etc.
BA dense or sparse matrix object.

Definition at line 191 of file SymShiftInvert.h.

Member Function Documentation

◆ cols()

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
Index Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::cols ( ) const
inline

Return the number of columns of the underlying matrix.

Definition at line 213 of file SymShiftInvert.h.

◆ perform_op()

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
void Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::perform_op ( const Scalar x_in,
Scalar y_out 
) const
inline

Perform the shift-invert operation $y=(A-\sigma B)^{-1}x$.

Parameters
x_inPointer to the $x$ vector.
y_outPointer to the $y$ vector.

Definition at line 235 of file SymShiftInvert.h.

◆ rows()

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
Index Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::rows ( ) const
inline

Return the number of rows of the underlying matrix.

Definition at line 209 of file SymShiftInvert.h.

◆ set_shift()

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
void Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::set_shift ( const Scalar sigma)
inline

Set the real shift $\sigma$.

Definition at line 218 of file SymShiftInvert.h.

Member Data Documentation

◆ m_matA

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
ConstGenericMatrixA Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::m_matA
private

Definition at line 175 of file SymShiftInvert.h.

◆ m_matB

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
ConstGenericMatrixB Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::m_matB
private

Definition at line 176 of file SymShiftInvert.h.

◆ m_n

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
const Index Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::m_n
private

Definition at line 177 of file SymShiftInvert.h.

◆ m_solver

template<typename Scalar_ , typename TypeA = Eigen::Sparse, typename TypeB = Eigen::Sparse, int UploA = Eigen::Lower, int UploB = Eigen::Lower, int FlagsA = Eigen::ColMajor, int FlagsB = Eigen::ColMajor, typename StorageIndexA = int, typename StorageIndexB = int>
FacType Spectra::SymShiftInvert< Scalar_, TypeA, TypeB, UploA, UploB, FlagsA, FlagsB, StorageIndexA, StorageIndexB >::m_solver
private

Definition at line 178 of file SymShiftInvert.h.


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


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