Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | Friends | List of all members
gnsstk::SparseVector< T > Class Template Reference

Detailed Description

template<class T>
class gnsstk::SparseVector< T >

forward declarations

Class SparseVector. This class is designed to present an interface nearly identical to class Vector, but more efficiently handle sparse vectors, in which most of the elements are zero. The class stores only non-zero elements in a map with key = index; it also stores a nominal length. The class uses a proxy class, SVecProxy, to access elements; this allows rvalues and lvalues to be treated separately.

Definition at line 60 of file SparseVector.hpp.

#include <SparseVector.hpp>

Public Member Functions

void addScaledSparseVector (const T &a, const SparseVector< T > &SV)
 
void clear ()
 clear - set all data to 0 (i.e. remove all data); leave length alone More...
 
unsigned int datasize () const
 datasize - number of non-zero data More...
 
double density () const
 density - ratio of number of non-zero element to size() More...
 
std::string dump (const int p=3, bool dosci=false) const
 Dump only non-zero values, with indexes (i,value) More...
 
bool isEmpty () const
 is this SV empty? NB may have to call zeroize() to get a yes. More...
 
bool isFilled (const unsigned int i) const
 true if the element is non-zero More...
 
 operator Vector< T > () const
 cast to Vector or implicit conversion to Matrix<T> More...
 
SparseVector< T > & operator*= (const T &value)
 
SparseVector< T > & operator+= (const SparseVector< T > &SV)
 
SparseVector< T > & operator+= (const Vector< T > &SV)
 
SparseVector< T > operator- () const
 
SparseVector< T > & operator-= (const SparseVector< T > &SV)
 
SparseVector< T > & operator-= (const Vector< T > &SV)
 
SparseVector< T > & operator/= (const T &value)
 
SVecProxy< T > operator[] (unsigned int in)
 operator[] for non-const, but SVecProxy does all the work More...
 
const SVecProxy< T > operator[] (unsigned int in) const
 operator[] for const, but SVecProxy does all the work More...
 
void resize (const unsigned int newlen)
 resize - remove elements (truncate) and change nominal length len More...
 
unsigned int size () const
 size - of the real Vector, not the data array More...
 
 SparseVector ()
 empty constructor More...
 
 SparseVector (const SparseVector< T > &SV, const unsigned int &ind, const unsigned int &len)
 
 SparseVector (const unsigned int N)
 constructor with length More...
 
 SparseVector (const Vector< T > &V)
 constructor from regular Vector<T> More...
 
sum (const SparseVector< T > &SV) const
 Sum of elements. More...
 
void truncate (const unsigned int n)
 
void zeroize (const T tol=static_cast< T >(zeroTolerance))
 

Static Public Attributes

static const double zeroTolerance = 1.0e-14
 

Private Member Functions

std::vector< unsigned int > getIndexes () const
 

Private Attributes

unsigned int len
 
std::map< unsigned int, T > vecMap
 map of index,value pairs; vecMap[index in real vector] = data element More...
 

Friends

cosVec (const SparseVector< T > &S1, const SparseVector< T > &S2)
 
cosVec (const SparseVector< T > &SV, const Vector< T > &V)
 
cosVec (const Vector< T > &V, const SparseVector< T > &SV)
 
dot (const SparseVector< T > &SL, const SparseVector< T > &SR)
 dot (SparseVector, SparseVector) More...
 
dot (const SparseVector< T > &SL, const Vector< T > &SR)
 dot (SparseVector, Vector) More...
 
dot (const Vector< T > &SL, const SparseVector< T > &SR)
 dot (Vector, SparseVector) More...
 
dot_lim (const SparseVector< T > &SL, const SparseVector< T > &SR, const unsigned int kb, const unsigned int ke)
 dot (SparseVector, SparseVector) but only use indexes k=kb, k<ke More...
 
SparseMatrix< T > identSparse (const unsigned int dim)
 
SparseMatrix< T > inverse (const SparseMatrix< T > &A)
 
SparseMatrix< T > inverseLT (const SparseMatrix< T > &LT, T *ptrSmall, T *ptrBig)
 Compute inverse of lower-triangular SparseMatrix. More...
 
SparseMatrix< T > lowerCholesky (const SparseMatrix< T > &A)
 
max (const SparseVector< T > &SV)
 
maxabs (const SparseVector< T > &SV)
 
min (const SparseVector< T > &SV)
 
minabs (const SparseVector< T > &SV)
 
norm (const SparseVector< T > &SV)
 
std::ostream & operator (std::ostream &os, const SparseVector< T > &S)
 lots of friends More...
 
SparseMatrix< T > operator* (const Matrix< T > &L, const SparseMatrix< T > &R)
 Matrix multiply: SparseMatrix = Matrix * SparseMatrix. More...
 
SparseMatrix< T > operator* (const SparseMatrix< T > &L, const Matrix< T > &R)
 Matrix multiply: SparseMatrix = SparseMatrix * Matrix. More...
 
SparseMatrix< T > operator* (const SparseMatrix< T > &L, const SparseMatrix< T > &V)
 Matrix multiply: SparseMatrix = SparseMatrix * SparseMatrix. More...
 
SparseVector< T > operator* (const SparseMatrix< T > &L, const SparseVector< T > &V)
 Matrix,Vector multiply: SparseVector = SparseMatrix * SparseVector. More...
 
SparseVector< T > operator* (const SparseMatrix< T > &L, const Vector< T > &V)
 Matrix,Vector multiply: SparseVector = SparseMatrix * Vector. More...
 
SparseVector< T > operator+ (const SparseVector< T > &L, const SparseVector< T > &R)
 
SparseVector< T > operator+ (const SparseVector< T > &L, const Vector< T > &R)
 
SparseVector< T > operator+ (const Vector< T > &L, const SparseVector< T > &R)
 
SparseVector< T > operator- (const SparseVector< T > &L, const SparseVector< T > &R)
 
SparseVector< T > operator- (const SparseVector< T > &L, const Vector< T > &R)
 
SparseVector< T > operator- (const Vector< T > &L, const SparseVector< T > &R)
 
SparseMatrix< T > operator|| (const SparseMatrix< T > &L, const SparseMatrix< T > &R)
 
SparseMatrix< T > operator|| (const SparseMatrix< T > &L, const Vector< T > &V)
 Concatenation SparseMatrix || Vector TD the rest of them... More...
 
SparseMatrix< T > SparseHouseholder (const SparseMatrix< T > &A)
 Householder transformation of a matrix. More...
 
class SparseMatrix< T >
 
void SrifMU (Matrix< T > &R, Vector< T > &Z, SparseMatrix< T > &A, const unsigned int M)
 
void SrifMU (Matrix< T > &R, Vector< T > &Z, SparseMatrix< T > &P, Vector< T > &D, const unsigned int M)
 
class SVecProxy< T >
 Proxy needs access to vecMap. More...
 
SparseMatrix< T > transform (const SparseMatrix< T > &M, const SparseMatrix< T > &C)
 
Vector< T > transformDiag (const SparseMatrix< T > &P, const Matrix< T > &C)
 Compute diagonal of P*C*P^T, ie diagonal of transform of square Matrix C. More...
 
SparseMatrix< T > transpose (const SparseMatrix< T > &M)
 transpose More...
 

Constructor & Destructor Documentation

◆ SparseVector() [1/4]

template<class T >
gnsstk::SparseVector< T >::SparseVector ( )
inline

empty constructor

Definition at line 348 of file SparseVector.hpp.

◆ SparseVector() [2/4]

template<class T >
gnsstk::SparseVector< T >::SparseVector ( const unsigned int  N)
inline

constructor with length

Definition at line 351 of file SparseVector.hpp.

◆ SparseVector() [3/4]

template<class T >
gnsstk::SparseVector< T >::SparseVector ( const Vector< T > &  V)

constructor from regular Vector<T>

Definition at line 592 of file SparseVector.hpp.

◆ SparseVector() [4/4]

template<class T >
gnsstk::SparseVector< T >::SparseVector ( const SparseVector< T > &  SV,
const unsigned int &  ind,
const unsigned int &  len 
)

subvector constructor

Parameters
SVSparseVector to copy
indstarting index for the copy
lenlength of new SparseVector

Definition at line 611 of file SparseVector.hpp.

Member Function Documentation

◆ addScaledSparseVector()

template<class T >
void gnsstk::SparseVector< T >::addScaledSparseVector ( const T &  a,
const SparseVector< T > &  SV 
)

Definition at line 1061 of file SparseVector.hpp.

◆ clear()

template<class T >
void gnsstk::SparseVector< T >::clear ( )
inline

clear - set all data to 0 (i.e. remove all data); leave length alone

Definition at line 415 of file SparseVector.hpp.

◆ datasize()

template<class T >
unsigned int gnsstk::SparseVector< T >::datasize ( ) const
inline

datasize - number of non-zero data

Definition at line 374 of file SparseVector.hpp.

◆ density()

template<class T >
double gnsstk::SparseVector< T >::density ( ) const
inline

density - ratio of number of non-zero element to size()

Definition at line 383 of file SparseVector.hpp.

◆ dump()

template<class T >
std::string gnsstk::SparseVector< T >::dump ( const int  p = 3,
bool  dosci = false 
) const
inline

Dump only non-zero values, with indexes (i,value)

Definition at line 458 of file SparseVector.hpp.

◆ getIndexes()

template<class T >
std::vector<unsigned int> gnsstk::SparseVector< T >::getIndexes ( ) const
inlineprivate

return a vector containing all the indexes, in order, of non-zero elements.

Definition at line 518 of file SparseVector.hpp.

◆ isEmpty()

template<class T >
bool gnsstk::SparseVector< T >::isEmpty ( ) const
inline

is this SV empty? NB may have to call zeroize() to get a yes.

Definition at line 377 of file SparseVector.hpp.

◆ isFilled()

template<class T >
bool gnsstk::SparseVector< T >::isFilled ( const unsigned int  i) const
inline

true if the element is non-zero

Definition at line 426 of file SparseVector.hpp.

◆ operator Vector< T >()

template<class T >
gnsstk::SparseVector< T >::operator Vector< T >

cast to Vector or implicit conversion to Matrix<T>

Definition at line 640 of file SparseVector.hpp.

◆ operator*=()

template<class T >
SparseVector< T > & gnsstk::SparseVector< T >::operator*= ( const T &  value)

Definition at line 1095 of file SparseVector.hpp.

◆ operator+=() [1/2]

template<class T >
SparseVector< T > & gnsstk::SparseVector< T >::operator+= ( const SparseVector< T > &  SV)

Definition at line 1004 of file SparseVector.hpp.

◆ operator+=() [2/2]

template<class T >
SparseVector< T > & gnsstk::SparseVector< T >::operator+= ( const Vector< T > &  SV)

Definition at line 1030 of file SparseVector.hpp.

◆ operator-()

template<class T >
SparseVector<T> gnsstk::SparseVector< T >::operator- ( ) const
inline

Definition at line 492 of file SparseVector.hpp.

◆ operator-=() [1/2]

template<class T >
SparseVector< T > & gnsstk::SparseVector< T >::operator-= ( const SparseVector< T > &  SV)

Definition at line 948 of file SparseVector.hpp.

◆ operator-=() [2/2]

template<class T >
SparseVector< T > & gnsstk::SparseVector< T >::operator-= ( const Vector< T > &  SV)

Definition at line 974 of file SparseVector.hpp.

◆ operator/=()

template<class T >
SparseVector< T > & gnsstk::SparseVector< T >::operator/= ( const T &  value)

Definition at line 1115 of file SparseVector.hpp.

◆ operator[]() [1/2]

template<class T >
SVecProxy<T> gnsstk::SparseVector< T >::operator[] ( unsigned int  in)
inline

operator[] for non-const, but SVecProxy does all the work

Definition at line 445 of file SparseVector.hpp.

◆ operator[]() [2/2]

template<class T >
const SVecProxy<T> gnsstk::SparseVector< T >::operator[] ( unsigned int  in) const
inline

operator[] for const, but SVecProxy does all the work

Definition at line 433 of file SparseVector.hpp.

◆ resize()

template<class T >
void gnsstk::SparseVector< T >::resize ( const unsigned int  newlen)
inline

resize - remove elements (truncate) and change nominal length len

Definition at line 408 of file SparseVector.hpp.

◆ size()

template<class T >
unsigned int gnsstk::SparseVector< T >::size ( ) const
inline

size - of the real Vector, not the data array

Definition at line 371 of file SparseVector.hpp.

◆ sum()

template<class T >
T gnsstk::SparseVector< T >::sum ( const SparseVector< T > &  SV) const
inline

Sum of elements.

Definition at line 472 of file SparseVector.hpp.

◆ truncate()

template<class T >
void gnsstk::SparseVector< T >::truncate ( const unsigned int  n)
inline

truncate - removes elements, if necessary, at and beyond column index j same as resize(n) but does not change the nominal length len.

Definition at line 392 of file SparseVector.hpp.

◆ zeroize()

template<class T >
void gnsstk::SparseVector< T >::zeroize ( const tol = static_cast<T>(zeroTolerance))

zeroize - remove elements that are less than or equal to tolerance in abs value. Called with a non-zero tolerance only by the user. NB this class and SparseMatrix call this when constructing a new object, e.g. after matrix multiply, but ONLY with the tolerance T(0).

Definition at line 656 of file SparseVector.hpp.

Friends And Related Function Documentation

◆ cosVec [1/3]

template<class T >
T cosVec ( const SparseVector< T > &  S1,
const SparseVector< T > &  S2 
)
friend

Definition at line 736 of file SparseVector.hpp.

◆ cosVec [2/3]

template<class T >
T cosVec ( const SparseVector< T > &  SV,
const Vector< T > &  V 
)
friend

Definition at line 758 of file SparseVector.hpp.

◆ cosVec [3/3]

template<class T >
T cosVec ( const Vector< T > &  V,
const SparseVector< T > &  SV 
)
friend

Definition at line 780 of file SparseVector.hpp.

◆ dot [1/3]

template<class T >
T dot ( const SparseVector< T > &  SL,
const SparseVector< T > &  SR 
)
friend

dot (SparseVector, SparseVector)

Definition at line 789 of file SparseVector.hpp.

◆ dot [2/3]

template<class T >
T dot ( const SparseVector< T > &  SL,
const Vector< T > &  SR 
)
friend

dot (SparseVector, Vector)

Definition at line 858 of file SparseVector.hpp.

◆ dot [3/3]

template<class T >
T dot ( const Vector< T > &  SL,
const SparseVector< T > &  SR 
)
friend

dot (Vector, SparseVector)

Definition at line 874 of file SparseVector.hpp.

◆ dot_lim

template<class T >
T dot_lim ( const SparseVector< T > &  SL,
const SparseVector< T > &  SR,
const unsigned int  kb,
const unsigned int  ke 
)
friend

dot (SparseVector, SparseVector) but only use indexes k=kb, k<ke

Definition at line 820 of file SparseVector.hpp.

◆ identSparse

template<class T >
SparseMatrix<T> identSparse ( const unsigned int  dim)
friend

Compute the identity matrix of dimension dim x dim

Parameters
dimdimension of desired identity matrix (dim x dim)
Returns
identity matrix

Definition at line 1776 of file SparseMatrix.hpp.

◆ inverse

template<class T >
SparseMatrix<T> inverse ( const SparseMatrix< T > &  A)
friend

inverse (via Gauss-Jordan)

Exceptions
Exceptioninverse via Gauss-Jordan; NB GJ involves only row operations. NB not the best numerically; for high condition number, use inverseViaCholesky, or cast to Matrix, use either LUD or SVD, then cast back to SparseMatrix.
Exception

Definition at line 1890 of file SparseMatrix.hpp.

◆ inverseLT

template<class T >
SparseMatrix<T> inverseLT ( const SparseMatrix< T > &  LT,
T *  ptrSmall,
T *  ptrBig 
)
friend

Compute inverse of lower-triangular SparseMatrix.

inverseLT

Exceptions
Exception
Exception

Definition at line 2154 of file SparseMatrix.hpp.

◆ lowerCholesky

template<class T >
SparseMatrix<T> lowerCholesky ( const SparseMatrix< T > &  A)
friend

Cholesky

Exceptions
ExceptionCompute lower triangular square root of a symmetric positive definite matrix (Cholesky decomposition) Crout algorithm.
Parameters
ASparseMatrix to be decomposed; symmetric and positive definite, const
Returns
SparseMatrix lower triangular square root of input matrix
Exceptions
ifinput SparseMatrix is not square
ifinput SparseMatrix is not positive definite
Exception

Definition at line 2065 of file SparseMatrix.hpp.

◆ max

template<class T >
T max ( const SparseVector< T > &  SV)
friend

Definition at line 895 of file SparseVector.hpp.

◆ maxabs

template<class T >
T maxabs ( const SparseVector< T > &  SV)
friend

Definition at line 927 of file SparseVector.hpp.

◆ min

template<class T >
T min ( const SparseVector< T > &  SV)
friend

Definition at line 879 of file SparseVector.hpp.

◆ minabs

template<class T >
T minabs ( const SparseVector< T > &  SV)
friend

Definition at line 911 of file SparseVector.hpp.

◆ norm

template<class T >
T norm ( const SparseVector< T > &  SV)
friend

Definition at line 705 of file SparseVector.hpp.

◆ operator

template<class T >
std::ostream& operator ( std::ostream &  os,
const SparseVector< T > &  S 
)
friend

lots of friends

◆ operator* [1/5]

template<class T >
SparseMatrix<T> operator* ( const Matrix< T > &  L,
const SparseMatrix< T > &  R 
)
friend

Matrix multiply: SparseMatrix = Matrix * SparseMatrix.

Definition at line 1270 of file SparseMatrix.hpp.

◆ operator* [2/5]

template<class T >
SparseMatrix<T> operator* ( const SparseMatrix< T > &  L,
const Matrix< T > &  R 
)
friend

Matrix multiply: SparseMatrix = SparseMatrix * Matrix.

Definition at line 1225 of file SparseMatrix.hpp.

◆ operator* [3/5]

template<class T >
SparseMatrix<T> operator* ( const SparseMatrix< T > &  L,
const SparseMatrix< T > &  V 
)
friend

Matrix multiply: SparseMatrix = SparseMatrix * SparseMatrix.

Definition at line 1186 of file SparseMatrix.hpp.

◆ operator* [4/5]

template<class T >
SparseVector<T> operator* ( const SparseMatrix< T > &  L,
const SparseVector< T > &  V 
)
friend

Matrix,Vector multiply: SparseVector = SparseMatrix * SparseVector.

Definition at line 996 of file SparseMatrix.hpp.

◆ operator* [5/5]

template<class T >
SparseVector<T> operator* ( const SparseMatrix< T > &  L,
const Vector< T > &  V 
)
friend

Matrix,Vector multiply: SparseVector = SparseMatrix * Vector.

Definition at line 1056 of file SparseMatrix.hpp.

◆ operator+ [1/3]

template<class T >
SparseVector<T> operator+ ( const SparseVector< T > &  L,
const SparseVector< T > &  R 
)
friend

Definition at line 1182 of file SparseVector.hpp.

◆ operator+ [2/3]

template<class T >
SparseVector<T> operator+ ( const SparseVector< T > &  L,
const Vector< T > &  R 
)
friend

Definition at line 1198 of file SparseVector.hpp.

◆ operator+ [3/3]

template<class T >
SparseVector<T> operator+ ( const Vector< T > &  L,
const SparseVector< T > &  R 
)
friend

Definition at line 1214 of file SparseVector.hpp.

◆ operator- [1/3]

template<class T >
SparseVector<T> operator- ( const SparseVector< T > &  L,
const SparseVector< T > &  R 
)
friend

Definition at line 1133 of file SparseVector.hpp.

◆ operator- [2/3]

template<class T >
SparseVector<T> operator- ( const SparseVector< T > &  L,
const Vector< T > &  R 
)
friend

Definition at line 1149 of file SparseVector.hpp.

◆ operator- [3/3]

template<class T >
SparseVector<T> operator- ( const Vector< T > &  L,
const SparseVector< T > &  R 
)
friend

Definition at line 1165 of file SparseVector.hpp.

◆ operator|| [1/2]

template<class T >
SparseMatrix<T> operator|| ( const SparseMatrix< T > &  L,
const SparseMatrix< T > &  R 
)
friend

Definition at line 1343 of file SparseMatrix.hpp.

◆ operator|| [2/2]

template<class T >
SparseMatrix<T> operator|| ( const SparseMatrix< T > &  L,
const Vector< T > &  V 
)
friend

Concatenation SparseMatrix || Vector TD the rest of them...

Definition at line 1313 of file SparseMatrix.hpp.

◆ SparseHouseholder

template<class T >
SparseMatrix<T> SparseHouseholder ( const SparseMatrix< T > &  A)
friend

Householder transformation of a matrix.

Householder

Exceptions
Exception

Definition at line 2297 of file SparseMatrix.hpp.

◆ SparseMatrix< T >

template<class T >
friend class SparseMatrix< T >
friend

Definition at line 273 of file SparseVector.hpp.

◆ SrifMU [1/2]

template<class T >
void SrifMU ( Matrix< T > &  R,
Vector< T > &  Z,
SparseMatrix< T > &  A,
const unsigned int  M 
)
friend
Exceptions
ExceptionSquare root information measurement update, with new data in the form of a single SparseMatrix concatenation of H and D: A = H || D. See doc for the overloaded SrifMU().

Definition at line 2467 of file SparseMatrix.hpp.

◆ SrifMU [2/2]

template<class T >
void SrifMU ( Matrix< T > &  R,
Vector< T > &  Z,
SparseMatrix< T > &  P,
Vector< T > &  D,
const unsigned int  M 
)
friend
Exceptions
Exception

Definition at line 2627 of file SparseMatrix.hpp.

◆ SVecProxy< T >

template<class T >
friend class SVecProxy< T >
friend

Proxy needs access to vecMap.

Definition at line 272 of file SparseVector.hpp.

◆ transform

template<class T >
SparseMatrix<T> transform ( const SparseMatrix< T > &  M,
const SparseMatrix< T > &  C 
)
friend
Exceptions
Exception

◆ transformDiag

template<class T >
Vector<T> transformDiag ( const SparseMatrix< T > &  P,
const Matrix< T > &  C 
)
friend

Compute diagonal of P*C*P^T, ie diagonal of transform of square Matrix C.

diag of P * C * PT

Exceptions
Exception

Definition at line 1836 of file SparseMatrix.hpp.

◆ transpose

template<class T >
SparseMatrix<T> transpose ( const SparseMatrix< T > &  M)
friend

transpose

Definition at line 829 of file SparseMatrix.hpp.

Member Data Documentation

◆ len

template<class T >
unsigned int gnsstk::SparseVector< T >::len
private

length of the "real" vector (not the number of data stored = vecMap.size())

Definition at line 509 of file SparseVector.hpp.

◆ vecMap

template<class T >
std::map<unsigned int, T> gnsstk::SparseVector< T >::vecMap
private

map of index,value pairs; vecMap[index in real vector] = data element

Definition at line 512 of file SparseVector.hpp.

◆ zeroTolerance

template<class T >
const double gnsstk::SparseVector< T >::zeroTolerance = 1.0e-14
static

tolerance in considering element to be zero is std::abs(elem) < tolerance see zeroize(), where this is the default input value

Definition at line 345 of file SparseVector.hpp.


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


gnsstk
Author(s):
autogenerated on Wed Oct 25 2023 02:40:46