Public Member Functions | Protected Attributes | List of all members
Matrix Class Referenceabstract

Abstract base class for interfacing tailored matrix-vector operations. More...

#include <Matrices.hpp>

Inheritance diagram for Matrix:
Inheritance graph
[legend]

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 Matrixduplicate () const =0
 
virtual Matrixduplicate () const =0
 
virtual void free ()=0
 
virtual void free ()=0
 
virtual real_tfull () 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
 

Detailed Description

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.

Constructor & Destructor Documentation

Matrix::Matrix ( )
inline

Default constructor.

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

virtual Matrix::~Matrix ( )
inlinevirtual

Destructor.

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

Matrix::Matrix ( )
inline

Default constructor.

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

virtual Matrix::~Matrix ( )
inlinevirtual

Destructor.

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

Member Function Documentation

virtual returnValue Matrix::addToDiag ( real_t  alpha)
pure virtual

Adds given offset to diagonal of matrix.

Returns
SUCCESSFUL_RETURN
RET_NO_DIAGONAL_AVAILABLE
Parameters
alphaDiagonal offset.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual returnValue Matrix::addToDiag ( real_t  alpha)
pure virtual

Adds given offset to diagonal of matrix.

Returns
SUCCESSFUL_RETURN
RET_NO_DIAGONAL_AVAILABLE
Parameters
alphaDiagonal offset.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual real_t Matrix::diag ( int  i) const
pure virtual

Returns i-th diagonal entry.

Returns
i-th diagonal entry
Parameters
iIndex.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual real_t Matrix::diag ( int_t  i) const
pure virtual

Returns i-th diagonal entry.

Returns
i-th diagonal entry
Parameters
iIndex.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

void Matrix::doFreeMemory ( )
inline

Enables de-allocation of internal memory.

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

void Matrix::doFreeMemory ( )
inline

Enables de-allocation of internal memory.

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

void Matrix::doNotFreeMemory ( )
inline

Disables de-allocation of internal memory.

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

void Matrix::doNotFreeMemory ( )
inline

Disables de-allocation of internal memory.

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

virtual Matrix* Matrix::duplicate ( ) const
pure virtual

Returns a deep-copy of the Matrix object.

Returns
Deep-copy of Matrix object

Implemented in SymSparseMat, SparseMatrixRow, SparseMatrix, SymSparseMat, SymDenseMat, SparseMatrix, SymDenseMat, DenseMatrix, and DenseMatrix.

virtual Matrix* Matrix::duplicate ( ) const
pure virtual

Returns a deep-copy of the Matrix object.

Returns
Deep-copy of Matrix object

Implemented in SymSparseMat, SparseMatrixRow, SparseMatrix, SymSparseMat, SymDenseMat, SparseMatrix, SymDenseMat, DenseMatrix, and DenseMatrix.

virtual void Matrix::free ( )
pure virtual

Frees all internal memory.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual void Matrix::free ( )
pure virtual

Frees all internal memory.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual real_t* Matrix::full ( ) const
pure virtual

Allocates and creates dense matrix array in row major format.

Note: Calling function has to free allocated memory!

Returns
Pointer to matrix array.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, and DenseMatrix.

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

Retrieve indexed entries of matrix column multiplied by alpha.

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

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

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

Retrieve indexed entries of matrix column multiplied by alpha.

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

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual real_t Matrix::getNorm ( int_t  type = 2) const
pure virtual

Get the N-norm of the matrix

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

Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.

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

Retrieve indexed entries of matrix row multiplied by alpha.

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

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

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

Retrieve indexed entries of matrix row multiplied by alpha.

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

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual real_t Matrix::getRowNorm ( int_t  rNum,
int_t  type = 2 
) const
pure 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.

Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.

BEGIN_NAMESPACE_QPOASES returnValue Matrix::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

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
irowsIndex list specifying rows.
icolsIndex list specifying columns.
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.

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

returnValue Matrix::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

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.

Returns
SUCCESSFUL_RETURN
Parameters
irowsIndex list specifying rows.
idx_icolIndex list specifying columns.
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.

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

returnValue Matrix::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

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.

Returns
SUCCESSFUL_RETURN
Parameters
idx_rowRow number.
icolsIndex list specifying columns.
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.

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

virtual returnValue Matrix::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
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.

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.

Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.

virtual BooleanType Matrix::isDiag ( ) const
pure virtual

Checks whether matrix is square and diagonal.

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

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual BooleanType Matrix::isDiag ( ) const
pure virtual

Checks whether matrix is square and diagonal.

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

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

BooleanType Matrix::needToFreeMemory ( ) const
inline

Returns whether internal memory needs to be de-allocated.

Returns
BT_TRUE iff internal memory needs to be de-allocated,
BT_FALSE otherwise

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

BooleanType Matrix::needToFreeMemory ( ) const
inline

Returns whether internal memory needs to be de-allocated.

Returns
BT_TRUE iff internal memory needs to be de-allocated,
BT_FALSE otherwise

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

virtual returnValue Matrix::print ( ) const
pure virtual

Prints matrix to screen.

Returns
SUCCESSFUL_RETURN
RET_NOT_YET_IMPLEMENTED

Implemented in SparseMatrix, and DenseMatrix.

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

Prints matrix to screen.

Returns
SUCCESSFUL_RETURN
Parameters
nameName of matrix.

Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.

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

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

Returns
SUCCESSFUL_RETURN
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.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual returnValue Matrix::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
pure virtual

Evaluate matrix vector product with submatrix given by Indexlist.

Returns
SUCCESSFUL_RETURN
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.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

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

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

Returns
SUCCESSFUL_RETURN
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.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual returnValue Matrix::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
pure virtual

Evaluate matrix vector product with submatrix given by Indexlist.

Returns
SUCCESSFUL_RETURN
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.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

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

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

Returns
SUCCESSFUL_RETURN
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.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual returnValue Matrix::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
pure virtual

Evaluate matrix transpose vector product.

Returns
SUCCESSFUL_RETURN
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.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

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

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

Returns
SUCCESSFUL_RETURN
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.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

virtual returnValue Matrix::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
pure virtual

Evaluate matrix transpose vector product.

Returns
SUCCESSFUL_RETURN
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.

Implemented in SparseMatrixRow, SparseMatrix, SparseMatrix, DenseMatrix, and DenseMatrix.

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

Write matrix to file.

Returns
SUCCESSFUL_RETURN

Implemented in SparseMatrixRow, SparseMatrix, and DenseMatrix.

Member Data Documentation

BooleanType Matrix::freeMemory
protected

Indicating whether internal memory needs to be de-allocated.

Definition at line 227 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:25