36 #include <qpOASES.hpp> 57 double*
lb,
double*
ub,
61 int_t nOutputs, mxArray* plhs[],
62 const double*
const guessedBounds,
const double*
const guessedConstraints,
63 const double*
const _R
78 if (guessedBounds != 0) {
79 for (
int_t i = 0; i < nV; i++) {
89 "ERROR (qpOASES): Only {-1, 0, 1} allowed for status of bounds!");
96 if (guessedConstraints != 0) {
97 for (
int_t i = 0; i < nC; i++) {
107 "ERROR (qpOASES): Only {-1, 0, 1} allowed for status of constraints!");
115 maxCpuTimeOut = (maxCpuTimeIn >= 0.0) ? maxCpuTimeIn :
INFTY;
117 returnvalue = QP.
init( H,g,A,lb,ub,lbA,ubA,
118 nWSRout,&maxCpuTimeOut,
120 (guessedBounds != 0) ? &bounds : 0, (guessedConstraints != 0) ? &constraints : 0,
133 for (
int_t k=0; k<nP; ++k )
138 g_current = &(g[k*nV]);
140 lb_current = &(lb[k*nV]);
142 ub_current = &(ub[k*nV]);
144 lbA_current = &(lbA[k*nC]);
146 ubA_current = &(ubA[k*nC]);
149 maxCpuTimeOut = (maxCpuTimeIn >= 0.0) ? maxCpuTimeIn :
INFTY;
150 returnvalue = QP.
hotstart( g_current,lb_current,ub_current,lbA_current,ubA_current, nWSRout,&maxCpuTimeOut );
155 nOutputs,plhs,nV,nC );
170 double*
lb,
double*
ub,
173 int_t nOutputs, mxArray* plhs[],
174 const double*
const guessedBounds,
175 const double*
const _R
189 if (guessedBounds != 0) {
190 for (
int_t i = 0; i < nV; i++) {
200 "ERROR (qpOASES): Only {-1, 0, 1} allowed for status of bounds!");
208 maxCpuTimeOut = (maxCpuTimeIn >= 0.0) ? maxCpuTimeIn :
INFTY;
210 returnvalue = QP.
init( H,g,lb,ub,
211 nWSRout,&maxCpuTimeOut,
213 (guessedBounds != 0) ? &bounds : 0,
224 for (
int_t k=0; k<nP; ++k )
229 g_current = &(g[k*nV]);
231 lb_current = &(lb[k*nV]);
233 ub_current = &(ub[k*nV]);
236 maxCpuTimeOut = (maxCpuTimeIn >= 0.0) ? maxCpuTimeIn :
INFTY;
237 returnvalue = QP.
hotstart( g_current,lb_current,ub_current, nWSRout,&maxCpuTimeOut );
253 void mexFunction(
int nlhs, mxArray* plhs[],
int nrhs,
const mxArray* prhs[] )
261 double *x0=0, *
R=0, *R_for=0;
262 double *guessedBounds=0, *guessedConstraints=0;
264 int H_idx=-1, g_idx=-1, A_idx=-1, lb_idx=-1, ub_idx=-1, lbA_idx=-1, ubA_idx=-1;
265 int options_idx=-1, x0_idx=-1, auxInput_idx=-1;
273 #ifdef __SUPPRESSANYOUTPUT__ 287 if ( ( nrhs < 4 ) || ( nrhs > 9 ) )
289 myMexErrMsgTxt(
"ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES' for further information." );
296 myMexErrMsgTxt(
"ERROR (qpOASES): At most six output arguments are allowed: \n [x,fval,exitflag,iter,lambda,auxOutput]!" );
301 myMexErrMsgTxt(
"ERROR (qpOASES): At least one output argument is required: [x,...]!" );
311 if ( mxIsEmpty(prhs[0]) == 1 )
314 nV = (
int_t)mxGetM( prhs[ g_idx ] );
319 nV = (
int_t)mxGetM( prhs[ H_idx ] );
322 nP = (
int_t)mxGetN( prhs[ g_idx ] );
331 if ( isSimplyBoundedQp ==
BT_TRUE )
333 if ( ( nrhs >= 5 ) && ( !mxIsEmpty(prhs[4]) ) && ( mxIsStruct(prhs[4]) ) )
339 if ( ( !mxIsEmpty(prhs[4]) ) && ( mxIsStruct(prhs[4]) ) )
341 myMexErrMsgTxt(
"ERROR (qpOASES): Fifth input argument must not be a struct when solving QP with general constraints!\nType 'help qpOASES' for further information." );
345 if ( ( nrhs >= 8 ) && ( !mxIsEmpty(prhs[7]) ) && ( mxIsStruct(prhs[7]) ) )
350 int_t numberOfColumns = (
int_t)mxGetN(prhs[2]);
353 if ( ( isSimplyBoundedQp ==
BT_TRUE ) ||
354 ( ( numberOfColumns == 1 ) && ( nV != 1 ) ) )
359 if ( ( nrhs >= 6 ) && ( !mxIsEmpty(prhs[5]) ) )
362 if ( mxIsStruct(prhs[5]) )
384 if ( mxIsEmpty( prhs[ A_idx ] ) )
398 nC = (
int_t)mxGetM( prhs[ A_idx ] );
401 if ( ( nrhs >= 9 ) && ( !mxIsEmpty(prhs[8]) ) )
404 if ( mxIsStruct(prhs[8]) )
424 if ( ( ( H_idx >= 0 ) && ( mxIsDouble( prhs[ H_idx ] ) == 0 ) ) ||
425 ( mxIsDouble( prhs[ g_idx ] ) == 0 ) )
427 myMexErrMsgTxt(
"ERROR (qpOASES): All data has to be provided in double precision!" );
445 if ( ( H_idx >= 0 ) && ( ( mxGetN( prhs[ H_idx ] ) != nV ) || ( mxGetM( prhs[ H_idx ] ) != nV ) ) )
448 snprintf(msg,
MAX_STRING_LENGTH,
"ERROR (qpOASES): Hessian matrix dimension mismatch (%ld != %d)!",
449 (
long int)mxGetN(prhs[H_idx]), (
int)nV);
457 if ( mxIsDouble( prhs[ A_idx ] ) == 0 )
459 myMexErrMsgTxt(
"ERROR (qpOASES): All data has to be provided in real_t precision!" );
464 if ( mxGetN( prhs[ A_idx ] ) != nV )
467 snprintf(msg,
MAX_STRING_LENGTH,
"ERROR (qpOASES): Constraint matrix input dimension mismatch (%ld != %d)!",
468 (
long int)mxGetN(prhs[A_idx]), (
int)nV);
505 if ( auxInput_idx >= 0 )
506 setupAuxiliaryInputs( prhs[auxInput_idx],nV,nC, &hessianType,&x0,&guessedBounds,&guessedConstraints,&R_for );
516 int_t nWSRin = 5*(nV+nC);
517 real_t maxCpuTimeIn = -1.0;
519 if ( options_idx > 0 )
520 setupOptions( &options,prhs[options_idx],nWSRin,maxCpuTimeIn );
527 if ( ( nC > 0 ) && ( A_idx >= 0 ) )
544 if (
R != 0)
delete R;
545 if (H != 0)
delete H;
546 if (Hv != 0)
delete[] Hv;
547 if (Hjc != 0)
delete[] Hjc;
548 if (Hir != 0)
delete[] Hir;
555 myMexErrMsgTxt(
"ERROR (qpOASES): Internal interface error related to constraint matrix!" );
566 guessedBounds,guessedConstraints,
R 569 if (
R != 0)
delete R;
570 if (A != 0)
delete A;
571 if (H != 0)
delete H;
572 if (Av != 0)
delete[] Av;
573 if (Ajc != 0)
delete[] Ajc;
574 if (Air != 0)
delete[] Air;
575 if (Hv != 0)
delete[] Hv;
576 if (Hjc != 0)
delete[] Hjc;
577 if (Hir != 0)
delete[] Hir;
#define USING_NAMESPACE_QPOASES
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)
BooleanType containsNaNorInf(const mxArray *prhs[], int_t rhs_index, bool mayContainInf)
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.
int_t QProblem_qpOASES(int_t nV, int_t nC, HessianType hessianType, int_t nP, SymmetricMatrix *H, double *g, Matrix *A, double *lb, double *ub, double *lbA, double *ubA, int_t nWSRin, real_t maxCpuTimeIn, const double *const x0, Options *options, int_t nOutputs, mxArray *plhs[], const double *const guessedBounds, const double *const guessedConstraints, const double *const _R)
returnValue setupOptions(Options *options, const mxArray *optionsPtr, int &nWSRin)
Allows to pass back messages to the calling function.
void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
returnValue smartDimensionCheck(real_t **input, unsigned int m, unsigned int n, BooleanType emptyAllowed, const mxArray *prhs[], int idx)
returnValue init(const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int &nWSR, const real_t *const yOpt=0, real_t *const cputime=0)
returnValue hotstart(const real_t *const g_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)
returnValue convertFortranToC(const real_t *const A_for, int nV, int nC, real_t *const A)
returnValue setupBound(int _number, SubjectToStatus _status)
returnValue setOptions(const Options &_options)
returnValue hotstart(const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int &nWSR, real_t *const cputime)
void allocateOutputs(int nlhs, mxArray *plhs[], int nV, int nC=0, int nP=1)
returnValue setupAuxiliaryInputs(const mxArray *auxInput, uint_t nV, uint_t nC, HessianType *hessianType, double **x0, double **guessedBounds, double **guessedConstraints, double **R)
static std::vector< QPInstance * > g_instances
returnValue setupConstraint(int _number, SubjectToStatus _status)
Provides a generic way to set and pass user-specified options.
int_t QProblemB_qpOASES(int_t nV, HessianType hessianType, int_t nP, SymmetricMatrix *H, double *g, double *lb, double *ub, int_t nWSRin, real_t maxCpuTimeIn, const double *const x0, Options *options, int_t nOutputs, mxArray *plhs[], const double *const guessedBounds, const double *const _R)
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)
const uint_t MAX_STRING_LENGTH
returnValue setupConstraintMatrix(const mxArray *prhsA, int_t nV, int_t nC, Matrix **A, sparse_int_t **Air, sparse_int_t **Ajc, real_t **Av)
static int_t s_nexthandle
Manages working sets of bounds (= box constraints).
Implements the online active set strategy for QPs with general constraints.
BooleanType isEqual(real_t x, real_t y, real_t TOL=ZERO)
Abstract base class for interfacing matrix-vector operations tailored to symmetric matrices...