Public Member Functions | Protected Attributes | List of all members
SparseMatrix Class Reference

Interfaces matrix-vector operations tailored to general sparse matrices. More...

#include <Matrices.hpp>

Inheritance diagram for SparseMatrix:
Inheritance graph
[legend]

Public Member Functions

virtual returnValue addToDiag (real_t alpha)
 
virtual returnValue addToDiag (real_t alpha)
 
long * createDiagInfo ()
 
sparse_int_tcreateDiagInfo ()
 
virtual real_t diag (int i) const
 
virtual real_t diag (int_t i) const
 
virtual Matrixduplicate () const
 
virtual Matrixduplicate () const
 
virtual void free ()
 
virtual void free ()
 
real_tfull () const
 
virtual real_tfull () const
 
virtual returnValue getCol (int cNum, const Indexlist *const irows, real_t alpha, real_t *col) const
 
virtual returnValue getCol (int_t cNum, const Indexlist *const irows, real_t alpha, real_t *col) const
 
virtual real_t getNorm (int_t type=2) const
 
virtual returnValue getRow (int rNum, const Indexlist *const icols, real_t alpha, real_t *row) const
 
virtual returnValue getRow (int_t rNum, const Indexlist *const icols, real_t alpha, real_t *row) const
 
virtual real_t getRowNorm (int_t rNum, int_t type=2) const
 
virtual returnValue getSparseSubmatrix (int_t irowsLength, const int_t *const irowsNumber, int_t icolsLength, const int_t *const icolsNumber, int_t rowoffset, int_t coloffset, int_t &numNonzeros, int_t *irn, int_t *jcn, real_t *avals, BooleanType only_lower_triangular=BT_FALSE) const
 
virtual BooleanType isDiag () const
 
virtual BooleanType isDiag () const
 
virtual returnValue print () const
 
virtual returnValue print (const char *name=0) const
 
 SparseMatrix ()
 
 SparseMatrix (long nr, long nc, long *r, long *c, real_t *v, long *d=0)
 
 SparseMatrix (int nr, int nc, int ld, const real_t *const v)
 
 SparseMatrix ()
 
 SparseMatrix (int_t nr, int_t nc, sparse_int_t *r, sparse_int_t *c, real_t *v)
 
 SparseMatrix (int_t nr, int_t nc, int_t ld, const real_t *const v)
 
virtual returnValue times (int xN, real_t alpha, const real_t *x, int xLD, real_t beta, real_t *y, int yLD) const
 
virtual returnValue times (const Indexlist *const irows, const Indexlist *const icols, int xN, real_t alpha, const real_t *x, int xLD, real_t beta, real_t *y, int yLD, BooleanType yCompr=BT_TRUE) const
 
virtual returnValue times (int_t xN, real_t alpha, const real_t *x, int_t xLD, real_t beta, real_t *y, int_t yLD) const
 
virtual returnValue times (const Indexlist *const irows, const Indexlist *const icols, int_t xN, real_t alpha, const real_t *x, int_t xLD, real_t beta, real_t *y, int_t yLD, BooleanType yCompr=BT_TRUE) const
 
virtual returnValue transTimes (int xN, real_t alpha, const real_t *x, int xLD, real_t beta, real_t *y, int yLD) const
 
virtual returnValue transTimes (const Indexlist *const irows, const Indexlist *const icols, int xN, real_t alpha, const real_t *x, int xLD, real_t beta, real_t *y, int yLD) const
 
virtual returnValue transTimes (int_t xN, real_t alpha, const real_t *x, int_t xLD, real_t beta, real_t *y, int_t yLD) const
 
virtual returnValue transTimes (const Indexlist *const irows, const Indexlist *const icols, int_t xN, real_t alpha, const real_t *x, int_t xLD, real_t beta, real_t *y, int_t yLD) const
 
virtual returnValue writeToFile (FILE *output_file, const char *prefix) const
 
virtual ~SparseMatrix ()
 
virtual ~SparseMatrix ()
 
- Public Member Functions inherited from Matrix
void doFreeMemory ()
 
void doFreeMemory ()
 
void doNotFreeMemory ()
 
void doNotFreeMemory ()
 
virtual returnValue getSparseSubmatrix (const Indexlist *const irows, const Indexlist *const icols, int_t rowoffset, int_t coloffset, int_t &numNonzeros, int_t *irn, int_t *jcn, real_t *avals, BooleanType only_lower_triangular=BT_FALSE) const
 
virtual returnValue getSparseSubmatrix (const Indexlist *const irows, int_t idx_icol, int_t rowoffset, int_t coloffset, int_t &numNonzeros, int_t *irn, int_t *jcn, real_t *avals, BooleanType only_lower_triangular=BT_FALSE) const
 
virtual returnValue getSparseSubmatrix (int_t idx_row, const Indexlist *const icols, int_t rowoffset, int_t coloffset, int_t &numNonzeros, int_t *irn, int_t *jcn, real_t *avals, BooleanType only_lower_triangular=BT_FALSE) const
 
 Matrix ()
 
 Matrix ()
 
BooleanType needToFreeMemory () const
 
BooleanType needToFreeMemory () const
 
virtual ~Matrix ()
 
virtual ~Matrix ()
 

Protected Attributes

long * ir
 
sparse_int_tir
 
long * jc
 
sparse_int_tjc
 
long * jd
 
sparse_int_tjd
 
long nCols
 
int_t nCols
 
long nRows
 
int_t nRows
 
real_tval
 
- Protected Attributes inherited from Matrix
BooleanType freeMemory
 

Detailed Description

Interfaces matrix-vector operations tailored to general sparse matrices.

Sparse matrix class (column compressed format).

Author
Andreas Potschka, Christian Kirches, Hans Joachim Ferreau
Version
3.0beta
Date
2011

Sparse matrix class (col compressed format).

Author
Andreas Potschka, Christian Kirches, Hans Joachim Ferreau
Version
3.2
Date
2011-2015

Definition at line 443 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.

Constructor & Destructor Documentation

SparseMatrix::SparseMatrix ( )

Default constructor.

Definition at line 485 of file qpOASES-3.0beta/src/Matrices.cpp.

SparseMatrix::SparseMatrix ( long  nr,
long  nc,
long *  r,
long *  c,
real_t v,
long *  d = 0 
)

Constructor with arguments.

Parameters
nrNumber of rows.
ncNumber of columns.
rRow indices (length).
cIndices to first entry of columns (nCols+1).
vVector of entries (length).
dIndices to first entry of lower triangle (including diagonal) (nCols).

Definition at line 487 of file qpOASES-3.0beta/src/Matrices.cpp.

SparseMatrix::SparseMatrix ( int  nr,
int  nc,
int  ld,
const real_t *const  v 
)

Constructor from dense matrix.

Parameters
nrNumber of rows.
ncNumber of columns.
ldLeading dimension.
vRow major stored matrix elements.

Definition at line 490 of file qpOASES-3.0beta/src/Matrices.cpp.

SparseMatrix::~SparseMatrix ( )
virtual

Destructor.

Definition at line 514 of file qpOASES-3.0beta/src/Matrices.cpp.

SparseMatrix::SparseMatrix ( )

Default constructor.

SparseMatrix::SparseMatrix ( int_t  nr,
int_t  nc,
sparse_int_t r,
sparse_int_t c,
real_t v 
)

Constructor with arguments.

Parameters
nrNumber of rows.
ncNumber of columns.
rRow indices (length).
cIndices to first entry of columns (nCols+1).
vVector of entries (length).

Definition at line 662 of file qpOASES-3.2.0/src/Matrices.cpp.

SparseMatrix::SparseMatrix ( int_t  nr,
int_t  nc,
int_t  ld,
const real_t *const  v 
)

Constructor from dense matrix.

Parameters
nrNumber of rows.
ncNumber of columns.
ldLeading dimension.
vRow major stored matrix elements.
virtual SparseMatrix::~SparseMatrix ( )
virtual

Destructor.

Member Function Documentation

returnValue SparseMatrix::addToDiag ( real_t  alpha)
virtual

Adds given offset to diagonal of matrix.

Returns
SUCCESSFUL_RETURN
RET_NO_DIAGONAL_AVAILABLE
Parameters
alphaDiagonal offset.

Implements Matrix.

Definition at line 1031 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual returnValue SparseMatrix::addToDiag ( real_t  alpha)
virtual

Adds given offset to diagonal of matrix.

Returns
SUCCESSFUL_RETURN
RET_NO_DIAGONAL_AVAILABLE
Parameters
alphaDiagonal offset.

Implements Matrix.

sparse_int_t * SparseMatrix::createDiagInfo ( )

Create jd field from ir and jc.

Returns
Pointer to jd.

Definition at line 1045 of file qpOASES-3.0beta/src/Matrices.cpp.

sparse_int_t* SparseMatrix::createDiagInfo ( )

Create jd field from ir and jc.

Returns
Pointer to jd.
real_t SparseMatrix::diag ( int  i) const
virtual

Returns i-th diagonal entry.

Returns
i-th diagonal entry
Parameters
iIndex.

Implements Matrix.

Definition at line 555 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual real_t SparseMatrix::diag ( int_t  i) const
virtual

Returns i-th diagonal entry.

Returns
i-th diagonal entry (or INFTY if diagonal does not exist)
Parameters
iIndex.

Implements Matrix.

Matrix * SparseMatrix::duplicate ( ) const
virtual

Returns a deep-copy of the Matrix object.

Returns
Deep-copy of Matrix object

Implements Matrix.

Reimplemented in SymSparseMat, and SymSparseMat.

Definition at line 533 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual Matrix* SparseMatrix::duplicate ( ) const
virtual

Returns a deep-copy of the Matrix object.

Returns
Deep-copy of Matrix object

Implements Matrix.

Reimplemented in SymSparseMat, and SymSparseMat.

void SparseMatrix::free ( )
virtual

Frees all internal memory.

Implements Matrix.

Definition at line 520 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual void SparseMatrix::free ( )
virtual

Frees all internal memory.

Implements Matrix.

real_t * SparseMatrix::full ( ) const
virtual

Allocate and create dense matrix in row major format.

Returns
Pointer to matrix array.

Implements Matrix.

Definition at line 1062 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual real_t* SparseMatrix::full ( ) const
virtual

Allocates and creates dense matrix array in row major format.

Note: Calling function has to free allocated memory!

Returns
Pointer to matrix array.

Implements Matrix.

returnValue SparseMatrix::getCol ( int  cNum,
const Indexlist *const  irows,
real_t  alpha,
real_t col 
) const
virtual

Retrieve indexed entries of matrix column multiplied by alpha.

Parameters
cNumColumn number.
irowsIndex list specifying rows.
alphaScalar factor.
colOutput column vector.

Implements Matrix.

Definition at line 618 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual returnValue SparseMatrix::getCol ( int_t  cNum,
const Indexlist *const  irows,
real_t  alpha,
real_t col 
) const
virtual

Retrieve indexed entries of matrix column multiplied by alpha.

Parameters
cNumColumn number.
irowsIndex list specifying rows.
alphaScalar factor.
colOutput column vector.

Implements Matrix.

real_t SparseMatrix::getNorm ( int_t  type = 2) const
virtual

Get the N-norm of the matrix

Returns
N-norm of the matrix
Parameters
typeNorm type, 1: one-norm, 2: Euclidean norm.

Implements Matrix.

Definition at line 780 of file qpOASES-3.2.0/src/Matrices.cpp.

returnValue SparseMatrix::getRow ( int  rNum,
const Indexlist *const  icols,
real_t  alpha,
real_t row 
) const
virtual

Retrieve indexed entries of matrix row multiplied by alpha.

Parameters
rNumRow number.
icolsIndex list specifying columns.
alphaScalar factor.
rowOutput row vector.

Implements Matrix.

Definition at line 566 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual returnValue SparseMatrix::getRow ( int_t  rNum,
const Indexlist *const  icols,
real_t  alpha,
real_t row 
) const
virtual

Retrieve indexed entries of matrix row multiplied by alpha.

Parameters
rNumRow number.
icolsIndex list specifying columns.
alphaScalar factor.
rowOutput row vector.

Implements Matrix.

real_t SparseMatrix::getRowNorm ( int_t  rNum,
int_t  type = 2 
) const
virtual

Get the N-norm of a row

Returns
N-norm of row rNum
Parameters
rNumRow number.
typeNorm type, 1: one-norm, 2: Euclidean norm.

Implements Matrix.

Definition at line 788 of file qpOASES-3.2.0/src/Matrices.cpp.

returnValue SparseMatrix::getSparseSubmatrix ( int_t  irowsLength,
const int_t *const  irowsNumber,
int_t  icolsLength,
const int_t *const  icolsNumber,
int_t  rowoffset,
int_t  coloffset,
int_t numNonzeros,
int_t irn,
int_t jcn,
real_t avals,
BooleanType  only_lower_triangular = BT_FALSE 
) const
virtual

Retrieve entries of submatrix in Harwell-Boeing sparse format. If irn, jcn, and avals are null, this only counts the number of nonzeros. Otherwise, numNonzeros containts the size of irn, jcn, and avals on entry, and the written number of entries on return.

Returns
SUCCESSFUL_RETURN
Parameters
irowsLengthNumber of rows.
irowsNumberArray with row numbers.
icolsLengthNumber of columns.
icolsNumberArray with column numbers.
rowoffsetOffset for row entries.
coloffsetOffset for row entries.
numNonzerosNumber of nonzeros in submatrix.
irnRow position of entries (as position in irows) plus rowoffset.
jcnColumn position of entries (as position in irows) plus coloffset.
avalsNumerical values of the entries.
only_lower_triangularif true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols.

Implements Matrix.

Definition at line 907 of file qpOASES-3.2.0/src/Matrices.cpp.

BooleanType SparseMatrix::isDiag ( ) const
virtual

Checks whether matrix is square and diagonal.

Returns
BT_TRUE iff matrix is square and diagonal;
BT_FALSE otherwise.

Implements Matrix.

Definition at line 561 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual BooleanType SparseMatrix::isDiag ( ) const
virtual

Checks whether matrix is square and diagonal.

Returns
BT_TRUE iff matrix is square and diagonal;
BT_FALSE otherwise.

Implements Matrix.

returnValue SparseMatrix::print ( ) const
virtual

Prints matrix to screen.

Returns
RET_NOT_YET_IMPLEMENTED

Implements Matrix.

Definition at line 1078 of file qpOASES-3.0beta/src/Matrices.cpp.

returnValue SparseMatrix::print ( const char *  name = 0) const
virtual

Prints matrix to screen.

Returns
SUCCESSFUL_RETURN
Parameters
nameName of matrix.

Implements Matrix.

Definition at line 1349 of file qpOASES-3.2.0/src/Matrices.cpp.

returnValue SparseMatrix::times ( int  xN,
real_t  alpha,
const real_t x,
int  xLD,
real_t  beta,
real_t y,
int  yLD 
) const
virtual

Evaluate Y=alpha*A*X + beta*Y.

Parameters
xNNumber of vectors to multiply.
alphaScalar factor for matrix vector product.
xInput vector to be multiplied.
xLDLeading dimension of input x.
betaScalar factor for y.
yOutput vector of results.
yLDLeading dimension of output y.

Implements Matrix.

Definition at line 656 of file qpOASES-3.0beta/src/Matrices.cpp.

returnValue SparseMatrix::times ( const Indexlist *const  irows,
const Indexlist *const  icols,
int  xN,
real_t  alpha,
const real_t x,
int  xLD,
real_t  beta,
real_t y,
int  yLD,
BooleanType  yCompr = BT_TRUE 
) const
virtual

Evaluate matrix vector product with submatrix given by Indexlist.

Parameters
irowsIndex list specifying rows.
icolsIndex list specifying columns.
xNNumber of vectors to multiply.
alphaScalar factor for matrix vector product.
xInput vector to be multiplied.
xLDLeading dimension of input x.
betaScalar factor for y.
yOutput vector of results.
yLDLeading dimension of output y.
yComprCompressed storage for y.

Implements Matrix.

Definition at line 730 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual returnValue SparseMatrix::times ( int_t  xN,
real_t  alpha,
const real_t x,
int_t  xLD,
real_t  beta,
real_t y,
int_t  yLD 
) const
virtual

Evaluate Y=alpha*A*X + beta*Y.

Parameters
xNNumber of vectors to multiply.
alphaScalar factor for matrix vector product.
xInput vector to be multiplied.
xLDLeading dimension of input x.
betaScalar factor for y.
yOutput vector of results.
yLDLeading dimension of output y.

Implements Matrix.

virtual returnValue SparseMatrix::times ( const Indexlist *const  irows,
const Indexlist *const  icols,
int_t  xN,
real_t  alpha,
const real_t x,
int_t  xLD,
real_t  beta,
real_t y,
int_t  yLD,
BooleanType  yCompr = BT_TRUE 
) const
virtual

Evaluate matrix vector product with submatrix given by Indexlist.

Parameters
irowsIndex list specifying rows.
icolsIndex list specifying columns.
xNNumber of vectors to multiply.
alphaScalar factor for matrix vector product.
xInput vector to be multiplied.
xLDLeading dimension of input x.
betaScalar factor for y.
yOutput vector of results.
yLDLeading dimension of output y.
yComprCompressed storage for y.

Implements Matrix.

returnValue SparseMatrix::transTimes ( int  xN,
real_t  alpha,
const real_t x,
int  xLD,
real_t  beta,
real_t y,
int  yLD 
) const
virtual

Evaluate Y=alpha*A'*X + beta*Y.

Parameters
xNNumber of vectors to multiply.
alphaScalar factor for matrix vector product.
xInput vector to be multiplied.
xLDLeading dimension of input x.
betaScalar factor for y.
yOutput vector of results.
yLDLeading dimension of output y.

Implements Matrix.

Definition at line 693 of file qpOASES-3.0beta/src/Matrices.cpp.

returnValue SparseMatrix::transTimes ( const Indexlist *const  irows,
const Indexlist *const  icols,
int  xN,
real_t  alpha,
const real_t x,
int  xLD,
real_t  beta,
real_t y,
int  yLD 
) const
virtual

Evaluate matrix transpose vector product.

Parameters
irowsIndex list specifying rows.
icolsIndex list specifying columns.
xNNumber of vectors to multiply.
alphaScalar factor for matrix vector product.
xInput vector to be multiplied.
xLDLeading dimension of input x.
betaScalar factor for y.
yOutput vector of results.
yLDLeading dimension of output y.

Implements Matrix.

Definition at line 961 of file qpOASES-3.0beta/src/Matrices.cpp.

virtual returnValue SparseMatrix::transTimes ( int_t  xN,
real_t  alpha,
const real_t x,
int_t  xLD,
real_t  beta,
real_t y,
int_t  yLD 
) const
virtual

Evaluate Y=alpha*A'*X + beta*Y.

Parameters
xNNumber of vectors to multiply.
alphaScalar factor for matrix vector product.
xInput vector to be multiplied.
xLDLeading dimension of input x.
betaScalar factor for y.
yOutput vector of results.
yLDLeading dimension of output y.

Implements Matrix.

virtual returnValue SparseMatrix::transTimes ( const Indexlist *const  irows,
const Indexlist *const  icols,
int_t  xN,
real_t  alpha,
const real_t x,
int_t  xLD,
real_t  beta,
real_t y,
int_t  yLD 
) const
virtual

Evaluate matrix transpose vector product.

Parameters
irowsIndex list specifying rows.
icolsIndex list specifying columns.
xNNumber of vectors to multiply.
alphaScalar factor for matrix vector product.
xInput vector to be multiplied.
xLDLeading dimension of input x.
betaScalar factor for y.
yOutput vector of results.
yLDLeading dimension of output y.

Implements Matrix.

returnValue SparseMatrix::writeToFile ( FILE *  output_file,
const char *  prefix 
) const
virtual

Write matrix to file.

Returns
SUCCESSFUL_RETURN

Implements Matrix.

Definition at line 1358 of file qpOASES-3.2.0/src/Matrices.cpp.

Member Data Documentation

long* SparseMatrix::ir
protected

Row indices (length).

Definition at line 570 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.

sparse_int_t* SparseMatrix::ir
protected

Row indices (length).

Definition at line 766 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.

long* SparseMatrix::jc
protected

Indices to first entry of columns (nCols+1).

Definition at line 571 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.

sparse_int_t* SparseMatrix::jc
protected

Indices to first entry of columns (nCols+1).

Definition at line 767 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.

long* SparseMatrix::jd
protected

Indices to first entry of lower triangle (including diagonal) (nCols).

Definition at line 572 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.

sparse_int_t* SparseMatrix::jd
protected

Indices to first entry of lower triangle (including diagonal) (nCols).

Definition at line 768 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.

long SparseMatrix::nCols
protected

Number of columns.

Definition at line 569 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.

int_t SparseMatrix::nCols
protected

Number of columns.

Definition at line 765 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.

long SparseMatrix::nRows
protected

Number of rows.

Definition at line 568 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.

int_t SparseMatrix::nRows
protected

Number of rows.

Definition at line 764 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.

real_t * SparseMatrix::val
protected

Vector of entries (length).

Definition at line 573 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.


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


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Mon Jun 10 2019 12:35:26