#include <qpOASES_e/Indexlist.h>
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_t * | DenseMatrix_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 *) |
Various matrix classes: Abstract base matrix class, dense and sparse matrices, including symmetry exploiting specializations.
Definition in file Matrices.h.
#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.
returnValue DenseMatrix_addToDiag | ( | DenseMatrix * | _THIS, |
real_t | alpha | ||
) |
Adds given offset to diagonal of matrix.
alpha | Diagonal 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.
icols | Index list specifying columns of x. |
xN | Number of vectors to multiply. |
x | Input vector to be multiplied (uncompressed). |
xLD | Leading dimension of input x. |
y | Output vector of results (compressed). |
yLD | Leading 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.
i | Index. |
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.
cNum | Column number. |
irows | Index list specifying rows. |
alpha | Scalar factor. |
col | Output 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
type | Norm 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.
rNum | Row number. |
icols | Index list specifying columns. |
alpha | Scalar factor. |
row | Output 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
rNum | Row number. |
type | Norm type, 1: one-norm, 2: Euclidean norm. |
Definition at line 141 of file Matrices.c.
|
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
m | Number of rows. |
n | Number of columns. |
lD | Leading dimension. |
v | Values. |
Definition at line 80 of file Matrices.c.
BooleanType DenseMatrix_isDiag | ( | DenseMatrix * | _THIS | ) |
Checks whether matrix is square and diagonal.
Definition at line 119 of file Matrices.c.
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 | ||
) |
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. |
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.
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. |
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.
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. |
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.
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. |
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
m | Number of rows. |
n | Number of columns. |
lD | Leading dimension. |
v | Values. |
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.