Classes | Macros | Functions
Matrices.h File Reference
#include <qpOASES_e/Indexlist.h>
Include dependency graph for Matrices.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  DenseMatrix
 Interfaces matrix-vector operations tailored to general dense matrices. More...
 

Macros

#define GEMM   dgemm_
 
#define POTRF   dpotrf_
 
#define SYR   dsyr_
 
#define SYR2   dsyr2_
 

Functions

returnValue DenseMatrix_addToDiag (DenseMatrix *_THIS, real_t alpha)
 
returnValue DenseMatrix_bilinear (DenseMatrix *_THIS, const Indexlist *const icols, int xN, const real_t *x, int xLD, real_t *y, int yLD)
 
real_t DenseMatrix_diag (DenseMatrix *_THIS, int i)
 
void DenseMatrix_free (DenseMatrix *_THIS)
 
returnValue DenseMatrix_getCol (DenseMatrix *_THIS, int cNum, const Indexlist *const irows, real_t alpha, real_t *col)
 
real_t DenseMatrix_getNorm (DenseMatrix *_THIS, int type)
 
returnValue DenseMatrix_getRow (DenseMatrix *_THIS, int rNum, const Indexlist *const icols, real_t alpha, real_t *row)
 
real_t DenseMatrix_getRowNorm (DenseMatrix *_THIS, int rNum, int type)
 
static real_tDenseMatrix_getVal (DenseMatrix *_THIS)
 
returnValue DenseMatrix_init (DenseMatrix *_THIS, int m, int n, int lD, real_t *v)
 
BooleanType DenseMatrix_isDiag (DenseMatrix *_THIS)
 
returnValue DenseMatrix_print (DenseMatrix *_THIS)
 
returnValue DenseMatrix_subTimes (DenseMatrix *_THIS, 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)
 
returnValue DenseMatrix_subTransTimes (DenseMatrix *_THIS, 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)
 
returnValue DenseMatrix_times (DenseMatrix *_THIS, int xN, real_t alpha, const real_t *x, int xLD, real_t beta, real_t *y, int yLD)
 
returnValue DenseMatrix_transTimes (DenseMatrix *_THIS, int xN, real_t alpha, const real_t *x, int xLD, real_t beta, real_t *y, int yLD)
 
void DenseMatrixCON (DenseMatrix *_THIS, int m, int n, int lD, real_t *v)
 
void DenseMatrixCPY (DenseMatrix *FROM, DenseMatrix *TO)
 
void dgemm_ (const char *, const char *, const unsigned long *, const unsigned long *, const unsigned long *, const double *, const double *, const unsigned long *, const double *, const unsigned long *, const double *, double *, const unsigned long *)
 
void dpotrf_ (const char *, const unsigned long *, double *, const unsigned long *, long *)
 
void dsyr2_ (const char *, const unsigned long *, const double *, const double *, const unsigned long *, const double *, const unsigned long *, double *, const unsigned long *)
 
void dsyr_ (const char *, const unsigned long *, const double *, const double *, const unsigned long *, double *, const unsigned long *)
 
void sgemm_ (const char *, const char *, const unsigned long *, const unsigned long *, const unsigned long *, const float *, const float *, const unsigned long *, const float *, const unsigned long *, const float *, float *, const unsigned long *)
 
void spotrf_ (const char *, const unsigned long *, float *, const unsigned long *, long *)
 
void ssyr2_ (const char *, const unsigned long *, const float *, const float *, const unsigned long *, const float *, const unsigned long *, float *, const unsigned long *)
 
void ssyr_ (const char *, const unsigned long *, const float *, const float *, const unsigned long *, float *, const unsigned long *)
 

Detailed Description

Author
Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
Version
3.1embedded
Date
2009-2015

Various matrix classes: Abstract base matrix class, dense and sparse matrices, including symmetry exploiting specializations.

Definition in file Matrices.h.

Macro Definition Documentation

#define GEMM   dgemm_

Macro for calling level 3 BLAS operation in double precision.

Definition at line 54 of file Matrices.h.

#define POTRF   dpotrf_

Macro for calling level 3 BLAS operation in double precision.

Definition at line 60 of file Matrices.h.

#define SYR   dsyr_

Macro for calling level 3 BLAS operation in double precision.

Definition at line 56 of file Matrices.h.

#define SYR2   dsyr2_

Macro for calling level 3 BLAS operation in double precision.

Definition at line 58 of file Matrices.h.

Function Documentation

returnValue DenseMatrix_addToDiag ( DenseMatrix _THIS,
real_t  alpha 
)

Adds given offset to diagonal of matrix.

Returns
SUCCESSFUL_RETURN
RET_NO_DIAGONAL_AVAILABLE
Parameters
alphaDiagonal offset.

Definition at line 474 of file Matrices.c.

returnValue DenseMatrix_bilinear ( DenseMatrix _THIS,
const Indexlist *const  icols,
int  xN,
const real_t x,
int  xLD,
real_t y,
int  yLD 
)

Compute bilinear form y = x'*H*x using submatrix given by index list.

Returns
SUCCESSFUL_RETURN
Parameters
icolsIndex list specifying columns of x.
xNNumber of vectors to multiply.
xInput vector to be multiplied (uncompressed).
xLDLeading dimension of input x.
yOutput vector of results (compressed).
yLDLeading dimension of output y.

Definition at line 490 of file Matrices.c.

real_t DenseMatrix_diag ( DenseMatrix _THIS,
int  i 
)

Returns i-th diagonal entry.

Returns
i-th diagonal entry
Parameters
iIndex.

Definition at line 108 of file Matrices.c.

void DenseMatrix_free ( DenseMatrix _THIS)

Frees all internal memory.

Definition at line 75 of file Matrices.c.

returnValue DenseMatrix_getCol ( DenseMatrix _THIS,
int  cNum,
const Indexlist *const  irows,
real_t  alpha,
real_t col 
)

Retrieve indexed entries of matrix column multiplied by alpha.

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

Definition at line 178 of file Matrices.c.

real_t DenseMatrix_getNorm ( DenseMatrix _THIS,
int  type 
)

Get the N-norm of the matrix

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

Definition at line 135 of file Matrices.c.

returnValue DenseMatrix_getRow ( DenseMatrix _THIS,
int  rNum,
const Indexlist *const  icols,
real_t  alpha,
real_t row 
)

Retrieve indexed entries of matrix row multiplied by alpha.

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

Definition at line 147 of file Matrices.c.

real_t DenseMatrix_getRowNorm ( DenseMatrix _THIS,
int  rNum,
int  type 
)

Get the N-norm of a row

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

Definition at line 141 of file Matrices.c.

static real_t* DenseMatrix_getVal ( DenseMatrix _THIS)
inlinestatic

Definition at line 257 of file Matrices.h.

returnValue DenseMatrix_init ( DenseMatrix _THIS,
int  m,
int  n,
int  lD,
real_t v 
)

Constructor from vector of values. Caution: Data pointer must be valid throughout lifetime

Parameters
mNumber of rows.
nNumber of columns.
lDLeading dimension.
vValues.

Definition at line 80 of file Matrices.c.

BooleanType DenseMatrix_isDiag ( DenseMatrix _THIS)

Checks whether matrix is square and diagonal.

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

Definition at line 119 of file Matrices.c.

returnValue DenseMatrix_print ( DenseMatrix _THIS)

Prints matrix to screen.

Returns
SUCCESSFUL_RETURN

Definition at line 484 of file Matrices.c.

returnValue DenseMatrix_subTimes ( DenseMatrix _THIS,
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 
)

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.

Definition at line 230 of file Matrices.c.

returnValue DenseMatrix_subTransTimes ( DenseMatrix _THIS,
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 
)

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.

Definition at line 416 of file Matrices.c.

returnValue DenseMatrix_times ( DenseMatrix _THIS,
int  xN,
real_t  alpha,
const real_t x,
int  xLD,
real_t  beta,
real_t y,
int  yLD 
)

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.

Definition at line 196 of file Matrices.c.

returnValue DenseMatrix_transTimes ( DenseMatrix _THIS,
int  xN,
real_t  alpha,
const real_t x,
int  xLD,
real_t  beta,
real_t y,
int  yLD 
)

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.

Definition at line 213 of file Matrices.c.

void DenseMatrixCON ( DenseMatrix _THIS,
int  m,
int  n,
int  lD,
real_t v 
)

Constructor from vector of values. Caution: Data pointer must be valid throughout lifetime

Parameters
mNumber of rows.
nNumber of columns.
lDLeading dimension.
vValues.

Definition at line 47 of file Matrices.c.

void DenseMatrixCPY ( DenseMatrix FROM,
DenseMatrix TO 
)

Definition at line 58 of file Matrices.c.

void dgemm_ ( const char *  ,
const char *  ,
const unsigned long *  ,
const unsigned long *  ,
const unsigned long *  ,
const double *  ,
const double *  ,
const unsigned long *  ,
const double *  ,
const unsigned long *  ,
const double *  ,
double *  ,
const unsigned long *   
)

Performs one of the matrix-matrix operation in double precision.

Definition at line 38 of file qpOASES-3.0beta/src/BLASReplacement.cpp.

void dpotrf_ ( const char *  ,
const unsigned long *  ,
double *  ,
const unsigned long *  ,
long *   
)

Calculates the Cholesky factorization of a real symmetric positive definite matrix in double precision.

Definition at line 38 of file qpOASES-3.0beta/src/LAPACKReplacement.cpp.

void dsyr2_ ( const char *  ,
const unsigned long *  ,
const double *  ,
const double *  ,
const unsigned long *  ,
const double *  ,
const unsigned long *  ,
double *  ,
const unsigned long *   
)

Performs a symmetric rank 2 operation in double precision.

void dsyr_ ( const char *  ,
const unsigned long *  ,
const double *  ,
const double *  ,
const unsigned long *  ,
double *  ,
const unsigned long *   
)

Performs a symmetric rank 1 operation in double precision.

void sgemm_ ( const char *  ,
const char *  ,
const unsigned long *  ,
const unsigned long *  ,
const unsigned long *  ,
const float *  ,
const float *  ,
const unsigned long *  ,
const float *  ,
const unsigned long *  ,
const float *  ,
float *  ,
const unsigned long *   
)

Performs one of the matrix-matrix operation in single precision.

Definition at line 92 of file qpOASES-3.0beta/src/BLASReplacement.cpp.

void spotrf_ ( const char *  ,
const unsigned long *  ,
float *  ,
const unsigned long *  ,
long *   
)

Calculates the Cholesky factorization of a real symmetric positive definite matrix in single precision.

Definition at line 80 of file qpOASES-3.2.0/src/LAPACKReplacement.cpp.

void ssyr2_ ( const char *  ,
const unsigned long *  ,
const float *  ,
const float *  ,
const unsigned long *  ,
const float *  ,
const unsigned long *  ,
float *  ,
const unsigned long *   
)

Performs a symmetric rank 2 operation in single precision.

void ssyr_ ( const char *  ,
const unsigned long *  ,
const float *  ,
const float *  ,
const unsigned long *  ,
float *  ,
const unsigned long *   
)

Performs a symmetric rank 1 operation in single precision.



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