39 #include <qpOASES.hpp> 48 #define S_FUNCTION_NAME qpOASES_QProblemB 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, 1);
73 if ( ssGetNumSFcnParams(
S) != ssGetSFcnParamsCount(
S) )
77 if ( !ssSetNumInputPorts(
S, 3) )
81 if ( !ssSetNumOutputPorts(
S, 4) )
85 ssSetInputPortVectorDimension(
S, 0, DYNAMICALLY_SIZED);
86 ssSetInputPortVectorDimension(
S, 1, DYNAMICALLY_SIZED);
87 ssSetInputPortVectorDimension(
S, 2, DYNAMICALLY_SIZED);
90 ssSetOutputPortVectorDimension(
S, 0, nU );
91 ssSetOutputPortVectorDimension(
S, 1, 1 );
92 ssSetOutputPortVectorDimension(
S, 2, 1 );
93 ssSetOutputPortVectorDimension(
S, 3, 1 );
96 ssSetInputPortDirectFeedThrough(
S, 0, 1);
97 ssSetInputPortDirectFeedThrough(
S, 1, 1);
98 ssSetInputPortDirectFeedThrough(
S, 2, 1);
101 ssSetNumSampleTimes(
S, 1);
116 #if defined(MATLAB_MEX_FILE) 118 #define MDL_SET_INPUT_PORT_DIMENSION_INFO 119 #define MDL_SET_OUTPUT_PORT_DIMENSION_INFO 121 static void mdlSetInputPortDimensionInfo(SimStruct *
S, int_T port,
const DimsInfo_T *dimsInfo)
123 if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) )
127 static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port,
const DimsInfo_T *dimsInfo)
129 if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) )
139 ssSetOffsetTime(S, 0, 0.0);
148 int size_g, size_lb, size_ub;
149 int size_H, nRows_H, nCols_H;
156 const mxArray* in_H = ssGetSFcnParam(S, 0);
158 if ( mxIsEmpty(in_H) == 1 )
162 #ifndef __SUPPRESSANYOUTPUT__ 163 mexErrMsgTxt(
"ERROR (qpOASES): Hessian can only be empty if type is set to HST_ZERO or HST_IDENTITY!" );
174 nRows_H = (int)mxGetM(in_H);
175 nCols_H = (int)mxGetN(in_H);
176 size_H = nRows_H * nCols_H;
179 size_g = ssGetInputPortWidth(S, 0);
180 size_lb = ssGetInputPortWidth(S, 1);
181 size_ub = ssGetInputPortWidth(S, 2);
189 #ifndef __SUPPRESSANYOUTPUT__ 190 mexErrMsgTxt(
"ERROR (qpOASES): Maximum number of iterations must not be negative!" );
197 #ifndef __SUPPRESSANYOUTPUT__ 198 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch!" );
203 if ( ( size_H != nV*nV ) && ( size_H != 0 ) )
205 #ifndef __SUPPRESSANYOUTPUT__ 206 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in H!" );
211 if ( nRows_H != nCols_H )
213 #ifndef __SUPPRESSANYOUTPUT__ 214 mexErrMsgTxt(
"ERROR (qpOASES): Hessian matrix must be square matrix!" );
219 if ( ( nU < 1 ) || ( nU > nV ) )
221 #ifndef __SUPPRESSANYOUTPUT__ 222 mexErrMsgTxt(
"ERROR (qpOASES): Invalid number of control inputs!" );
227 if ( ( size_lb != nV ) && ( size_lb != 0 ) )
229 #ifndef __SUPPRESSANYOUTPUT__ 230 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in lb!" );
235 if ( ( size_ub != nV ) && ( size_ub != 0 ) )
237 #ifndef __SUPPRESSANYOUTPUT__ 238 mexErrMsgTxt(
"ERROR (qpOASES): Dimension mismatch in ub!" );
248 #ifndef __SUPPRESSANYOUTPUT__ 249 mexErrMsgTxt(
"ERROR (qpOASES): Unable to create QProblemB object!" );
261 #ifdef __SUPPRESSANYOUTPUT__ 265 ssGetPWork(S)[0] = (
void *) problem;
269 ssGetPWork(S)[1] = (
void *) calloc( size_H,
sizeof(
real_t) );
271 ssGetPWork(S)[1] = 0;
273 ssGetPWork(S)[2] = (
void *) calloc( size_g,
sizeof(
real_t) );
276 ssGetPWork(S)[3] = (
void *) calloc( size_lb,
sizeof(
real_t) );
278 ssGetPWork(S)[3] = 0;
281 ssGetPWork(S)[4] = (
void *) calloc( size_ub,
sizeof(
real_t) );
283 ssGetPWork(S)[4] = 0;
298 InputRealPtrsType in_g, in_lb, in_ub;
305 real_T *out_uOpt, *out_objVal, *out_status, *out_nWSR;
309 const mxArray* in_H = ssGetSFcnParam(S, 0);
310 in_g = ssGetInputPortRealSignalPtrs(S, 0);
311 in_lb = ssGetInputPortRealSignalPtrs(S, 1);
312 in_ub = ssGetInputPortRealSignalPtrs(S, 2);
317 H = (
real_t *) ssGetPWork(S)[1];
318 g = (
real_t *) ssGetPWork(S)[2];
319 lb = (
real_t *) ssGetPWork(S)[3];
320 ub = (
real_t *) ssGetPWork(S)[4];
324 nV = ssGetInputPortWidth(S, 1);
329 for ( i=0; i<nV*nV; ++i )
330 H[i] = (mxGetPr(in_H))[i];
333 for ( i=0; i<nV; ++i )
338 for ( i=0; i<nV; ++i )
344 for ( i=0; i<nV; ++i )
353 status = problem->
init( H,g,lb,ub, nWSR,0 );
359 status = problem->
hotstart( g,lb,ub, nWSR,0 );
367 status = problem->
init( H,g,lb,ub, nWSR_retry,0 );
376 out_uOpt = ssGetOutputPortRealSignal(S, 0);
377 out_objVal = ssGetOutputPortRealSignal(S, 1);
378 out_status = ssGetOutputPortRealSignal(S, 2);
379 out_nWSR = ssGetOutputPortRealSignal(S, 3);
381 for ( i=0; i<nU; ++i )
382 out_uOpt[i] = (real_T)(xOpt[i]);
384 out_objVal[0] = (real_T)(problem->
getObjVal());
386 out_nWSR[0] = (real_T)(nWSR);
406 if ( ssGetPWork(S)[0] != 0 )
409 for ( i=1; i<5; ++i )
411 if ( ssGetPWork(S)[i] != 0 )
412 free( ssGetPWork(S)[i] );
417 #ifdef MATLAB_MEX_FILE 418 #include "simulink.c" returnValue getPrimalSolution(real_t *const xOpt) const
#define USING_NAMESPACE_QPOASES
static void mdlInitializeSampleTimes(SimStruct *S)
Implements the online active set strategy for box-constrained QPs.
Allows to pass back messages to the calling function.
static void mdlStart(SimStruct *S)
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 removeNaNs(real_t *const data, unsigned int dim)
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)
static void mdlOutputs(SimStruct *S, int_T tid)
Provides a generic way to set and pass user-specified options.
static void mdlTerminate(SimStruct *S)
int_t getSimpleStatus(returnValue returnvalue, BooleanType doPrintStatus=BT_FALSE)
returnValue removeInfs(real_t *const data, unsigned int dim)
MessageHandling * getGlobalMessageHandler()
returnValue setPrintLevel(PrintLevel _printlevel)