qpOASES_e_QProblem.c
Go to the documentation of this file.
1 /*
2  * This file is part of qpOASES.
3  *
4  * qpOASES -- An Implementation of the Online Active Set Strategy.
5  * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka,
6  * Christian Kirches et al. All rights reserved.
7  *
8  * qpOASES is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU Lesser General Public
10  * License as published by the Free Software Foundation; either
11  * version 2.1 of the License, or (at your option) any later version.
12  *
13  * qpOASES is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
16  * See the GNU Lesser General Public License for more details.
17  *
18  * You should have received a copy of the GNU Lesser General Public
19  * License along with qpOASES; if not, write to the Free Software
20  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
21  *
22  */
23 
24 
37 #include <stdlib.h>
38 
39 #include <qpOASES_e.h>
41 
42 
43 #ifdef __cplusplus
44 extern "C" {
45 #endif
46 
47 
48 #define S_FUNCTION_NAME qpOASES_e_QProblem
49 #define S_FUNCTION_LEVEL 2
51 #define MDL_START
53 #include "simstruc.h"
54 
55 
56 /* SETTINGS: */
57 #define SAMPLINGTIME -1
58 #define NCONTROLINPUTS 2
59 #define MAXITER 100
60 #define HESSIANTYPE HST_UNKNOWN
64 static void mdlInitializeSizes (SimStruct *S) /* Init sizes array */
65 {
66  int nU = NCONTROLINPUTS;
67 
68  /* Specify the number of continuous and discrete states */
69  ssSetNumContStates(S, 0);
70  ssSetNumDiscStates(S, 0);
71 
72  /* Specify the number of parameters */
73  ssSetNumSFcnParams(S, 2); /* H, A */
74  if ( ssGetNumSFcnParams(S) != ssGetSFcnParamsCount(S) )
75  return;
76 
77  /* Specify the number of intput ports */
78  if ( !ssSetNumInputPorts(S, 5) )
79  return;
80 
81  /* Specify the number of output ports */
82  if ( !ssSetNumOutputPorts(S, 4) )
83  return;
84 
85  /* Specify dimension information for the input ports */
86  ssSetInputPortVectorDimension(S, 0, DYNAMICALLY_SIZED); /* g */
87  ssSetInputPortVectorDimension(S, 1, DYNAMICALLY_SIZED); /* lb */
88  ssSetInputPortVectorDimension(S, 2, DYNAMICALLY_SIZED); /* ub */
89  ssSetInputPortVectorDimension(S, 3, DYNAMICALLY_SIZED); /* lbA */
90  ssSetInputPortVectorDimension(S, 4, DYNAMICALLY_SIZED); /* ubA */
91 
92  /* Specify dimension information for the output ports */
93  ssSetOutputPortVectorDimension(S, 0, nU ); /* uOpt */
94  ssSetOutputPortVectorDimension(S, 1, 1 ); /* fval */
95  ssSetOutputPortVectorDimension(S, 2, 1 ); /* exitflag */
96  ssSetOutputPortVectorDimension(S, 3, 1 ); /* iter */
97 
98  /* Specify the direct feedthrough status */
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);
106 
107  /* One sample time */
108  ssSetNumSampleTimes(S, 1);
109 
110  /* global variables:
111  * 0: problem
112  * 1: H
113  * 2: g
114  * 3: A
115  * 4: lb
116  * 5: ub
117  * 6: lbA
118  * 7: ubA
119  */
120 
121  /* Specify the size of the block's pointer work vector */
122  ssSetNumPWork(S, 8);
123 }
124 
125 
126 #if defined(MATLAB_MEX_FILE)
127 
128 #define MDL_SET_INPUT_PORT_DIMENSION_INFO
129 #define MDL_SET_OUTPUT_PORT_DIMENSION_INFO
130 
131 static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo)
132 {
133  if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) )
134  return;
135 }
136 
137 static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo)
138 {
139  if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) )
140  return;
141 }
142 
143 #endif
144 
145 
146 static void mdlInitializeSampleTimes(SimStruct *S)
147 {
148  ssSetSampleTime(S, 0, SAMPLINGTIME);
149  ssSetOffsetTime(S, 0, 0.0);
150 }
151 
152 
153 static void mdlStart(SimStruct *S)
154 {
156 
157  int nU = NCONTROLINPUTS;
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;
160  int nV, nC;
161 
162  static QProblem problem;
163  static Options problemOptions;
164 
165 
166  /* get block inputs dimensions */
167  const mxArray* in_H = ssGetSFcnParam(S, 0);
168  const mxArray* in_A = ssGetSFcnParam(S, 1);
169 
170  if ( mxIsEmpty(in_H) == 1 )
171  {
172  if ( ( HESSIANTYPE != HST_ZERO ) && ( HESSIANTYPE != HST_IDENTITY ) )
173  {
174  #ifndef __SUPPRESSANYOUTPUT__
175  mexErrMsgTxt( "ERROR (qpOASES): Hessian can only be empty if type is set to HST_ZERO or HST_IDENTITY!" );
176  #endif
177  return;
178  }
179 
180  nRows_H = 0;
181  nCols_H = 0;
182  size_H = 0;
183  }
184  else
185  {
186  nRows_H = (int)mxGetM(in_H);
187  nCols_H = (int)mxGetN(in_H);
188  size_H = nRows_H * nCols_H;
189  }
190 
191  if ( mxIsEmpty(in_A) == 1 )
192  {
193  nRows_A = 0;
194  nCols_A = 0;
195  size_A = 0;
196  }
197  else
198  {
199  nRows_A = (int)mxGetM(in_A);
200  nCols_A = (int)mxGetN(in_A);
201  size_A = nRows_A * nCols_A;
202  }
203 
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);
209 
210 
211  /* dimension checks */
212  nV = size_g;
213  nC = nRows_A;
214 
215 
216  if ( MAXITER < 0 )
217  {
218  #ifndef __SUPPRESSANYOUTPUT__
219  mexErrMsgTxt( "ERROR (qpOASES): Maximum number of iterations must not be negative!" );
220  #endif
221  return;
222  }
223 
224  if ( nV <= 0 )
225  {
226  #ifndef __SUPPRESSANYOUTPUT__
227  mexErrMsgTxt( "ERROR (qpOASES): Dimension mismatch (nV must be positive)!" );
228  #endif
229  return;
230  }
231 
232  if ( ( size_H != nV*nV ) && ( size_H != 0 ) )
233  {
234  #ifndef __SUPPRESSANYOUTPUT__
235  mexErrMsgTxt( "ERROR (qpOASES): Dimension mismatch in H!" );
236  #endif
237  return;
238  }
239 
240  if ( nRows_H != nCols_H )
241  {
242  #ifndef __SUPPRESSANYOUTPUT__
243  mexErrMsgTxt( "ERROR (qpOASES): Hessian matrix must be square matrix!" );
244  #endif
245  return;
246  }
247 
248  if ( ( nU < 1 ) || ( nU > nV ) )
249  {
250  #ifndef __SUPPRESSANYOUTPUT__
251  mexErrMsgTxt( "ERROR (qpOASES): Invalid number of control inputs!" );
252  #endif
253  return;
254  }
255 
256  if ( ( size_lb != nV ) && ( size_lb != 0 ) )
257  {
258  #ifndef __SUPPRESSANYOUTPUT__
259  mexErrMsgTxt( "ERROR (qpOASES): Dimension mismatch in lb!" );
260  #endif
261  return;
262  }
263 
264  if ( ( size_ub != nV ) && ( size_lb != 0 ) )
265  {
266  #ifndef __SUPPRESSANYOUTPUT__
267  mexErrMsgTxt( "ERROR (qpOASES): Dimension mismatch in ub!" );
268  #endif
269  return;
270  }
271 
272  if ( ( size_lbA != nC ) && ( size_lbA != 0 ) )
273  {
274  #ifndef __SUPPRESSANYOUTPUT__
275  mexErrMsgTxt( "ERROR (qpOASES): Dimension mismatch in lbA!" );
276  #endif
277  return;
278  }
279 
280  if ( ( size_ubA != nC ) && ( size_ubA != 0 ) )
281  {
282  #ifndef __SUPPRESSANYOUTPUT__
283  mexErrMsgTxt( "ERROR (qpOASES): Dimension mismatch in ubA!" );
284  #endif
285  return;
286  }
287 
288 
289  /* allocate QProblem object */
290  QProblemCON( &problem,nV,nC,HESSIANTYPE );
291 
292  Options_setToMPC( &problemOptions );
293  QProblem_setOptions( &problem,problemOptions );
294  #ifndef __DEBUG__
295  QProblem_setPrintLevel( &problem,PL_LOW );
296  #endif
297  #ifdef __SUPPRESSANYOUTPUT__
298  QProblem_setPrintLevel( &problem,PL_NONE );
299  #endif
300 
301  ssGetPWork(S)[0] = (void*)(&problem);
302 
303  /* allocate memory for QP data ... */
304  if ( size_H > 0 )
305  ssGetPWork(S)[1] = (void *) calloc( size_H, sizeof(real_t) ); /* H */
306  else
307  ssGetPWork(S)[1] = 0;
308 
309  ssGetPWork(S)[2] = (void *) calloc( size_g, sizeof(real_t) ); /* g */
310  ssGetPWork(S)[3] = (void *) calloc( size_A, sizeof(real_t) ); /* A */
311 
312  if ( size_lb > 0 )
313  ssGetPWork(S)[4] = (void *) calloc( size_lb, sizeof(real_t) ); /* lb */
314  else
315  ssGetPWork(S)[4] = 0;
316 
317  if ( size_ub > 0 )
318  ssGetPWork(S)[5] = (void *) calloc( size_ub, sizeof(real_t) ); /* ub */
319  else
320  ssGetPWork(S)[5] = 0;
321 
322  if ( size_lbA > 0 )
323  ssGetPWork(S)[6] = (void *) calloc( size_lbA, sizeof(real_t) ); /* lbA */
324  else
325  ssGetPWork(S)[6] = 0;
326 
327  if ( size_ubA > 0 )
328  ssGetPWork(S)[7] = (void *) calloc( size_ubA, sizeof(real_t) ); /* ubA */
329  else
330  ssGetPWork(S)[7] = 0;
331 }
332 
333 
334 static void mdlOutputs(SimStruct *S, int_T tid)
335 {
337 
338  int i;
339  int nV, nC;
340  returnValue status;
341 
342  int nWSR = MAXITER;
343  int nU = NCONTROLINPUTS;
344 
345  InputRealPtrsType in_g, in_lb, in_ub, in_lbA, in_ubA;
346 
347  QProblem* problem;
348  real_t *H, *g, *A, *lb, *ub, *lbA, *ubA;
349 
350  real_t xOpt[NVMAX];
351  real_t yOpt[NVMAX+NCMAX];
352 
353  real_T *out_uOpt, *out_objVal, *out_status, *out_nWSR;
354  real_t stat, feas, cmpl, kktTol;
355 
356  int nWSR_retry;
357 
358  FILE* matFile = 0;
359  char fileName[20] = "qpData000000000.mat";
360 
361 
362  /* get pointers to block inputs ... */
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);
370 
371 
372  /* ... and to the QP data */
373  problem = (QProblem*)(ssGetPWork(S)[0]);
374 
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]);
382 
383 
384  /* setup QP data */
385  nV = ssGetInputPortWidth(S, 0); /* nV = size_g */
386  nC = (int)mxGetM(in_A); /* nC = nRows_A*/
387 
388  if ( H != 0 )
389  {
390  /* no conversion from FORTRAN to C as Hessian is symmetric! */
391  for ( i=0; i<nV*nV; ++i )
392  H[i] = (mxGetPr(in_H))[i];
393  }
394 
395  convertFortranToC( mxGetPr(in_A),nV,nC, A );
396 
397  for ( i=0; i<nV; ++i )
398  g[i] = (*in_g)[i];
399 
400  if ( lb != 0 )
401  {
402  for ( i=0; i<nV; ++i )
403  lb[i] = (*in_lb)[i];
404  }
405 
406  if ( ub != 0 )
407  {
408  for ( i=0; i<nV; ++i )
409  ub[i] = (*in_ub)[i];
410  }
411 
412  if ( lbA != 0 )
413  {
414  for ( i=0; i<nC; ++i )
415  lbA[i] = (*in_lbA)[i];
416  }
417 
418  if ( ubA != 0 )
419  {
420  for ( i=0; i<nC; ++i )
421  ubA[i] = (*in_ubA)[i];
422  }
423 
424 
425  #ifdef __SIMULINK_DEBUG__
426 
427  sprintf( fileName,"qpData%09d.mat",(int)(QProblem_getCount( problem )) );
428  matFile = fopen( fileName,"w+" );
429  /*qpOASES_writeIntoMatFile( matFile, H, nV,nV, "H" );*/
430  //qpOASES_writeIntoMatFile( matFile, g, nV,1, "g" );
431  qpOASES_writeIntoMatFile( matFile, lb, nV,1, "lb" );
432  qpOASES_writeIntoMatFile( matFile, ub, nV,1, "ub" );
433  //qpOASES_writeIntoMatFile( matFile, A, nC,nV, "A" );
434  qpOASES_writeIntoMatFile( matFile, lbA, nC,1, "lbA" );
435  qpOASES_writeIntoMatFile( matFile, ubA, nC,1, "ubA" );
436  fclose( matFile );
437 
438  #endif /* __SIMULINK_DEBUG__ */
439 
440 
441  if ( QProblem_getCount( problem ) == 0 )
442  {
443  /* initialise and solve first QP */
444  status = QProblem_init( problem,H,g,A,lb,ub,lbA,ubA, &nWSR,0 );
445  QProblem_getPrimalSolution( problem,xOpt );
446  QProblem_getDualSolution( problem,yOpt );
447  }
448  else
449  {
450  /* solve neighbouring QP using hotstart technique */
451  status = QProblem_hotstart( problem,g,lb,ub,lbA,ubA, &nWSR,0 );
452  if ( ( status != SUCCESSFUL_RETURN ) && ( status != RET_MAX_NWSR_REACHED ) )
453  {
454  /* if an error occurs, reset problem data structures ... */
455  QProblem_reset( problem );
456 
457  /* ... and initialise/solve again with remaining number of iterations. */
458  nWSR_retry = MAXITER - nWSR;
459  status = QProblem_init( problem,H,g,A,lb,ub,lbA,ubA, &nWSR_retry,0 );
460  nWSR += nWSR_retry;
461 
462  }
463 
464  /* obtain optimal solution */
465  QProblem_getPrimalSolution( problem,xOpt );
466  QProblem_getDualSolution( problem,yOpt );
467  }
468 
469  /* generate block output: status information ... */
470  out_uOpt = ssGetOutputPortRealSignal(S, 0);
471  out_objVal = ssGetOutputPortRealSignal(S, 1);
472  out_status = ssGetOutputPortRealSignal(S, 2);
473  out_nWSR = ssGetOutputPortRealSignal(S, 3);
474 
475  for ( i=0; i<nU; ++i )
476  out_uOpt[i] = (real_T)(xOpt[i]);
477 
478  out_objVal[0] = (real_T)(QProblem_getObjVal( problem ));
479  out_status[0] = (real_t)(qpOASES_getSimpleStatus( status,BT_FALSE ));
480  out_nWSR[0] = (real_T)(nWSR);
481 
482  removeNaNs( out_uOpt,nU );
483  removeInfs( out_uOpt,nU );
484  removeNaNs( out_objVal,1 );
485  removeInfs( out_objVal,1 );
486 
487  #ifdef __SIMULINK_DEBUG__
488 
490  H,g,A,lb,ub,lbA,ubA,
491  xOpt,yOpt,
492  &stat,&feas,&cmpl
493  );
494  mexPrintf( "KKT residuals: stat=%e, feas=%e, cmpl=%e\n", stat,feas,cmpl );
495 
496  kktTol = stat;
497  if ( feas > kktTol )
498  kktTol = feas;
499  if ( cmpl > kktTol )
500  kktTol = cmpl;
501 
502  if ( ( qpOASES_getAbs( out_status[0] ) < QPOASES_EPS ) && ( kktTol > 1e-4 ) )
503  out_status[0] = 2.0;
504 
505  #endif /* __SIMULINK_DEBUG__ */
506 }
507 
508 
509 static void mdlTerminate(SimStruct *S)
510 {
512 
513  int i;
514 
515  /* reset global message handler */
517 
518  for ( i=1; i<8; ++i )
519  {
520  if ( ssGetPWork(S)[i] != 0 )
521  free( ssGetPWork(S)[i] );
522  }
523 }
524 
525 
526 #ifdef MATLAB_MEX_FILE
527 #include "simulink.c"
528 #else
529 #include "cg_sfun.h"
530 #endif
531 
532 
533 #ifdef __cplusplus
534 }
535 #endif
536 
537 
538 /*
539  * end of file
540  */
returnValue QProblem_getPrimalSolution(QProblem *_THIS, real_t *const xOpt)
Definition: QProblem.c:1168
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)
Definition: Utils.c:658
int qpOASES_getSimpleStatus(returnValue returnvalue, BooleanType doPrintStatus)
Definition: Utils.c:882
Allows to pass back messages to the calling function.
#define SAMPLINGTIME
#define HESSIANTYPE
returnValue convertFortranToC(const real_t *const A_for, int nV, int nC, real_t *const A)
#define HST_IDENTITY
#define PL_NONE
returnValue MessageHandling_reset(MessageHandling *_THIS)
returnValue QProblem_setPrintLevel(QProblem *_THIS, PrintLevel _printlevel)
Definition: QProblem.c:1193
static real_t qpOASES_getAbs(real_t x)
Definition: Utils.h:468
Provides a generic way to set and pass user-specified options.
Definition: options.hpp:65
real_t QProblem_getObjVal(QProblem *_THIS)
Definition: QProblem.c:1095
static void mdlOutputs(SimStruct *S, int_T tid)
#define MAXITER
#define PL_LOW
returnValue qpOASES_writeIntoMatFile(FILE *const matFile, const real_t *const data, int nRows, int nCols, const char *name)
Definition: Utils.c:540
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)
Definition: Options.c:214
MessageHandling * qpOASES_getGlobalMessageHandler()
returnValue QProblem_getDualSolution(QProblem *_THIS, real_t *const yOpt)
Definition: QProblem.c:1058
static void mdlStart(SimStruct *S)
#define HST_ZERO
static const real_t QPOASES_EPS
static unsigned int QProblem_getCount(QProblem *_THIS)
Definition: QProblem.h:1843
returnValue QProblem_reset(QProblem *_THIS)
Definition: QProblem.c:202
#define BT_FALSE
Definition: acado_types.hpp:49
#define NCONTROLINPUTS
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)
double real_t
Definition: AD_test.c:10
Implements the online active set strategy for QPs with general constraints.
void QProblemCON(QProblem *_THIS, int _nV, int _nC, HessianType _hessianType)
Definition: QProblem.c:51
static returnValue QProblem_setOptions(QProblem *_THIS, Options _options)
Definition: QProblem.h:1818


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Mon Jun 10 2019 12:35:00