39 #include <qpOASES.hpp> 48 #define S_FUNCTION_NAME qpOASES_SQProblem 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, 0);
73 if ( ssGetNumSFcnParams(
S) != ssGetSFcnParamsCount(
S) )
77 if ( !ssSetNumInputPorts(
S, 7) )
79 #ifndef __SUPPRESSANYOUTPUT__ 80 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of input ports!" );
86 if ( !ssSetNumOutputPorts(
S, 4) )
88 #ifndef __SUPPRESSANYOUTPUT__ 89 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of output ports!" );
95 ssSetInputPortVectorDimension(
S, 0, DYNAMICALLY_SIZED);
96 ssSetInputPortVectorDimension(
S, 1, DYNAMICALLY_SIZED);
97 ssSetInputPortVectorDimension(
S, 2, DYNAMICALLY_SIZED);
98 ssSetInputPortVectorDimension(
S, 3, DYNAMICALLY_SIZED);
99 ssSetInputPortVectorDimension(
S, 4, DYNAMICALLY_SIZED);
100 ssSetInputPortVectorDimension(
S, 5, DYNAMICALLY_SIZED);
101 ssSetInputPortVectorDimension(
S, 6, DYNAMICALLY_SIZED);
104 ssSetOutputPortVectorDimension(
S, 0, nU );
105 ssSetOutputPortVectorDimension(
S, 1, 1 );
106 ssSetOutputPortVectorDimension(
S, 2, 1 );
107 ssSetOutputPortVectorDimension(
S, 3, 1 );
110 ssSetInputPortDirectFeedThrough(
S, 0, 1);
111 ssSetInputPortDirectFeedThrough(
S, 1, 1);
112 ssSetInputPortDirectFeedThrough(
S, 2, 1);
113 ssSetInputPortDirectFeedThrough(
S, 3, 1);
114 ssSetInputPortDirectFeedThrough(
S, 4, 1);
115 ssSetInputPortDirectFeedThrough(
S, 5, 1);
116 ssSetInputPortDirectFeedThrough(
S, 6, 1);
119 ssSetNumSampleTimes(
S, 1);
137 #if defined(MATLAB_MEX_FILE) 139 #define MDL_SET_INPUT_PORT_DIMENSION_INFO 140 #define MDL_SET_OUTPUT_PORT_DIMENSION_INFO 142 static void mdlSetInputPortDimensionInfo(SimStruct *
S, int_T port,
const DimsInfo_T *dimsInfo)
144 if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) )
148 static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port,
const DimsInfo_T *dimsInfo)
150 if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) )
160 ssSetOffsetTime(S, 0, 0.0);
169 int size_H, size_g, size_A, size_lb, size_ub, size_lbA, size_ubA;
176 size_H = ssGetInputPortWidth(S, 0);
177 size_g = ssGetInputPortWidth(S, 1);
178 size_A = ssGetInputPortWidth(S, 2);
179 size_lb = ssGetInputPortWidth(S, 3);
180 size_ub = ssGetInputPortWidth(S, 4);
181 size_lbA = ssGetInputPortWidth(S, 5);
182 size_ubA = ssGetInputPortWidth(S, 6);
191 #ifndef __SUPPRESSANYOUTPUT__ 192 mexErrMsgTxt(
"ERROR (qpOASES): Maximum number of iterations must not be negative!" );
199 #ifndef __SUPPRESSANYOUTPUT__ 200 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch!" );
205 if ( ( size_H != nV*nV ) && ( size_H != 0 ) )
207 #ifndef __SUPPRESSANYOUTPUT__ 208 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in H!" );
213 if ( ( nU < 1 ) || ( nU > nV ) )
215 #ifndef __SUPPRESSANYOUTPUT__ 216 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of control inputs!" );
221 if ( ( size_lb != nV ) && ( size_lb != 0 ) )
223 #ifndef __SUPPRESSANYOUTPUT__ 224 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in lb!" );
229 if ( ( size_ub != nV ) && ( size_ub != 0 ) )
231 #ifndef __SUPPRESSANYOUTPUT__ 232 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in ub!" );
237 if ( ( size_lbA != nC ) && ( size_lbA != 0 ) )
239 #ifndef __SUPPRESSANYOUTPUT__ 240 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in lbA!" );
245 if ( ( size_ubA != nC ) && ( size_ubA != 0 ) )
247 #ifndef __SUPPRESSANYOUTPUT__ 248 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in ubA!" );
258 #ifndef __SUPPRESSANYOUTPUT__ 259 mexErrMsgTxt(
"ERROR (qpOASES): Unable to create SQProblem object!" );
271 #ifdef __SUPPRESSANYOUTPUT__ 275 ssGetPWork(S)[0] = (
void *) problem;
279 ssGetPWork(S)[1] = (
void *) calloc( size_H,
sizeof(
real_t) );
281 ssGetPWork(S)[1] = 0;
283 ssGetPWork(S)[2] = (
void *) calloc( size_g,
sizeof(
real_t) );
284 ssGetPWork(S)[3] = (
void *) calloc( size_A,
sizeof(
real_t) );
287 ssGetPWork(S)[4] = (
void *) calloc( size_lb,
sizeof(
real_t) );
289 ssGetPWork(S)[4] = 0;
292 ssGetPWork(S)[5] = (
void *) calloc( size_ub,
sizeof(
real_t) );
294 ssGetPWork(S)[5] = 0;
297 ssGetPWork(S)[6] = (
void *) calloc( size_lbA,
sizeof(
real_t) );
299 ssGetPWork(S)[6] = 0;
302 ssGetPWork(S)[7] = (
void *) calloc( size_ubA,
sizeof(
real_t) );
304 ssGetPWork(S)[7] = 0;
320 InputRealPtrsType in_H, in_g, in_A, in_lb, in_ub, in_lbA, in_ubA;
327 real_T *out_uOpt, *out_objVal, *out_status, *out_nWSR;
331 in_H = ssGetInputPortRealSignalPtrs(S, 0);
332 in_g = ssGetInputPortRealSignalPtrs(S, 1);
333 in_A = ssGetInputPortRealSignalPtrs(S, 2);
334 in_lb = ssGetInputPortRealSignalPtrs(S, 3);
335 in_ub = ssGetInputPortRealSignalPtrs(S, 4);
336 in_lbA = ssGetInputPortRealSignalPtrs(S, 5);
337 in_ubA = ssGetInputPortRealSignalPtrs(S, 6);
343 H = (
real_t *) ssGetPWork(S)[1];
344 g = (
real_t *) ssGetPWork(S)[2];
345 A = (
real_t *) ssGetPWork(S)[3];
346 lb = (
real_t *) ssGetPWork(S)[4];
347 ub = (
real_t *) ssGetPWork(S)[5];
348 lbA = (
real_t *) ssGetPWork(S)[6];
349 ubA = (
real_t *) ssGetPWork(S)[7];
353 nV = ssGetInputPortWidth(S, 1);
354 nC = (int) ( ((
real_t) ssGetInputPortWidth(S, 2)) / ((
real_t) nV) );
359 for ( i=0; i<nV*nV; ++i )
365 for ( i=0; i<nV; ++i )
370 for ( i=0; i<nV; ++i )
376 for ( i=0; i<nV; ++i )
382 for ( i=0; i<nC; ++i )
383 lbA[i] = (*in_lbA)[i];
388 for ( i=0; i<nC; ++i )
389 ubA[i] = (*in_ubA)[i];
397 status = problem->
init( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
403 status = problem->
hotstart( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
411 status = problem->
init( H,g,A,lb,ub,lbA,ubA, nWSR_retry,0 );
420 out_uOpt = ssGetOutputPortRealSignal(S, 0);
421 out_objVal = ssGetOutputPortRealSignal(S, 1);
422 out_status = ssGetOutputPortRealSignal(S, 2);
423 out_nWSR = ssGetOutputPortRealSignal(S, 3);
425 for ( i=0; i<nU; ++i )
426 out_uOpt[i] = (real_T)(xOpt[i]);
428 out_objVal[0] = (real_T)(problem->
getObjVal( ));
430 out_nWSR[0] = (real_T)(nWSR);
450 if ( ssGetPWork(S)[0] != 0 )
453 for ( i=1; i<8; ++i )
455 if ( ssGetPWork(S)[i] != 0 )
456 free( ssGetPWork(S)[i] );
461 #ifdef MATLAB_MEX_FILE 462 #include "simulink.c" returnValue getPrimalSolution(real_t *const xOpt) const
#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)
static void mdlTerminate(SimStruct *S)
Implements the online active set strategy for QPs with varying matrices.
Allows to pass back messages to the calling function.
static void mdlStart(SimStruct *S)
returnValue convertFortranToC(const real_t *const A_for, int nV, int nC, real_t *const A)
returnValue removeNaNs(real_t *const data, unsigned int dim)
static void mdlOutputs(SimStruct *S, int_T tid)
returnValue setOptions(const Options &_options)
static void mdlInitializeSampleTimes(SimStruct *S)
Provides a generic way to set and pass user-specified options.
int_t getSimpleStatus(returnValue returnvalue, BooleanType doPrintStatus=BT_FALSE)
returnValue removeInfs(real_t *const data, unsigned int dim)
MessageHandling * getGlobalMessageHandler()
returnValue setPrintLevel(PrintLevel _printlevel)
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)