38 #include <qpOASES/SQProblem.hpp> 86 if ( globalSQP_H != 0 )
92 if ( globalSQP_A != 0 )
115 int nOutputs, mxArray* plhs[]
125 returnvalue = globalSQP->
init( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
127 returnvalue = globalSQP->
init( H,g,A,lb,ub,lbA,ubA, nWSR,0, x0,0,0,0 );
143 int nOutputs, mxArray* plhs[]
162 void mexFunction(
int nlhs, mxArray* plhs[],
int nrhs,
const mxArray* prhs[] )
168 real_t *H_for=0, *H_mem=0, *
g=0, *A_for=0, *A_mem=0, *
lb=0, *
ub=0, *
lbA=0, *
ubA=0, *x0=0;
175 #ifdef __SUPPRESSANYOUTPUT__ 180 unsigned int nV=0, nC=0;
185 if ( ( nrhs < 8 ) || ( nrhs > 10 ) )
187 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
190 if ( mxIsChar( prhs[0] ) != 1 )
191 mexErrMsgTxt(
"ERROR (qpOASES): First input argument must be a string!" );
193 typeString = (
char*) mxGetPr( prhs[0] );
199 if ( ( strcmp( typeString,
"i" ) == 0 ) || ( strcmp( typeString,
"I" ) == 0 ) ||
200 ( strcmp( typeString,
"h" ) == 0 ) || ( strcmp( typeString,
"H" ) == 0 ) )
203 if ( ( nlhs < 1 ) || ( nlhs > 5 ) )
204 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of output arguments!\nType 'help qpOASES_sequenceVM' for further information." );
206 if ( ( nrhs < 8 ) || ( nrhs > 10 ) )
207 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
210 if ( ( mxIsDouble( prhs[1] ) == 0 ) ||
211 ( mxIsDouble( prhs[2] ) == 0 ) ||
212 ( mxIsDouble( prhs[3] ) == 0 ) )
213 mexErrMsgTxt(
"ERROR (qpOASES): All data has to be provided in real_t precision!" );
221 nV = mxGetM( prhs[1] );
222 nC = mxGetM( prhs[3] );
224 if ( ( mxGetN( prhs[1] ) != nV ) || ( ( mxGetN( prhs[3] ) != 0 ) && ( mxGetN( prhs[3] ) != nV ) ) )
225 mexErrMsgTxt(
"ERROR (qpOASES): Input dimension mismatch!" );
243 int nWSRin = 5*(nV+nC);
246 if ( ( ( strcmp( typeString,
"i" ) == 0 ) ) || ( strcmp( typeString,
"I" ) == 0 ) )
254 if ( ( !mxIsEmpty( prhs[9] ) ) && ( mxIsStruct( prhs[9] ) ) )
261 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
264 if ( ( !mxIsEmpty( prhs[8] ) ) && ( mxIsStruct( prhs[8] ) ) )
271 if ( mxIsSparse( prhs[1] ) != 0 )
273 long *ir = (
long *)mxGetIr(prhs[1]);
274 long *jc = (
long *)mxGetJc(prhs[1]);
283 H_for = (
real_t*) mxGetPr( prhs[1] );
284 H_mem =
new real_t[nV*nV];
285 for(
int i=0; i<nV*nV; ++i )
287 globalSQP_H =
new SymDenseMat( nV, nV, nV, H_mem );
296 if ( mxIsSparse( prhs[3] ) != 0 )
298 long *ir = (
long *)mxGetIr(prhs[3]);
299 long *jc = (
long *)mxGetJc(prhs[3]);
308 A_for = (
real_t*) mxGetPr( prhs[3] );
309 A_mem =
new real_t[nC*nV];
320 if ( ( ( strcmp( typeString,
"i" ) == 0 ) ) || ( strcmp( typeString,
"I" ) == 0 ) )
325 globalSQP_H,
g,globalSQP_A,
333 if ( globalSQP == 0 )
334 mexErrMsgTxt(
"ERROR (qpOASES): QP needs to be initialised first!" );
336 if ( ( (
int)nV != globalSQP->
getNV( ) ) || ( (
int)nC != globalSQP->
getNC( ) ) )
337 mexErrMsgTxt(
"ERROR (qpOASES): QP dimensions must be constant during a sequence!" );
340 globalSQP->resetMatrixPointers( );
353 if ( ( strcmp( typeString,
"c" ) == 0 ) || ( strcmp( typeString,
"C" ) == 0 ) )
357 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of output arguments!\nType 'help qpOASES_sequenceVM' for further information." );
360 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
Interfaces matrix-vector operations tailored to symmetric sparse matrices.
returnValue init(const real_t *const _H, const real_t *const _g, const real_t *const _A, const real_t *const _lb, const real_t *const _ub, const real_t *const _lbA, const real_t *const _ubA, int &nWSR, const real_t *const yOpt=0, real_t *const cputime=0)
Implements the online active set strategy for QPs with varying matrices.
static long * globalSQP_Hdiag
returnValue setupOptions(Options *options, const mxArray *optionsPtr, int &nWSRin)
Allows to pass back messages to the calling function.
Interfaces matrix-vector operations tailored to symmetric dense matrices.
returnValue smartDimensionCheck(real_t **input, unsigned int m, unsigned int n, BooleanType emptyAllowed, const mxArray *prhs[], int idx)
returnValue convertFortranToC(const real_t *const A_for, int nV, int nC, real_t *const A)
void initVM(int nV, int nC, SymmetricMatrix *H, real_t *g, Matrix *A, const real_t *const lb, const real_t *const ub, const real_t *const lbA, const real_t *const ubA, int nWSR, const real_t *const x0, Options *options, int nOutputs, mxArray *plhs[])
returnValue setOptions(const Options &_options)
void deleteGlobalSQProblemInstance()
Interfaces matrix-vector operations tailored to general dense matrices.
void allocateGlobalSQProblemInstance(int nV, int nC, Options *options)
void hotstartVM(SymmetricMatrix *H, real_t *g, Matrix *A, const real_t *const lb, const real_t *const ub, const real_t *const lbA, const real_t *const ubA, int nWSR, Options *options, int nOutputs, mxArray *plhs[])
void allocateOutputs(int nlhs, mxArray *plhs[], int nV, int nC=0, int nP=1)
Interfaces matrix-vector operations tailored to general sparse matrices.
static SQProblem * globalSQP
Provides a generic way to set and pass user-specified options.
void deleteGlobalSQProblemMatrices()
Abstract base class for interfacing tailored matrix-vector operations.
void obtainOutputs(int k, QProblemB *qp, returnValue returnvalue, int nWSRin, int nlhs, mxArray *plhs[], int nV, int nC=0)
static SymmetricMatrix * globalSQP_H
static Matrix * globalSQP_A
void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
Abstract base class for interfacing matrix-vector operations tailored to symmetric matrices...
returnValue hotstart(const real_t *const H_new, const real_t *const g_new, const real_t *const A_new, const real_t *const lb_new, const real_t *const ub_new, const real_t *const lbA_new, const real_t *const ubA_new, int &nWSR, real_t *const cputime)