Abstract base class for interfacing tailored matrix-vector operations. More...
#include <Matrices.hpp>
Public Member Functions | |
virtual returnValue | addToDiag (real_t alpha)=0 |
virtual returnValue | addToDiag (real_t alpha)=0 |
virtual real_t | diag (int i) const =0 |
virtual real_t | diag (int_t i) const =0 |
void | doFreeMemory () |
void | doFreeMemory () |
void | doNotFreeMemory () |
void | doNotFreeMemory () |
virtual Matrix * | duplicate () const =0 |
virtual Matrix * | duplicate () const =0 |
virtual void | free ()=0 |
virtual void | free ()=0 |
virtual real_t * | full () const =0 |
virtual returnValue | getCol (int cNum, const Indexlist *const irows, real_t alpha, real_t *col) const =0 |
virtual returnValue | getCol (int_t cNum, const Indexlist *const irows, real_t alpha, real_t *col) const =0 |
virtual real_t | getNorm (int_t type=2) const =0 |
virtual returnValue | getRow (int rNum, const Indexlist *const icols, real_t alpha, real_t *row) const =0 |
virtual returnValue | getRow (int_t rNum, const Indexlist *const icols, real_t alpha, real_t *row) const =0 |
virtual real_t | getRowNorm (int_t rNum, int_t type=2) const =0 |
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 |
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 =0 |
virtual BooleanType | isDiag () const =0 |
virtual BooleanType | isDiag () const =0 |
Matrix () | |
Matrix () | |
BooleanType | needToFreeMemory () const |
BooleanType | needToFreeMemory () const |
virtual returnValue | print () const =0 |
virtual returnValue | print (const char *name=0) const =0 |
virtual returnValue | times (int xN, real_t alpha, const real_t *x, int xLD, real_t beta, real_t *y, int yLD) const =0 |
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 =0 |
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 =0 |
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 =0 |
virtual returnValue | transTimes (int xN, real_t alpha, const real_t *x, int xLD, real_t beta, real_t *y, int yLD) const =0 |
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 =0 |
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 =0 |
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 =0 |
virtual returnValue | writeToFile (FILE *output_file, const char *prefix) const =0 |
virtual | ~Matrix () |
virtual | ~Matrix () |
Protected Attributes | |
BooleanType | freeMemory |
Abstract base class for interfacing tailored matrix-vector operations.
Abstract base matrix class. Supplies interface to matrix vector products, including products with submatrices given by (ordered) working set index lists (see SubjectTo).
\author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau \version 3.0beta \date 2011
Abstract base matrix class. Supplies interface to matrix vector products, including products with submatrices given by (ordered) working set index lists (see SubjectTo).
\author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau \version 3.2 \date 2011-2015
Definition at line 112 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.
|
inline |
Default constructor.
Definition at line 116 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.
|
inlinevirtual |
Destructor.
Definition at line 119 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.
|
inline |
Default constructor.
Definition at line 120 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.
|
inlinevirtual |
Destructor.
Definition at line 123 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.
|
pure virtual |
Adds given offset to diagonal of matrix.
alpha | Diagonal offset. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Adds given offset to diagonal of matrix.
alpha | Diagonal offset. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Returns i-th diagonal entry.
i | Index. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
Returns i-th diagonal entry.
i | Index. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
inline |
Enables de-allocation of internal memory.
Definition at line 224 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.
|
inline |
Enables de-allocation of internal memory.
Definition at line 321 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.
|
inline |
Disables de-allocation of internal memory.
Definition at line 227 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.
|
inline |
Disables de-allocation of internal memory.
Definition at line 324 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.
|
pure virtual |
Returns a deep-copy of the Matrix object.
Implemented in SymSparseMat, SparseMatrixRow, SparseMatrix, SymSparseMat, SymDenseMat, SparseMatrix, SymDenseMat, DenseMatrix, and DenseMatrix.
|
pure virtual |
Returns a deep-copy of the Matrix object.
Implemented in SymSparseMat, SparseMatrixRow, SparseMatrix, SymSparseMat, SymDenseMat, SparseMatrix, SymDenseMat, DenseMatrix, and DenseMatrix.
|
pure virtual |
Frees all internal memory.
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Frees all internal memory.
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Allocates and creates dense matrix array in row major format.
Note: Calling function has to free allocated memory!
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, and DenseMatrix.
|
pure virtual |
Retrieve indexed entries of matrix column multiplied by alpha.
cNum | Column number. |
irows | Index list specifying rows. |
alpha | Scalar factor. |
col | Output column vector. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Retrieve indexed entries of matrix column multiplied by alpha.
cNum | Column number. |
irows | Index list specifying rows. |
alpha | Scalar factor. |
col | Output column vector. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
Get the N-norm of the matrix
type | Norm type, 1: one-norm, 2: Euclidean norm. |
Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.
|
pure virtual |
Retrieve indexed entries of matrix row multiplied by alpha.
rNum | Row number. |
icols | Index list specifying columns. |
alpha | Scalar factor. |
row | Output row vector. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Retrieve indexed entries of matrix row multiplied by alpha.
rNum | Row number. |
icols | Index list specifying columns. |
alpha | Scalar factor. |
row | Output row vector. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
Get the N-norm of a row
rNum | Row number. |
type | Norm type, 1: one-norm, 2: Euclidean norm. |
Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.
|
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.
irows | Index list specifying rows. |
icols | Index list specifying columns. |
rowoffset | Offset for row entries. |
coloffset | Offset for row entries. |
numNonzeros | Number of nonzeros in submatrix. |
irn | Row position of entries (as position in irows) plus rowoffset. |
jcn | Column position of entries (as position in irows) plus coloffset. |
avals | Numerical values of the entries. |
only_lower_triangular | if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. |
Definition at line 46 of file qpOASES-3.2.0/src/Matrices.cpp.
|
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. This version retrieves one column.
irows | Index list specifying rows. |
idx_icol | Index list specifying columns. |
rowoffset | Offset for row entries. |
coloffset | Offset for row entries. |
numNonzeros | Number of nonzeros in submatrix. |
irn | Row position of entries (as position in irows) plus rowoffset. |
jcn | Column position of entries (as position in irows) plus coloffset. |
avals | Numerical values of the entries. |
only_lower_triangular | if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. |
Definition at line 65 of file qpOASES-3.2.0/src/Matrices.cpp.
|
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. This version retrieves one row.
idx_row | Row number. |
icols | Index list specifying columns. |
rowoffset | Offset for row entries. |
coloffset | Offset for row entries. |
numNonzeros | Number of nonzeros in submatrix. |
irn | Row position of entries (as position in irows) plus rowoffset. |
jcn | Column position of entries (as position in irows) plus coloffset. |
avals | Numerical values of the entries. |
only_lower_triangular | if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. |
Definition at line 82 of file qpOASES-3.2.0/src/Matrices.cpp.
|
pure 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.
irowsLength | Number of rows. |
irowsNumber | Array with row numbers. |
icolsLength | Number of columns. |
icolsNumber | Array with column numbers. |
rowoffset | Offset for row entries. |
coloffset | Offset for row entries. |
numNonzeros | Number of nonzeros in submatrix. |
irn | Row position of entries (as position in irows) plus rowoffset. |
jcn | Column position of entries (as position in irows) plus coloffset. |
avals | Numerical values of the entries. |
only_lower_triangular | if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. |
Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.
|
pure virtual |
Checks whether matrix is square and diagonal.
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Checks whether matrix is square and diagonal.
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
inline |
Returns whether internal memory needs to be de-allocated.
Definition at line 221 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.
|
inline |
Returns whether internal memory needs to be de-allocated.
Definition at line 318 of file qpOASES-3.2.0/include/qpOASES/Matrices.hpp.
|
pure virtual |
Prints matrix to screen.
Implemented in SparseMatrix, and DenseMatrix.
|
pure virtual |
Prints matrix to screen.
name | Name of matrix. |
Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.
|
pure virtual |
Evaluate Y=alpha*A*X + beta*Y.
xN | Number of vectors to multiply. |
alpha | Scalar factor for matrix vector product. |
x | Input vector to be multiplied. |
xLD | Leading dimension of input x. |
beta | Scalar factor for y. |
y | Output vector of results. |
yLD | Leading dimension of output y. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Evaluate matrix vector product with submatrix given by Indexlist.
irows | Index list specifying rows. |
icols | Index list specifying columns. |
xN | Number of vectors to multiply. |
alpha | Scalar factor for matrix vector product. |
x | Input vector to be multiplied. |
xLD | Leading dimension of input x. |
beta | Scalar factor for y. |
y | Output vector of results. |
yLD | Leading dimension of output y. |
yCompr | Compressed storage for y. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Evaluate Y=alpha*A*X + beta*Y.
xN | Number of vectors to multiply. |
alpha | Scalar factor for matrix vector product. |
x | Input vector to be multiplied. |
xLD | Leading dimension of input x. |
beta | Scalar factor for y. |
y | Output vector of results. |
yLD | Leading dimension of output y. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Evaluate matrix vector product with submatrix given by Indexlist.
irows | Index list specifying rows. |
icols | Index list specifying columns. |
xN | Number of vectors to multiply. |
alpha | Scalar factor for matrix vector product. |
x | Input vector to be multiplied. |
xLD | Leading dimension of input x. |
beta | Scalar factor for y. |
y | Output vector of results. |
yLD | Leading dimension of output y. |
yCompr | Compressed storage for y. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Evaluate Y=alpha*A'*X + beta*Y.
xN | Number of vectors to multiply. |
alpha | Scalar factor for matrix vector product. |
x | Input vector to be multiplied. |
xLD | Leading dimension of input x. |
beta | Scalar factor for y. |
y | Output vector of results. |
yLD | Leading dimension of output y. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Evaluate matrix transpose vector product.
irows | Index list specifying rows. |
icols | Index list specifying columns. |
xN | Number of vectors to multiply. |
alpha | Scalar factor for matrix vector product. |
x | Input vector to be multiplied. |
xLD | Leading dimension of input x. |
beta | Scalar factor for y. |
y | Output vector of results. |
yLD | Leading dimension of output y. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Evaluate Y=alpha*A'*X + beta*Y.
xN | Number of vectors to multiply. |
alpha | Scalar factor for matrix vector product. |
x | Input vector to be multiplied. |
xLD | Leading dimension of input x. |
beta | Scalar factor for y. |
y | Output vector of results. |
yLD | Leading dimension of output y. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Evaluate matrix transpose vector product.
irows | Index list specifying rows. |
icols | Index list specifying columns. |
xN | Number of vectors to multiply. |
alpha | Scalar factor for matrix vector product. |
x | Input vector to be multiplied. |
xLD | Leading dimension of input x. |
beta | Scalar factor for y. |
y | Output vector of results. |
yLD | Leading dimension of output y. |
Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.
|
pure virtual |
Write matrix to file.
Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.
|
protected |
Indicating whether internal memory needs to be de-allocated.
Definition at line 227 of file qpOASES-3.0beta/include/qpOASES/Matrices.hpp.