48 #define S_FUNCTION_NAME qpOASES_e_QProblem 49 #define S_FUNCTION_LEVEL 2 57 #define SAMPLINGTIME -1 58 #define NCONTROLINPUTS 2 60 #define HESSIANTYPE HST_UNKNOWN 64 static void mdlInitializeSizes (SimStruct *S) 69 ssSetNumContStates(
S, 0);
70 ssSetNumDiscStates(
S, 0);
73 ssSetNumSFcnParams(
S, 2);
74 if ( ssGetNumSFcnParams(
S) != ssGetSFcnParamsCount(
S) )
78 if ( !ssSetNumInputPorts(
S, 5) )
82 if ( !ssSetNumOutputPorts(
S, 4) )
86 ssSetInputPortVectorDimension(
S, 0, DYNAMICALLY_SIZED);
87 ssSetInputPortVectorDimension(
S, 1, DYNAMICALLY_SIZED);
88 ssSetInputPortVectorDimension(
S, 2, DYNAMICALLY_SIZED);
89 ssSetInputPortVectorDimension(
S, 3, DYNAMICALLY_SIZED);
90 ssSetInputPortVectorDimension(
S, 4, DYNAMICALLY_SIZED);
93 ssSetOutputPortVectorDimension(
S, 0, nU );
94 ssSetOutputPortVectorDimension(
S, 1, 1 );
95 ssSetOutputPortVectorDimension(
S, 2, 1 );
96 ssSetOutputPortVectorDimension(
S, 3, 1 );
99 ssSetInputPortDirectFeedThrough(
S, 0, 1);
100 ssSetInputPortDirectFeedThrough(
S, 1, 1);
101 ssSetInputPortDirectFeedThrough(
S, 2, 1);
102 ssSetInputPortDirectFeedThrough(
S, 3, 1);
103 ssSetInputPortDirectFeedThrough(
S, 4, 1);
104 ssSetInputPortDirectFeedThrough(
S, 5, 1);
105 ssSetInputPortDirectFeedThrough(
S, 6, 1);
108 ssSetNumSampleTimes(
S, 1);
126 #if defined(MATLAB_MEX_FILE) 128 #define MDL_SET_INPUT_PORT_DIMENSION_INFO 129 #define MDL_SET_OUTPUT_PORT_DIMENSION_INFO 131 static void mdlSetInputPortDimensionInfo(SimStruct *
S, int_T port,
const DimsInfo_T *dimsInfo)
133 if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) )
137 static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port,
const DimsInfo_T *dimsInfo)
139 if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) )
149 ssSetOffsetTime(S, 0, 0.0);
158 int size_g, size_lb, size_ub, size_lbA, size_ubA;
159 int size_H, nRows_H, nCols_H, size_A, nRows_A, nCols_A;
167 const mxArray* in_H = ssGetSFcnParam(S, 0);
168 const mxArray* in_A = ssGetSFcnParam(S, 1);
170 if ( mxIsEmpty(in_H) == 1 )
174 #ifndef __SUPPRESSANYOUTPUT__ 175 mexErrMsgTxt(
"ERROR (qpOASES): Hessian can only be empty if type is set to HST_ZERO or HST_IDENTITY!" );
186 nRows_H = (int)mxGetM(in_H);
187 nCols_H = (int)mxGetN(in_H);
188 size_H = nRows_H * nCols_H;
191 if ( mxIsEmpty(in_A) == 1 )
199 nRows_A = (int)mxGetM(in_A);
200 nCols_A = (int)mxGetN(in_A);
201 size_A = nRows_A * nCols_A;
204 size_g = ssGetInputPortWidth(S, 0);
205 size_lb = ssGetInputPortWidth(S, 1);
206 size_ub = ssGetInputPortWidth(S, 2);
207 size_lbA = ssGetInputPortWidth(S, 3);
208 size_ubA = ssGetInputPortWidth(S, 4);
218 #ifndef __SUPPRESSANYOUTPUT__ 219 mexErrMsgTxt(
"ERROR (qpOASES): Maximum number of iterations must not be negative!" );
226 #ifndef __SUPPRESSANYOUTPUT__ 227 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch (nV must be positive)!" );
232 if ( ( size_H != nV*nV ) && ( size_H != 0 ) )
234 #ifndef __SUPPRESSANYOUTPUT__ 235 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in H!" );
240 if ( nRows_H != nCols_H )
242 #ifndef __SUPPRESSANYOUTPUT__ 243 mexErrMsgTxt(
"ERROR (qpOASES): Hessian matrix must be square matrix!" );
248 if ( ( nU < 1 ) || ( nU > nV ) )
250 #ifndef __SUPPRESSANYOUTPUT__ 251 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of control inputs!" );
256 if ( ( size_lb != nV ) && ( size_lb != 0 ) )
258 #ifndef __SUPPRESSANYOUTPUT__ 259 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in lb!" );
264 if ( ( size_ub != nV ) && ( size_lb != 0 ) )
266 #ifndef __SUPPRESSANYOUTPUT__ 267 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in ub!" );
272 if ( ( size_lbA != nC ) && ( size_lbA != 0 ) )
274 #ifndef __SUPPRESSANYOUTPUT__ 275 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in lbA!" );
280 if ( ( size_ubA != nC ) && ( size_ubA != 0 ) )
282 #ifndef __SUPPRESSANYOUTPUT__ 283 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in ubA!" );
297 #ifdef __SUPPRESSANYOUTPUT__ 301 ssGetPWork(S)[0] = (
void*)(&problem);
305 ssGetPWork(S)[1] = (
void *) calloc( size_H,
sizeof(
real_t) );
307 ssGetPWork(S)[1] = 0;
309 ssGetPWork(S)[2] = (
void *) calloc( size_g,
sizeof(
real_t) );
310 ssGetPWork(S)[3] = (
void *) calloc( size_A,
sizeof(
real_t) );
313 ssGetPWork(S)[4] = (
void *) calloc( size_lb,
sizeof(
real_t) );
315 ssGetPWork(S)[4] = 0;
318 ssGetPWork(S)[5] = (
void *) calloc( size_ub,
sizeof(
real_t) );
320 ssGetPWork(S)[5] = 0;
323 ssGetPWork(S)[6] = (
void *) calloc( size_lbA,
sizeof(
real_t) );
325 ssGetPWork(S)[6] = 0;
328 ssGetPWork(S)[7] = (
void *) calloc( size_ubA,
sizeof(
real_t) );
330 ssGetPWork(S)[7] = 0;
345 InputRealPtrsType in_g, in_lb, in_ub, in_lbA, in_ubA;
353 real_T *out_uOpt, *out_objVal, *out_status, *out_nWSR;
354 real_t stat, feas, cmpl, kktTol;
359 char fileName[20] =
"qpData000000000.mat";
363 const mxArray* in_H = ssGetSFcnParam(S, 0);
364 const mxArray* in_A = ssGetSFcnParam(S, 1);
365 in_g = ssGetInputPortRealSignalPtrs(S, 0);
366 in_lb = ssGetInputPortRealSignalPtrs(S, 1);
367 in_ub = ssGetInputPortRealSignalPtrs(S, 2);
368 in_lbA = ssGetInputPortRealSignalPtrs(S, 3);
369 in_ubA = ssGetInputPortRealSignalPtrs(S, 4);
373 problem = (
QProblem*)(ssGetPWork(S)[0]);
375 H = (
real_t*)(ssGetPWork(S)[1]);
376 g = (
real_t*)(ssGetPWork(S)[2]);
377 A = (
real_t*)(ssGetPWork(S)[3]);
378 lb = (
real_t*)(ssGetPWork(S)[4]);
379 ub = (
real_t*)(ssGetPWork(S)[5]);
380 lbA = (
real_t*)(ssGetPWork(S)[6]);
381 ubA = (
real_t*)(ssGetPWork(S)[7]);
385 nV = ssGetInputPortWidth(S, 0);
386 nC = (int)mxGetM(in_A);
391 for ( i=0; i<nV*nV; ++i )
392 H[i] = (mxGetPr(in_H))[i];
397 for ( i=0; i<nV; ++i )
402 for ( i=0; i<nV; ++i )
408 for ( i=0; i<nV; ++i )
414 for ( i=0; i<nC; ++i )
415 lbA[i] = (*in_lbA)[i];
420 for ( i=0; i<nC; ++i )
421 ubA[i] = (*in_ubA)[i];
425 #ifdef __SIMULINK_DEBUG__ 428 matFile = fopen( fileName,
"w+" );
444 status =
QProblem_init( problem,H,g,A,lb,ub,lbA,ubA, &nWSR,0 );
459 status =
QProblem_init( problem,H,g,A,lb,ub,lbA,ubA, &nWSR_retry,0 );
470 out_uOpt = ssGetOutputPortRealSignal(S, 0);
471 out_objVal = ssGetOutputPortRealSignal(S, 1);
472 out_status = ssGetOutputPortRealSignal(S, 2);
473 out_nWSR = ssGetOutputPortRealSignal(S, 3);
475 for ( i=0; i<nU; ++i )
476 out_uOpt[i] = (real_T)(xOpt[i]);
480 out_nWSR[0] = (real_T)(nWSR);
487 #ifdef __SIMULINK_DEBUG__ 494 mexPrintf(
"KKT residuals: stat=%e, feas=%e, cmpl=%e\n", stat,feas,cmpl );
518 for ( i=1; i<8; ++i )
520 if ( ssGetPWork(S)[i] != 0 )
521 free( ssGetPWork(S)[i] );
526 #ifdef MATLAB_MEX_FILE 527 #include "simulink.c" #define USING_NAMESPACE_QPOASES
returnValue QProblem_getPrimalSolution(QProblem *_THIS, real_t *const xOpt)
static void mdlTerminate(SimStruct *S)
static void mdlInitializeSampleTimes(SimStruct *S)
returnValue qpOASES_getKktViolation(int nV, int nC, 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, const real_t *const x, const real_t *const y, real_t *const _stat, real_t *const feas, real_t *const cmpl)
int qpOASES_getSimpleStatus(returnValue returnvalue, BooleanType doPrintStatus)
Allows to pass back messages to the calling function.
returnValue convertFortranToC(const real_t *const A_for, int nV, int nC, real_t *const A)
returnValue MessageHandling_reset(MessageHandling *_THIS)
returnValue removeNaNs(real_t *const data, unsigned int dim)
returnValue QProblem_setPrintLevel(QProblem *_THIS, PrintLevel _printlevel)
static real_t qpOASES_getAbs(real_t x)
Provides a generic way to set and pass user-specified options.
real_t QProblem_getObjVal(QProblem *_THIS)
static void mdlOutputs(SimStruct *S, int_T tid)
returnValue qpOASES_writeIntoMatFile(FILE *const matFile, const real_t *const data, int nRows, int nCols, const char *name)
int_t QProblem_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_t *const nWSR, real_t *const cputime, const qpOASES_Options *const options, real_t *const x, real_t *const y, real_t *const obj, int_t *const status)
returnValue Options_setToMPC(Options *_THIS)
MessageHandling * qpOASES_getGlobalMessageHandler()
returnValue QProblem_getDualSolution(QProblem *_THIS, real_t *const yOpt)
static void mdlStart(SimStruct *S)
static const real_t QPOASES_EPS
static unsigned int QProblem_getCount(QProblem *_THIS)
returnValue QProblem_reset(QProblem *_THIS)
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)
returnValue removeInfs(real_t *const data, unsigned int dim)
Implements the online active set strategy for QPs with general constraints.
void QProblemCON(QProblem *_THIS, int _nV, int _nC, HessianType _hessianType)
static returnValue QProblem_setOptions(QProblem *_THIS, Options _options)