39 #include <qpOASES.hpp> 48 #define S_FUNCTION_NAME qpOASES_QProblem 49 #define S_FUNCTION_LEVEL 2 57 #define SAMPLINGTIME -1 58 #define NCONTROLINPUTS 2 60 #define HESSIANTYPE HST_UNKNOWN 63 static void mdlInitializeSizes (SimStruct *S) 68 ssSetNumContStates(
S, 0);
69 ssSetNumDiscStates(
S, 0);
72 ssSetNumSFcnParams(
S, 2);
73 if ( ssGetNumSFcnParams(
S) != ssGetSFcnParamsCount(
S) )
77 if ( !ssSetNumInputPorts(
S, 5) )
81 if ( !ssSetNumOutputPorts(
S, 4) )
85 ssSetInputPortVectorDimension(
S, 0, DYNAMICALLY_SIZED);
86 ssSetInputPortVectorDimension(
S, 1, DYNAMICALLY_SIZED);
87 ssSetInputPortVectorDimension(
S, 2, DYNAMICALLY_SIZED);
88 ssSetInputPortVectorDimension(
S, 3, DYNAMICALLY_SIZED);
89 ssSetInputPortVectorDimension(
S, 4, DYNAMICALLY_SIZED);
92 ssSetOutputPortVectorDimension(
S, 0, nU );
93 ssSetOutputPortVectorDimension(
S, 1, 1 );
94 ssSetOutputPortVectorDimension(
S, 2, 1 );
95 ssSetOutputPortVectorDimension(
S, 3, 1 );
98 ssSetInputPortDirectFeedThrough(
S, 0, 1);
99 ssSetInputPortDirectFeedThrough(
S, 1, 1);
100 ssSetInputPortDirectFeedThrough(
S, 2, 1);
101 ssSetInputPortDirectFeedThrough(
S, 3, 1);
102 ssSetInputPortDirectFeedThrough(
S, 4, 1);
105 ssSetNumSampleTimes(
S, 1);
123 #if defined(MATLAB_MEX_FILE) 125 #define MDL_SET_INPUT_PORT_DIMENSION_INFO 126 #define MDL_SET_OUTPUT_PORT_DIMENSION_INFO 128 static void mdlSetInputPortDimensionInfo(SimStruct *
S, int_T port,
const DimsInfo_T *dimsInfo)
130 if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) )
134 static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port,
const DimsInfo_T *dimsInfo)
136 if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) )
146 ssSetOffsetTime(S, 0, 0.0);
155 int size_g, size_lb, size_ub, size_lbA, size_ubA;
156 int size_H, nRows_H, nCols_H, size_A, nRows_A, nCols_A;
163 const mxArray* in_H = ssGetSFcnParam(S, 0);
164 const mxArray* in_A = ssGetSFcnParam(S, 1);
166 if ( mxIsEmpty(in_H) == 1 )
170 #ifndef __SUPPRESSANYOUTPUT__ 171 mexErrMsgTxt(
"ERROR (qpOASES): Hessian can only be empty if type is set to HST_ZERO or HST_IDENTITY!" );
182 nRows_H = (int)mxGetM(in_H);
183 nCols_H = (int)mxGetN(in_H);
184 size_H = nRows_H * nCols_H;
187 if ( mxIsEmpty(in_A) == 1 )
195 nRows_A = (int)mxGetM(in_A);
196 nCols_A = (int)mxGetN(in_A);
197 size_A = nRows_A * nCols_A;
200 size_g = ssGetInputPortWidth(S, 0);
201 size_lb = ssGetInputPortWidth(S, 1);
202 size_ub = ssGetInputPortWidth(S, 2);
203 size_lbA = ssGetInputPortWidth(S, 3);
204 size_ubA = ssGetInputPortWidth(S, 4);
214 #ifndef __SUPPRESSANYOUTPUT__ 215 mexErrMsgTxt(
"ERROR (qpOASES): Maximum number of iterations must not be negative!" );
222 #ifndef __SUPPRESSANYOUTPUT__ 223 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch!" );
228 if ( ( size_H != nV*nV ) && ( size_H != 0 ) )
230 #ifndef __SUPPRESSANYOUTPUT__ 231 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in H!" );
236 if ( nRows_H != nCols_H )
238 #ifndef __SUPPRESSANYOUTPUT__ 239 mexErrMsgTxt(
"ERROR (qpOASES): Hessian matrix must be square matrix!" );
244 if ( ( nU < 1 ) || ( nU > nV ) )
246 #ifndef __SUPPRESSANYOUTPUT__ 247 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of control inputs!" );
252 if ( ( size_lb != nV ) && ( size_lb != 0 ) )
254 #ifndef __SUPPRESSANYOUTPUT__ 255 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in lb!" );
260 if ( ( size_ub != nV ) && ( size_lb != 0 ) )
262 #ifndef __SUPPRESSANYOUTPUT__ 263 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in ub!" );
268 if ( ( size_lbA != nC ) && ( size_lbA != 0 ) )
270 #ifndef __SUPPRESSANYOUTPUT__ 271 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in lbA!" );
276 if ( ( size_ubA != nC ) && ( size_ubA != 0 ) )
278 #ifndef __SUPPRESSANYOUTPUT__ 279 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in ubA!" );
289 #ifndef __SUPPRESSANYOUTPUT__ 290 mexErrMsgTxt(
"ERROR (qpOASES): Unable to create QProblem object!" );
302 #ifdef __SUPPRESSANYOUTPUT__ 306 ssGetPWork(S)[0] = (
void *) problem;
310 ssGetPWork(S)[1] = (
void *) calloc( size_H,
sizeof(
real_t) );
312 ssGetPWork(S)[1] = 0;
314 ssGetPWork(S)[2] = (
void *) calloc( size_g,
sizeof(
real_t) );
315 ssGetPWork(S)[3] = (
void *) calloc( size_A,
sizeof(
real_t) );
318 ssGetPWork(S)[4] = (
void *) calloc( size_lb,
sizeof(
real_t) );
320 ssGetPWork(S)[4] = 0;
323 ssGetPWork(S)[5] = (
void *) calloc( size_ub,
sizeof(
real_t) );
325 ssGetPWork(S)[5] = 0;
328 ssGetPWork(S)[6] = (
void *) calloc( size_lbA,
sizeof(
real_t) );
330 ssGetPWork(S)[6] = 0;
333 ssGetPWork(S)[7] = (
void *) calloc( size_ubA,
sizeof(
real_t) );
335 ssGetPWork(S)[7] = 0;
350 InputRealPtrsType in_g, in_lb, in_ub, in_lbA, in_ubA;
357 real_T *out_uOpt, *out_objVal, *out_status, *out_nWSR;
361 const mxArray* in_H = ssGetSFcnParam(S, 0);
362 const mxArray* in_A = ssGetSFcnParam(S, 1);
363 in_g = ssGetInputPortRealSignalPtrs(S, 0);
364 in_lb = ssGetInputPortRealSignalPtrs(S, 1);
365 in_ub = ssGetInputPortRealSignalPtrs(S, 2);
366 in_lbA = ssGetInputPortRealSignalPtrs(S, 3);
367 in_ubA = ssGetInputPortRealSignalPtrs(S, 4);
371 problem = (
QProblem*)(ssGetPWork(S)[0]);
373 H = (
real_t *) ssGetPWork(S)[1];
374 g = (
real_t *) ssGetPWork(S)[2];
375 A = (
real_t *) ssGetPWork(S)[3];
376 lb = (
real_t *) ssGetPWork(S)[4];
377 ub = (
real_t *) ssGetPWork(S)[5];
378 lbA = (
real_t *) ssGetPWork(S)[6];
379 ubA = (
real_t *) ssGetPWork(S)[7];
383 nV = ssGetInputPortWidth(S, 0);
384 nC = (int)mxGetM(in_A);
389 for ( i=0; i<nV*nV; ++i )
390 H[i] = (mxGetPr(in_H))[i];
395 for ( i=0; i<nV; ++i )
400 for ( i=0; i<nV; ++i )
406 for ( i=0; i<nV; ++i )
412 for ( i=0; i<nC; ++i )
413 lbA[i] = (*in_lbA)[i];
418 for ( i=0; i<nC; ++i )
419 ubA[i] = (*in_ubA)[i];
427 status = problem->
init( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
433 status = problem->
hotstart( g,lb,ub,lbA,ubA, nWSR,0 );
441 status = problem->
init( H,g,A,lb,ub,lbA,ubA, nWSR_retry,0 );
451 out_uOpt = ssGetOutputPortRealSignal(S, 0);
452 out_objVal = ssGetOutputPortRealSignal(S, 1);
453 out_status = ssGetOutputPortRealSignal(S, 2);
454 out_nWSR = ssGetOutputPortRealSignal(S, 3);
456 for ( i=0; i<nU; ++i )
457 out_uOpt[i] = (real_T)(xOpt[i]);
459 out_objVal[0] = (real_T)(problem->
getObjVal());
461 out_nWSR[0] = (real_T)(nWSR);
481 if ( ssGetPWork(S)[0] != 0 )
482 delete ((
QProblem*)(ssGetPWork(S)[0]));
484 for ( i=1; i<8; ++i )
486 if ( ssGetPWork(S)[i] != 0 )
487 free( ssGetPWork(S)[i] );
492 #ifdef MATLAB_MEX_FILE 493 #include "simulink.c" returnValue getPrimalSolution(real_t *const xOpt) const
static void mdlTerminate(SimStruct *S)
#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)
Allows to pass back messages to the calling function.
static void mdlStart(SimStruct *S)
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)
static void mdlOutputs(SimStruct *S, int_T tid)
returnValue removeNaNs(real_t *const data, unsigned int dim)
returnValue setOptions(const Options &_options)
Provides a generic way to set and pass user-specified options.
static void mdlInitializeSampleTimes(SimStruct *S)
int_t getSimpleStatus(returnValue returnvalue, BooleanType doPrintStatus=BT_FALSE)
returnValue removeInfs(real_t *const data, unsigned int dim)
Implements the online active set strategy for QPs with general constraints.
MessageHandling * getGlobalMessageHandler()
returnValue setPrintLevel(PrintLevel _printlevel)