54 int nWSRin,
real_t maxCpuTimeIn,
56 int nOutputs, mxArray* plhs[],
57 const double*
const guessedBounds,
58 const double*
const _R
76 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid handle to QP instance!" );
88 if (guessedBounds != 0) {
89 for (i = 0; i < nV; i++) {
98 "ERROR (qpOASES_e): Only {-1, 0, 1} allowed for status of bounds!");
106 &nWSRout,&maxCpuTimeOut,
108 (guessedBounds != 0) ? &bounds : 0,
114 nOutputs,plhs,nV,handle );
127 int nWSRin,
real_t maxCpuTimeIn,
129 int nOutputs, mxArray* plhs[],
130 const double*
const guessedBounds,
const double*
const guessedConstraints,
131 const double*
const _R
136 int nWSRout = nWSRin;
148 if ( globalSQP == 0 )
150 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid handle to QP instance!" );
163 if (guessedBounds != 0) {
164 for (i = 0; i < nV; i++) {
173 "ERROR (qpOASES_e): Only {-1, 0, 1} allowed for status of bounds!");
180 if (guessedConstraints != 0) {
181 for (i = 0; i < nC; i++) {
190 "ERROR (qpOASES_e): Only {-1, 0, 1} allowed for status of constraints!");
198 &nWSRout,&maxCpuTimeOut,
200 (guessedBounds != 0) ? &bounds : 0, (guessedConstraints != 0) ? &constraints : 0,
205 obtainOutputs( 0,globalSQP,returnvalue,nWSRout,maxCpuTimeOut,
206 nOutputs,plhs,nV,nC,handle );
219 int nWSRin,
real_t maxCpuTimeIn,
221 int nOutputs, mxArray* plhs[]
225 int nWSRout = nWSRin;
234 if ( globalQPB == 0 )
236 myMexErrMsgTxt(
"ERROR (qpOASES_e): QP needs to be initialised first!" );
246 nOutputs,plhs,nV,-1 );
259 int nWSRin,
real_t maxCpuTimeIn,
261 int nOutputs, mxArray* plhs[]
265 int nWSRout = nWSRin;
275 if ( globalSQP == 0 )
277 myMexErrMsgTxt(
"ERROR (qpOASES_e): QP needs to be initialised first!" );
284 returnvalue =
QProblem_hotstart( globalSQP,g,lb,ub,lbA,ubA, &nWSRout,&maxCpuTimeOut );
287 obtainOutputs( 0,globalSQP,returnvalue,nWSRout,maxCpuTimeOut,
288 nOutputs,plhs,nV,nC,-1 );
298 void mexFunction(
int nlhs, mxArray* plhs[],
int nrhs,
const mxArray* prhs[] )
305 double *x0=0, *R_for=0;
307 double *guessedBounds=0, *guessedConstraints=0;
309 int H_idx=-1, g_idx=-1, A_idx=-1, lb_idx=-1, ub_idx=-1, lbA_idx=-1, ubA_idx=-1;
310 int x0_idx=-1, auxInput_idx=-1;
315 unsigned int nV=0, nC=0, handle=0;
317 real_t maxCpuTimeIn = -1.0;
321 real_t *x_out=0, *y_out=0;
323 real_t* workingSetB=0, *workingSetC=0;
334 #ifdef __SUPPRESSANYOUTPUT__ 340 if ( ( nrhs < 5 ) || ( nrhs > 10 ) )
344 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
350 if ( mxIsChar( prhs[0] ) != 1 )
352 myMexErrMsgTxt(
"ERROR (qpOASES_e): First input argument must be a string!" );
356 mxGetString( prhs[0], typeString, 2 );
359 if ( ( strcmp( typeString,
"i" ) != 0 ) && ( strcmp( typeString,
"I" ) != 0 ) &&
360 ( strcmp( typeString,
"h" ) != 0 ) && ( strcmp( typeString,
"H" ) != 0 ) &&
361 ( strcmp( typeString,
"m" ) != 0 ) && ( strcmp( typeString,
"M" ) != 0 ) &&
362 ( strcmp( typeString,
"e" ) != 0 ) && ( strcmp( typeString,
"E" ) != 0 ) &&
363 ( strcmp( typeString,
"c" ) != 0 ) && ( strcmp( typeString,
"C" ) != 0 ) )
365 myMexErrMsgTxt(
"ERROR (qpOASES_e): Undefined first input argument!\nType 'help qpOASES_sequence' for further information." );
372 if ( ( strcmp( typeString,
"i" ) == 0 ) || ( strcmp( typeString,
"I" ) == 0 ) )
375 if ( ( nlhs < 2 ) || ( nlhs > 7 ) )
377 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
381 if ( ( nrhs < 5 ) || ( nrhs > 10 ) )
383 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
389 if ( mxIsEmpty(prhs[1]) == 1 )
392 nV = (
unsigned int)mxGetM( prhs[ g_idx ] );
397 nV = (
unsigned int)mxGetM( prhs[ H_idx ] );
402 if ( ( ( H_idx >= 0 ) && ( mxIsDouble( prhs[ H_idx ] ) == 0 ) ) ||
403 ( mxIsDouble( prhs[ g_idx ] ) == 0 ) )
405 myMexErrMsgTxt(
"ERROR (qpOASES_e): All data has to be provided in double precision!" );
409 if ( ( H_idx >= 0 ) && ( ( mxGetN( prhs[ H_idx ] ) != nV ) || ( mxGetM( prhs[ H_idx ] ) != nV ) ) )
411 myMexErrMsgTxt(
"ERROR (qpOASES_e): Hessian matrix dimension mismatch!" );
430 if ( isSimplyBoundedQp ==
BT_TRUE )
460 if ((!mxIsEmpty(prhs[5])) && (mxIsStruct(prhs[5])))
463 if ( ( nrhs >= 7 ) && ( !mxIsEmpty(prhs[6]) ) )
466 if ( mxIsStruct(prhs[6]) )
489 if ( mxIsDouble( prhs[ A_idx ] ) == 0 )
491 myMexErrMsgTxt(
"ERROR (qpOASES_e): All data has to be provided in double precision!" );
496 nC = (
unsigned int)mxGetM( prhs[ A_idx ] );
518 if ( ( mxGetN( prhs[ A_idx ] ) != 0 ) && ( mxGetN( prhs[ A_idx ] ) != nV ) )
520 myMexErrMsgTxt(
"ERROR (qpOASES_e): Constraint matrix dimension mismatch!" );
545 if ((!mxIsEmpty(prhs[8])) && (mxIsStruct(prhs[8])))
548 if ( ( nrhs >= 10 ) && ( !mxIsEmpty(prhs[9]) ) )
551 if ( mxIsStruct(prhs[9]) )
575 if ( auxInput_idx >= 0 )
576 setupAuxiliaryInputs( prhs[auxInput_idx],nV,nC, &hessianType,&x0,&guessedBounds,&guessedConstraints,&R_for );
593 if ( ( nC > 0 ) && ( A_idx >= 0 ) )
600 if ( isSimplyBoundedQp ==
BT_TRUE )
603 ( H_idx >= 0 ) ? &(globalQP->
H) : 0, g,
609 ( R_for != 0 ) ? R : 0
615 ( H_idx >= 0 ) ? &(globalQP->
H) : 0, g, ( ( nC > 0 ) && ( A_idx >= 0 ) ) ? &(globalQP->
A) : 0,
620 guessedBounds,guessedConstraints,
621 ( R_for != 0 ) ? R : 0
628 if ( ( strcmp( typeString,
"h" ) == 0 ) || ( strcmp( typeString,
"H" ) == 0 ) )
631 if ( ( nlhs < 1 ) || ( nlhs > 6 ) )
633 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
637 if ( ( nrhs < 5 ) || ( nrhs > 8 ) )
639 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
650 if ( ( mxIsDouble( prhs[1] ) ==
false ) || (
mxIsScalar( prhs[1] ) ==
false ) )
652 myMexErrMsgTxt(
"ERROR (qpOASES_e): Expecting a handle to QP object as second argument!\nType 'help qpOASES_sequence' for further information." );
657 handle = (
unsigned int)mxGetScalar( prhs[1] );
661 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid handle to QP instance!" );
682 if ( isSimplyBoundedQp ==
BT_TRUE )
700 if ( ( !mxIsEmpty( prhs[5] ) ) && ( mxIsStruct( prhs[5] ) ) )
736 if ( ( !mxIsEmpty( prhs[7] ) ) && ( mxIsStruct( prhs[7] ) ) )
744 if ( isSimplyBoundedQp ==
BT_TRUE )
767 if ( ( strcmp( typeString,
"m" ) == 0 ) || ( strcmp( typeString,
"M" ) == 0 ) )
770 if ( ( nlhs < 1 ) || ( nlhs > 6 ) )
772 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
776 if ( ( nrhs < 9 ) || ( nrhs > 10 ) )
778 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
782 if ( ( mxIsDouble( prhs[1] ) ==
false ) || (
mxIsScalar( prhs[1] ) ==
false ) )
784 myMexErrMsgTxt(
"ERROR (qpOASES_e): Expecting a handle to QP object as second argument!\nType 'help qpOASES_sequence' for further information." );
790 handle = (
unsigned int)mxGetScalar( prhs[1] );
794 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid handle to QP instance!" );
801 if ( mxIsEmpty(prhs[2]) == 1 )
804 nV = (
unsigned int)mxGetM( prhs[ g_idx ] );
809 nV = (
unsigned int)mxGetM( prhs[ H_idx ] );
813 nC = (
unsigned int)mxGetM( prhs[ A_idx ] );
822 if ( ( ( H_idx >= 0 ) && ( mxIsDouble( prhs[H_idx] ) == 0 ) ) ||
823 ( mxIsDouble( prhs[g_idx] ) == 0 ) ||
824 ( mxIsDouble( prhs[A_idx] ) == 0 ) )
826 myMexErrMsgTxt(
"ERROR (qpOASES_e): All data has to be provided in real_t precision!" );
855 myMexErrMsgTxt(
"ERROR (qpOASES_e): QP dimensions must be constant during a sequence! Try creating a new QP instance instead." );
859 if ( ( H_idx >= 0 ) && ( ( mxGetN( prhs[ H_idx ] ) != nV ) || ( mxGetM( prhs[ H_idx ] ) != nV ) ) )
861 myMexErrMsgTxt(
"ERROR (qpOASES_e): Hessian matrix dimension mismatch!" );
865 if ( ( mxGetN( prhs[ A_idx ] ) != 0 ) && ( mxGetN( prhs[ A_idx ] ) != nV ) )
867 myMexErrMsgTxt(
"ERROR (qpOASES_e): Constraint matrix dimension mismatch!" );
891 if ( ( !mxIsEmpty( prhs[9] ) ) && ( mxIsStruct( prhs[9] ) ) )
899 if ( ( nC > 0 ) && ( A_idx >= 0 ) )
912 myMexErrMsgTxt(
"ERROR (qpOASES_e): Hotstart with varying matrices not yet supported!" );
918 if ( ( strcmp( typeString,
"e" ) == 0 ) || ( strcmp( typeString,
"E" ) == 0 ) )
921 if ( ( nlhs < 1 ) || ( nlhs > 4 ) )
923 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
927 if ( ( nrhs < 7 ) || ( nrhs > 8 ) )
929 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
933 if ( ( mxIsDouble( prhs[1] ) ==
false ) || (
mxIsScalar( prhs[1] ) ==
false ) )
935 myMexErrMsgTxt(
"ERROR (qpOASES_e): Expecting a handle to QP object as second argument!\nType 'help qpOASES_sequence' for further information." );
940 handle = (
unsigned int)mxGetScalar( prhs[1] );
944 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid handle to QP instance!" );
949 nRHS = (int)mxGetN(prhs[2]);
991 if ( ( nrhs == 8 ) && ( !mxIsEmpty( prhs[7] ) ) && ( mxIsStruct( prhs[7] ) ) )
999 plhs[0] = mxCreateDoubleMatrix( nV, nRHS, mxREAL );
1000 x_out = mxGetPr(plhs[0]);
1003 plhs[1] = mxCreateDoubleMatrix( nV+nC, nRHS, mxREAL );
1004 y_out = mxGetPr(plhs[1]);
1008 plhs[2] = mxCreateDoubleMatrix( nV, nRHS, mxREAL );
1009 workingSetB = mxGetPr(plhs[2]);
1014 plhs[3] = mxCreateDoubleMatrix( nC, nRHS, mxREAL );
1015 workingSetC = mxGetPr(plhs[3]);
1035 if ( ( strcmp( typeString,
"c" ) == 0 ) || ( strcmp( typeString,
"C" ) == 0 ) )
1040 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
1046 myMexErrMsgTxt(
"ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
1050 if ( ( mxIsDouble( prhs[1] ) ==
false ) || (
mxIsScalar( prhs[1] ) ==
false ) )
1052 myMexErrMsgTxt(
"ERROR (qpOASES_e): Expecting a handle to QP object as second argument!\nType 'help qpOASES_sequence' for further information." );
returnValue Bounds_setupBound(Bounds *_THIS, int number, SubjectToStatus _status)
#define USING_NAMESPACE_QPOASES
static int QProblemB_getNV(QProblemB *_THIS)
void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
BooleanType containsNaNorInf(const mxArray *prhs[], int_t rhs_index, bool mayContainInf)
int QPInstance_getNV(QPInstance *_THIS)
static BooleanType qpOASES_isEqual(real_t x, real_t y, real_t TOL)
Manages working sets of constraints.
returnValue setupHessianMatrix(const mxArray *prhsH, int_t nV, SymmetricMatrix **H, sparse_int_t **Hir, sparse_int_t **Hjc, real_t **Hv)
Implements the online active set strategy for box-constrained QPs.
bool mxIsScalar(const mxArray *pm)
returnValue setupOptions(Options *options, const mxArray *optionsPtr, int &nWSRin)
Allows to pass back messages to the calling function.
int QPInstance_getNC(QPInstance *_THIS)
returnValue QProblem_initMW(QProblem *_THIS, DenseMatrix *_H, const real_t *const _g, DenseMatrix *_A, const real_t *const _lb, const real_t *const _ub, const real_t *const _lbA, const real_t *const _ubA, int *nWSR, real_t *const cputime, const real_t *const xOpt, const real_t *const yOpt, Bounds *const guessedBounds, Constraints *const guessedConstraints, const real_t *const _R)
returnValue smartDimensionCheck(real_t **input, unsigned int m, unsigned int n, BooleanType emptyAllowed, const mxArray *prhs[], int idx)
returnValue Constraints_setupConstraint(Constraints *_THIS, int number, SubjectToStatus _status)
returnValue convertFortranToC(const real_t *const A_for, int nV, int nC, real_t *const A)
returnValue obtainOutputsSB(int k, QProblemB *qp, returnValue returnvalue, int _nWSRout, double _cpuTime, int nlhs, mxArray *plhs[], int nV, int handle)
int mex_SQProblem_init(int handle, DenseMatrix *H, real_t *g, DenseMatrix *A, const real_t *const lb, const real_t *const ub, const real_t *const lbA, const real_t *const ubA, int nWSRin, real_t maxCpuTimeIn, const double *const x0, Options *options, int nOutputs, mxArray *plhs[], const double *const guessedBounds, const double *const guessedConstraints, const double *const _R)
static int QProblem_getNV(QProblem *_THIS)
returnValue QProblem_solveCurrentEQP(QProblem *_THIS, const int n_rhs, const real_t *g_in, const real_t *lb_in, const real_t *ub_in, const real_t *lbA_in, const real_t *ubA_in, real_t *x_out, real_t *y_out)
static QProblemB * globalQPB
USING_NAMESPACE_QPOASES int mex_QProblemB_init(int handle, DenseMatrix *H, real_t *g, const real_t *const lb, const real_t *const ub, int nWSRin, real_t maxCpuTimeIn, const double *const x0, Options *options, int nOutputs, mxArray *plhs[], const double *const guessedBounds, const double *const _R)
Interfaces matrix-vector operations tailored to general dense matrices.
void allocateOutputs(int nlhs, mxArray *plhs[], int nV, int nC=0, int nP=1)
static SQProblem * globalSQP
returnValue setupAuxiliaryInputs(const mxArray *auxInput, uint_t nV, uint_t nC, HessianType *hessianType, double **x0, double **guessedBounds, double **guessedConstraints, double **R)
static QProblem * globalQP
int_t QProblemB_hotstart(const real_t *const g, const real_t *const lb, const real_t *const ub, int_t *const nWSR, real_t *const cputime, real_t *const x, real_t *const y, real_t *const obj, int_t *const status)
Provides a generic way to set and pass user-specified options.
int_t allocateQPInstance(int_t nV, int_t nC, HessianType hessianType, BooleanType isSimplyBounded, const Options *options)
static returnValue QProblemB_setOptions(QProblemB *_THIS, Options _options)
static const real_t QPOASES_INFTY
void obtainOutputs(int k, QProblemB *qp, returnValue returnvalue, int nWSRin, int nlhs, mxArray *plhs[], int nV, int nC=0)
static int QProblem_getNC(QProblem *_THIS)
returnValue Options_setToDefault(Options *_THIS)
returnValue QProblem_getWorkingSetConstraints(QProblem *_THIS, real_t *workingSetC)
returnValue setupConstraintMatrix(const mxArray *prhsA, int_t nV, int_t nC, Matrix **A, sparse_int_t **Air, sparse_int_t **Ajc, real_t **Av)
#define QPOASES_MAX_STRING_LENGTH
int mex_QProblem_hotstart(int handle, const real_t *const g, const real_t *const lb, const real_t *const ub, const real_t *const lbA, const real_t *const ubA, int nWSRin, real_t maxCpuTimeIn, Options *options, int nOutputs, mxArray *plhs[])
Manages working sets of bounds (= box constraints).
int_t QProblem_hotstart(const real_t *const g, const real_t *const lb, const real_t *const ub, const real_t *const lbA, const real_t *const ubA, int_t *const nWSR, real_t *const cputime, real_t *const x, real_t *const y, real_t *const obj, int_t *const status)
int mex_QProblemB_hotstart(int handle, const real_t *const g, const real_t *const lb, const real_t *const ub, int nWSRin, real_t maxCpuTimeIn, Options *options, int nOutputs, mxArray *plhs[])
Implements the online active set strategy for QPs with general constraints.
QPInstance * getQPInstance(int_t handle)
static const real_t QPOASES_TOL
void ConstraintsCON(Constraints *_THIS, int _n)
returnValue QProblemB_initMW(QProblemB *_THIS, DenseMatrix *_H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int *nWSR, real_t *const cputime, const real_t *const xOpt, const real_t *const yOpt, Bounds *const guessedBounds, const real_t *const _R)
static returnValue QProblem_setOptions(QProblem *_THIS, Options _options)
void BoundsCON(Bounds *_THIS, int _n)
returnValue QProblem_getWorkingSetBounds(QProblem *_THIS, real_t *workingSetB)