qpOASES_e_sequence.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 
38 #include <qpOASES_e.h>
39 
40 
42 
43 
44 #include "qpOASES_e_matlab_utils.h"
45 #include "qpOASES_e_matlab_utils.c"
46 
47 
48 /*
49  * Q P r o b l e m B _ i n i t
50  */
51 int mex_QProblemB_init( int handle,
52  DenseMatrix *H, real_t* g,
53  const real_t* const lb, const real_t* const ub,
54  int nWSRin, real_t maxCpuTimeIn,
55  const double* const x0, Options* options,
56  int nOutputs, mxArray* plhs[],
57  const double* const guessedBounds,
58  const double* const _R
59  )
60 {
61  int i;
62  int nV;
63  int nWSRout = nWSRin;
64  real_t maxCpuTimeOut = (maxCpuTimeIn >= 0.0) ? maxCpuTimeIn : QPOASES_INFTY;
65  returnValue returnvalue;
66  static char msg[QPOASES_MAX_STRING_LENGTH];
67 
68  /* 1) setup initial QP. */
69  static Bounds bounds;
70 
71  QPInstance* inst = getQPInstance(handle);
72  QProblemB* globalQPB = &(inst->qpb);
73 
74  if ( globalQPB == 0 )
75  {
76  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid handle to QP instance!" );
77  return -1;
78  }
79 
80  QProblemB_setOptions( globalQPB,*options );
81 
82  /* 2) Solve initial QP. */
83 
84  nV = QProblemB_getNV( globalQPB );
85 
86  /* 3) Fill the working set. */
87  BoundsCON( &bounds,nV );
88  if (guessedBounds != 0) {
89  for (i = 0; i < nV; i++) {
90  if ( qpOASES_isEqual(guessedBounds[i],-1.0,QPOASES_TOL) == BT_TRUE ) {
91  Bounds_setupBound( &bounds,i,ST_LOWER );
92  } else if ( qpOASES_isEqual(guessedBounds[i],1.0,QPOASES_TOL) == BT_TRUE ) {
93  Bounds_setupBound( &bounds,i,ST_UPPER );
94  } else if ( qpOASES_isEqual(guessedBounds[i],0.0,QPOASES_TOL) == BT_TRUE ) {
95  Bounds_setupBound( &bounds,i,ST_INACTIVE );
96  } else {
97  snprintf(msg, QPOASES_MAX_STRING_LENGTH,
98  "ERROR (qpOASES_e): Only {-1, 0, 1} allowed for status of bounds!");
99  myMexErrMsgTxt(msg);
100  return -1;
101  }
102  }
103  }
104 
105  returnvalue = QProblemB_initMW( globalQPB,H,g,lb,ub,
106  &nWSRout,&maxCpuTimeOut,
107  x0,0,
108  (guessedBounds != 0) ? &bounds : 0,
109  _R
110  );
111 
112  /* 3) Assign lhs arguments. */
113  obtainOutputsSB( 0,globalQPB,returnvalue,nWSRout,maxCpuTimeOut,
114  nOutputs,plhs,nV,handle );
115 
116  return 0;
117 }
118 
119 
120 /*
121  * S Q P r o b l e m _ i n i t
122  */
123 int mex_SQProblem_init( int handle,
125  const real_t* const lb, const real_t* const ub,
126  const real_t* const lbA, const real_t* const ubA,
127  int nWSRin, real_t maxCpuTimeIn,
128  const double* const x0, Options* options,
129  int nOutputs, mxArray* plhs[],
130  const double* const guessedBounds, const double* const guessedConstraints,
131  const double* const _R
132  )
133 {
134  int i;
135  int nV, nC;
136  int nWSRout = nWSRin;
137  real_t maxCpuTimeOut = (maxCpuTimeIn >= 0.0) ? maxCpuTimeIn : QPOASES_INFTY;
138  returnValue returnvalue;
139  static char msg[QPOASES_MAX_STRING_LENGTH];
140 
141  /* 1) setup initial QP. */
142  static Bounds bounds;
143  static Constraints constraints;
144 
145  QPInstance* inst = getQPInstance(handle);
146  QProblem* globalSQP = &(inst->sqp);
147 
148  if ( globalSQP == 0 )
149  {
150  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid handle to QP instance!" );
151  return -1;
152  }
153 
154  QProblem_setOptions( globalSQP,*options );
155 
156  /* 2) Solve initial QP. */
157  nV = QProblem_getNV( globalSQP );
158  nC = QProblem_getNC( globalSQP );
159 
160  /* 3) Fill the working set. */
161  BoundsCON( &bounds,nV );
162  ConstraintsCON( &constraints,nC );
163  if (guessedBounds != 0) {
164  for (i = 0; i < nV; i++) {
165  if ( qpOASES_isEqual(guessedBounds[i],-1.0,QPOASES_TOL) == BT_TRUE ) {
166  Bounds_setupBound( &bounds,i,ST_LOWER );
167  } else if ( qpOASES_isEqual(guessedBounds[i],1.0,QPOASES_TOL) == BT_TRUE ) {
168  Bounds_setupBound( &bounds,i,ST_UPPER );
169  } else if ( qpOASES_isEqual(guessedBounds[i],0.0,QPOASES_TOL) == BT_TRUE ) {
170  Bounds_setupBound( &bounds,i,ST_INACTIVE );
171  } else {
172  snprintf(msg, QPOASES_MAX_STRING_LENGTH,
173  "ERROR (qpOASES_e): Only {-1, 0, 1} allowed for status of bounds!");
174  myMexErrMsgTxt(msg);
175  return -1;
176  }
177  }
178  }
179 
180  if (guessedConstraints != 0) {
181  for (i = 0; i < nC; i++) {
182  if ( qpOASES_isEqual(guessedConstraints[i],-1.0,QPOASES_TOL) == BT_TRUE ) {
183  Constraints_setupConstraint( &constraints,i,ST_LOWER );
184  } else if ( qpOASES_isEqual(guessedConstraints[i],1.0,QPOASES_TOL) == BT_TRUE ) {
185  Constraints_setupConstraint( &constraints,i,ST_UPPER );
186  } else if ( qpOASES_isEqual(guessedConstraints[i],0.0,QPOASES_TOL) == BT_TRUE ) {
187  Constraints_setupConstraint( &constraints,i,ST_INACTIVE );
188  } else {
189  snprintf(msg, QPOASES_MAX_STRING_LENGTH,
190  "ERROR (qpOASES_e): Only {-1, 0, 1} allowed for status of constraints!");
191  myMexErrMsgTxt(msg);
192  return -1;
193  }
194  }
195  }
196 
197  returnvalue = QProblem_initMW( globalSQP,H,g,A,lb,ub,lbA,ubA,
198  &nWSRout,&maxCpuTimeOut,
199  x0,0,
200  (guessedBounds != 0) ? &bounds : 0, (guessedConstraints != 0) ? &constraints : 0,
201  _R
202  );
203 
204  /* 3) Assign lhs arguments. */
205  obtainOutputs( 0,globalSQP,returnvalue,nWSRout,maxCpuTimeOut,
206  nOutputs,plhs,nV,nC,handle );
207 
208  return 0;
209 }
210 
211 
212 
213 /*
214  * Q P r o b l e m B _ h o t s t a r t
215  */
216 int mex_QProblemB_hotstart( int handle,
217  const real_t* const g,
218  const real_t* const lb, const real_t* const ub,
219  int nWSRin, real_t maxCpuTimeIn,
220  Options* options,
221  int nOutputs, mxArray* plhs[]
222  )
223 {
224  int nV;
225  int nWSRout = nWSRin;
226  real_t maxCpuTimeOut = (maxCpuTimeIn >= 0.0) ? maxCpuTimeIn : QPOASES_INFTY;
227  returnValue returnvalue;
228 
229  QPInstance* inst = getQPInstance(handle);
230  QProblemB* globalQPB = &(inst->qpb);
231 
232  nV = QProblemB_getNV( globalQPB );
233 
234  if ( globalQPB == 0 )
235  {
236  myMexErrMsgTxt( "ERROR (qpOASES_e): QP needs to be initialised first!" );
237  return -1;
238  }
239 
240  /* 1) Solve QP with given options. */
241  QProblemB_setOptions( globalQPB,*options );
242  returnvalue = QProblemB_hotstart( globalQPB,g,lb,ub, &nWSRout,&maxCpuTimeOut );
243 
244  /* 2) Assign lhs arguments. */
245  obtainOutputsSB( 0,globalQPB,returnvalue,nWSRout,maxCpuTimeOut,
246  nOutputs,plhs,nV,-1 );
247 
248  return 0;
249 }
250 
251 
252 /*
253  * Q P r o b l e m _ h o t s t a r t
254  */
255 int mex_QProblem_hotstart( int handle,
256  const real_t* const g,
257  const real_t* const lb, const real_t* const ub,
258  const real_t* const lbA, const real_t* const ubA,
259  int nWSRin, real_t maxCpuTimeIn,
260  Options* options,
261  int nOutputs, mxArray* plhs[]
262  )
263 {
264  int nV, nC;
265  int nWSRout = nWSRin;
266  real_t maxCpuTimeOut = (maxCpuTimeIn >= 0.0) ? maxCpuTimeIn : QPOASES_INFTY;
267  returnValue returnvalue;
268 
269  QPInstance* inst = getQPInstance(handle);
270  QProblem* globalSQP = &(inst->sqp);
271 
272  nV = QProblem_getNV( globalSQP );
273  nC = QProblem_getNC( globalSQP );
274 
275  if ( globalSQP == 0 )
276  {
277  myMexErrMsgTxt( "ERROR (qpOASES_e): QP needs to be initialised first!" );
278  return -1;
279  }
280 
281  /* 1) Solve QP with given options. */
282  QProblem_setOptions( globalSQP,*options );
283  /*mexPrintf( "handle = %d\n",handle );*/
284  returnvalue = QProblem_hotstart( globalSQP,g,lb,ub,lbA,ubA, &nWSRout,&maxCpuTimeOut );
285 
286  /* 2) Assign lhs arguments. */
287  obtainOutputs( 0,globalSQP,returnvalue,nWSRout,maxCpuTimeOut,
288  nOutputs,plhs,nV,nC,-1 );
289 
290  return 0;
291 }
292 
293 
294 
295 /*
296  * m e x F u n c t i o n
297  */
298 void mexFunction( int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[] )
299 {
300  /* inputs */
301  char typeString[2];
302 
303  real_t *g=0, *lb=0, *ub=0, *lbA=0, *ubA=0;
304  HessianType hessianType = HST_UNKNOWN;
305  double *x0=0, *R_for=0;
306  static real_t R[NVMAX*NVMAX];
307  double *guessedBounds=0, *guessedConstraints=0;
308 
309  int H_idx=-1, g_idx=-1, A_idx=-1, lb_idx=-1, ub_idx=-1, lbA_idx=-1, ubA_idx=-1;
310  int x0_idx=-1, auxInput_idx=-1;
311 
312  BooleanType isSimplyBoundedQp = BT_FALSE;
313 
314  /* dimensions */
315  unsigned int nV=0, nC=0, handle=0;
316  int nWSRin;
317  real_t maxCpuTimeIn = -1.0;
318  QPInstance* globalQP = 0;
319 
320  int nRHS;
321  real_t *x_out=0, *y_out=0;
322  static real_t y_out_tmp[NVMAX+NCMAX];
323  real_t* workingSetB=0, *workingSetC=0;
324 
325  returnValue returnvalue;
326  static char msg[QPOASES_MAX_STRING_LENGTH];
327 
328  static Options options;
329  Options_setToDefault( &options );
330  options.printLevel = PL_LOW;
331  #ifdef __DEBUG__
332  options.printLevel = PL_HIGH;
333  #endif
334  #ifdef __SUPPRESSANYOUTPUT__
335  options.printLevel = PL_NONE;
336  #endif
337 
338  /* I) CONSISTENCY CHECKS: */
339  /* 1) Ensure that qpOASES is called with a feasible number of input arguments. */
340  if ( ( nrhs < 5 ) || ( nrhs > 10 ) )
341  {
342  if ( nrhs != 2 )
343  {
344  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
345  return;
346  }
347  }
348 
349  /* 2) Ensure that first input is a string ... */
350  if ( mxIsChar( prhs[0] ) != 1 )
351  {
352  myMexErrMsgTxt( "ERROR (qpOASES_e): First input argument must be a string!" );
353  return;
354  }
355 
356  mxGetString( prhs[0], typeString, 2 );
357 
358  /* ... and if so, check if it is an allowed one. */
359  if ( ( strcmp( typeString,"i" ) != 0 ) && ( strcmp( typeString,"I" ) != 0 ) &&
360  ( strcmp( typeString,"h" ) != 0 ) && ( strcmp( typeString,"H" ) != 0 ) &&
361  ( strcmp( typeString,"m" ) != 0 ) && ( strcmp( typeString,"M" ) != 0 ) &&
362  ( strcmp( typeString,"e" ) != 0 ) && ( strcmp( typeString,"E" ) != 0 ) &&
363  ( strcmp( typeString,"c" ) != 0 ) && ( strcmp( typeString,"C" ) != 0 ) )
364  {
365  myMexErrMsgTxt( "ERROR (qpOASES_e): Undefined first input argument!\nType 'help qpOASES_sequence' for further information." );
366  return;
367  }
368 
369 
370  /* II) SELECT RESPECTIVE QPOASES FUNCTION CALL: */
371  /* 1) Init (without or with initial guess for primal solution). */
372  if ( ( strcmp( typeString,"i" ) == 0 ) || ( strcmp( typeString,"I" ) == 0 ) )
373  {
374  /* consistency checks */
375  if ( ( nlhs < 2 ) || ( nlhs > 7 ) )
376  {
377  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
378  return;
379  }
380 
381  if ( ( nrhs < 5 ) || ( nrhs > 10 ) )
382  {
383  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
384  return;
385  }
386 
387  g_idx = 2;
388 
389  if ( mxIsEmpty(prhs[1]) == 1 )
390  {
391  H_idx = -1;
392  nV = (unsigned int)mxGetM( prhs[ g_idx ] ); /* row number of Hessian matrix */
393  }
394  else
395  {
396  H_idx = 1;
397  nV = (unsigned int)mxGetM( prhs[ H_idx ] ); /* row number of Hessian matrix */
398  }
399 
400 
401  /* ensure that data is given in double precision */
402  if ( ( ( H_idx >= 0 ) && ( mxIsDouble( prhs[ H_idx ] ) == 0 ) ) ||
403  ( mxIsDouble( prhs[ g_idx ] ) == 0 ) )
404  {
405  myMexErrMsgTxt( "ERROR (qpOASES_e): All data has to be provided in double precision!" );
406  return;
407  }
408 
409  if ( ( H_idx >= 0 ) && ( ( mxGetN( prhs[ H_idx ] ) != nV ) || ( mxGetM( prhs[ H_idx ] ) != nV ) ) )
410  {
411  myMexErrMsgTxt( "ERROR (qpOASES_e): Hessian matrix dimension mismatch!" );
412  return;
413  }
414 
415 
416  /* Check for 'Inf' and 'Nan' in Hessian */
417  if (containsNaNorInf( prhs,H_idx,BT_FALSE ) == BT_TRUE)
418  return;
419 
420  /* Check for 'Inf' and 'Nan' in gradient */
421  if (containsNaNorInf( prhs,g_idx,BT_FALSE ) == BT_TRUE)
422  return;
423 
424  /* determine whether is it a simply bounded QP */
425  if ( nrhs <= 7 )
426  isSimplyBoundedQp = BT_TRUE;
427  else
428  isSimplyBoundedQp = BT_FALSE;
429 
430  if ( isSimplyBoundedQp == BT_TRUE )
431  {
432  lb_idx = 3;
433  ub_idx = 4;
434 
435  if (containsNaNorInf( prhs,lb_idx,BT_TRUE ) == BT_TRUE)
436  return;
437 
438  if (containsNaNorInf( prhs,ub_idx,BT_TRUE ) == BT_TRUE)
439  return;
440 
441  /* Check inputs dimensions and assign pointers to inputs. */
442  nC = 0; /* row number of constraint matrix */
443 
444 
445  if ( smartDimensionCheck( &g,nV,1, BT_FALSE,prhs,2 ) != SUCCESSFUL_RETURN )
446  return;
447 
448  if ( smartDimensionCheck( &lb,nV,1, BT_TRUE,prhs,3 ) != SUCCESSFUL_RETURN )
449  return;
450 
451  if ( smartDimensionCheck( &ub,nV,1, BT_TRUE,prhs,4 ) != SUCCESSFUL_RETURN )
452  return;
453 
454  /* default value for nWSR */
455  nWSRin = 5*nV;
456 
457  /* Check whether x0 and options are specified .*/
458  if ( nrhs >= 6 )
459  {
460  if ((!mxIsEmpty(prhs[5])) && (mxIsStruct(prhs[5])))
461  setupOptions( &options,prhs[5],&nWSRin,&maxCpuTimeIn );
462 
463  if ( ( nrhs >= 7 ) && ( !mxIsEmpty(prhs[6]) ) )
464  {
465  /* auxInput specified */
466  if ( mxIsStruct(prhs[6]) )
467  {
468  auxInput_idx = 6;
469  x0_idx = -1;
470  }
471  else
472  {
473  auxInput_idx = -1;
474  x0_idx = 6;
475  }
476  }
477  else
478  {
479  auxInput_idx = -1;
480  x0_idx = -1;
481  }
482  }
483  }
484  else
485  {
486  A_idx = 3;
487 
488  /* ensure that data is given in double precision */
489  if ( mxIsDouble( prhs[ A_idx ] ) == 0 )
490  {
491  myMexErrMsgTxt( "ERROR (qpOASES_e): All data has to be provided in double precision!" );
492  return;
493  }
494 
495  /* Check inputs dimensions and assign pointers to inputs. */
496  nC = (unsigned int)mxGetM( prhs[ A_idx ] ); /* row number of constraint matrix */
497 
498  lb_idx = 4;
499  ub_idx = 5;
500  lbA_idx = 6;
501  ubA_idx = 7;
502 
503  if (containsNaNorInf( prhs,A_idx,BT_FALSE ) == BT_TRUE)
504  return;
505 
506  if (containsNaNorInf( prhs,lb_idx,BT_TRUE ) == BT_TRUE)
507  return;
508 
509  if (containsNaNorInf( prhs,ub_idx,BT_TRUE ) == BT_TRUE)
510  return;
511 
512  if (containsNaNorInf( prhs,lbA_idx,BT_TRUE ) == BT_TRUE)
513  return;
514 
515  if (containsNaNorInf( prhs,ubA_idx,BT_TRUE ) == BT_TRUE)
516  return;
517 
518  if ( ( mxGetN( prhs[ A_idx ] ) != 0 ) && ( mxGetN( prhs[ A_idx ] ) != nV ) )
519  {
520  myMexErrMsgTxt( "ERROR (qpOASES_e): Constraint matrix dimension mismatch!" );
521  return;
522  }
523 
524  if ( smartDimensionCheck( &g,nV,1, BT_FALSE,prhs,g_idx ) != SUCCESSFUL_RETURN )
525  return;
526 
527  if ( smartDimensionCheck( &lb,nV,1, BT_TRUE,prhs,lb_idx ) != SUCCESSFUL_RETURN )
528  return;
529 
530  if ( smartDimensionCheck( &ub,nV,1, BT_TRUE,prhs,ub_idx ) != SUCCESSFUL_RETURN )
531  return;
532 
533  if ( smartDimensionCheck( &lbA,nC,1, BT_TRUE,prhs,lbA_idx ) != SUCCESSFUL_RETURN )
534  return;
535 
536  if ( smartDimensionCheck( &ubA,nC,1, BT_TRUE,prhs,ubA_idx ) != SUCCESSFUL_RETURN )
537  return;
538 
539  /* default value for nWSR */
540  nWSRin = 5*(nV+nC);
541 
542  /* Check whether x0 and options are specified .*/
543  if ( nrhs >= 9 )
544  {
545  if ((!mxIsEmpty(prhs[8])) && (mxIsStruct(prhs[8])))
546  setupOptions( &options,prhs[8],&nWSRin,&maxCpuTimeIn );
547 
548  if ( ( nrhs >= 10 ) && ( !mxIsEmpty(prhs[9]) ) )
549  {
550  /* auxInput specified */
551  if ( mxIsStruct(prhs[9]) )
552  {
553  auxInput_idx = 9;
554  x0_idx = -1;
555  }
556  else
557  {
558  auxInput_idx = -1;
559  x0_idx = 9;
560  }
561  }
562  else
563  {
564  auxInput_idx = -1;
565  x0_idx = -1;
566  }
567  }
568  }
569 
570 
571  /* check dimensions and copy auxInputs */
572  if ( smartDimensionCheck( &x0,nV,1, BT_TRUE,prhs,x0_idx ) != SUCCESSFUL_RETURN )
573  return;
574 
575  if ( auxInput_idx >= 0 )
576  setupAuxiliaryInputs( prhs[auxInput_idx],nV,nC, &hessianType,&x0,&guessedBounds,&guessedConstraints,&R_for );
577 
578  /* convert Cholesky factor to C storage format */
579  if ( R_for != 0 )
580  {
581  convertFortranToC( R_for, nV,nV, R );
582  }
583 
584  /* allocate instance */
585  handle = allocateQPInstance( nV,nC,hessianType, isSimplyBoundedQp,&options );
586  globalQP = getQPInstance( handle );
587 
588  /* make a deep-copy of the user-specified Hessian matrix (possibly sparse) */
589  if ( H_idx >= 0 )
590  setupHessianMatrix( prhs[H_idx],nV, &(globalQP->H) );
591 
592  /* make a deep-copy of the user-specified constraint matrix (possibly sparse) */
593  if ( ( nC > 0 ) && ( A_idx >= 0 ) )
594  setupConstraintMatrix( prhs[A_idx],nV,nC, &(globalQP->A) );
595 
596  /* Create output vectors and assign pointers to them. */
597  allocateOutputs( nlhs,plhs, nV,nC,1,handle );
598 
599  /* Call qpOASES. */
600  if ( isSimplyBoundedQp == BT_TRUE )
601  {
602  mex_QProblemB_init( handle,
603  ( H_idx >= 0 ) ? &(globalQP->H) : 0, g,
604  lb,ub,
605  nWSRin,maxCpuTimeIn,
606  x0,&options,
607  nlhs,plhs,
608  guessedBounds,
609  ( R_for != 0 ) ? R : 0
610  );
611  }
612  else
613  {
614  mex_SQProblem_init( handle,
615  ( H_idx >= 0 ) ? &(globalQP->H) : 0, g, ( ( nC > 0 ) && ( A_idx >= 0 ) ) ? &(globalQP->A) : 0,
616  lb,ub,lbA,ubA,
617  nWSRin,maxCpuTimeIn,
618  x0,&options,
619  nlhs,plhs,
620  guessedBounds,guessedConstraints,
621  ( R_for != 0 ) ? R : 0
622  );
623  }
624  return;
625  }
626 
627  /* 2) Hotstart. */
628  if ( ( strcmp( typeString,"h" ) == 0 ) || ( strcmp( typeString,"H" ) == 0 ) )
629  {
630  /* consistency checks */
631  if ( ( nlhs < 1 ) || ( nlhs > 6 ) )
632  {
633  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
634  return;
635  }
636 
637  if ( ( nrhs < 5 ) || ( nrhs > 8 ) )
638  {
639  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
640  return;
641  }
642 
643  /* determine whether is it a simply bounded QP */
644  if ( nrhs < 7 )
645  isSimplyBoundedQp = BT_TRUE;
646  else
647  isSimplyBoundedQp = BT_FALSE;
648 
649 
650  if ( ( mxIsDouble( prhs[1] ) == false ) || ( mxIsScalar( prhs[1] ) == false ) )
651  {
652  myMexErrMsgTxt( "ERROR (qpOASES_e): Expecting a handle to QP object as second argument!\nType 'help qpOASES_sequence' for further information." );
653  return;
654  }
655 
656  /* get QP instance */
657  handle = (unsigned int)mxGetScalar( prhs[1] );
658  globalQP = getQPInstance( handle );
659  if ( globalQP == 0 )
660  {
661  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid handle to QP instance!" );
662  return;
663  }
664 
665  nV = QPInstance_getNV( globalQP );
666 
667  g_idx = 2;
668  lb_idx = 3;
669  ub_idx = 4;
670 
671  if (containsNaNorInf( prhs,g_idx,BT_FALSE ) == BT_TRUE)
672  return;
673 
674  if (containsNaNorInf( prhs,lb_idx,BT_TRUE ) == BT_TRUE)
675  return;
676 
677  if (containsNaNorInf( prhs,ub_idx,BT_TRUE ) == BT_TRUE)
678  return;
679 
680 
681  /* Check inputs dimensions and assign pointers to inputs. */
682  if ( isSimplyBoundedQp == BT_TRUE )
683  {
684  nC = 0;
685 
686  if ( smartDimensionCheck( &g,nV,1, BT_FALSE,prhs,g_idx ) != SUCCESSFUL_RETURN )
687  return;
688 
689  if ( smartDimensionCheck( &lb,nV,1, BT_TRUE,prhs,lb_idx ) != SUCCESSFUL_RETURN )
690  return;
691 
692  if ( smartDimensionCheck( &ub,nV,1, BT_TRUE,prhs,ub_idx ) != SUCCESSFUL_RETURN )
693  return;
694 
695  /* default value for nWSR */
696  nWSRin = 5*nV;
697 
698  /* Check whether options are specified .*/
699  if ( nrhs == 6 )
700  if ( ( !mxIsEmpty( prhs[5] ) ) && ( mxIsStruct( prhs[5] ) ) )
701  setupOptions( &options,prhs[5],&nWSRin,&maxCpuTimeIn );
702  }
703  else
704  {
705  nC = QPInstance_getNC( globalQP );
706 
707  lbA_idx = 5;
708  ubA_idx = 6;
709 
710  if (containsNaNorInf( prhs,lbA_idx,BT_TRUE ) == BT_TRUE)
711  return;
712 
713  if (containsNaNorInf( prhs,ubA_idx,BT_TRUE ) == BT_TRUE)
714  return;
715 
716  if ( smartDimensionCheck( &g,nV,1, BT_FALSE,prhs,g_idx ) != SUCCESSFUL_RETURN )
717  return;
718 
719  if ( smartDimensionCheck( &lb,nV,1, BT_TRUE,prhs,lb_idx ) != SUCCESSFUL_RETURN )
720  return;
721 
722  if ( smartDimensionCheck( &ub,nV,1, BT_TRUE,prhs,ub_idx ) != SUCCESSFUL_RETURN )
723  return;
724 
725  if ( smartDimensionCheck( &lbA,nC,1, BT_TRUE,prhs,lbA_idx ) != SUCCESSFUL_RETURN )
726  return;
727 
728  if ( smartDimensionCheck( &ubA,nC,1, BT_TRUE,prhs,ubA_idx ) != SUCCESSFUL_RETURN )
729  return;
730 
731  /* default value for nWSR */
732  nWSRin = 5*(nV+nC);
733 
734  /* Check whether options are specified .*/
735  if ( nrhs == 8 )
736  if ( ( !mxIsEmpty( prhs[7] ) ) && ( mxIsStruct( prhs[7] ) ) )
737  setupOptions( &options,prhs[7],&nWSRin,&maxCpuTimeIn );
738  }
739 
740  /* Create output vectors and assign pointers to them. */
741  allocateOutputs( nlhs,plhs, nV,nC,1,-1 );
742 
743  /* call qpOASES */
744  if ( isSimplyBoundedQp == BT_TRUE )
745  {
746  mex_QProblemB_hotstart( handle, g,
747  lb,ub,
748  nWSRin,maxCpuTimeIn,
749  &options,
750  nlhs,plhs
751  );
752  }
753  else
754  {
755  mex_QProblem_hotstart( handle, g,
756  lb,ub,lbA,ubA,
757  nWSRin,maxCpuTimeIn,
758  &options,
759  nlhs,plhs
760  );
761  }
762 
763  return;
764  }
765 
766  /* 3) Modify matrices. */
767  if ( ( strcmp( typeString,"m" ) == 0 ) || ( strcmp( typeString,"M" ) == 0 ) )
768  {
769  /* consistency checks */
770  if ( ( nlhs < 1 ) || ( nlhs > 6 ) )
771  {
772  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
773  return;
774  }
775 
776  if ( ( nrhs < 9 ) || ( nrhs > 10 ) )
777  {
778  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
779  return;
780  }
781 
782  if ( ( mxIsDouble( prhs[1] ) == false ) || ( mxIsScalar( prhs[1] ) == false ) )
783  {
784  myMexErrMsgTxt( "ERROR (qpOASES_e): Expecting a handle to QP object as second argument!\nType 'help qpOASES_sequence' for further information." );
785  return;
786  }
787 
788 
789  /* get QP instance */
790  handle = (unsigned int)mxGetScalar( prhs[1] );
791  globalQP = getQPInstance( handle );
792  if ( globalQP == 0 )
793  {
794  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid handle to QP instance!" );
795  return;
796  }
797 
798  /* Check inputs dimensions and assign pointers to inputs. */
799  g_idx = 3;
800 
801  if ( mxIsEmpty(prhs[2]) == 1 )
802  {
803  H_idx = -1;
804  nV = (unsigned int)mxGetM( prhs[ g_idx ] ); /* if Hessian is empty, row number of gradient vector */
805  }
806  else
807  {
808  H_idx = 2;
809  nV = (unsigned int)mxGetM( prhs[ H_idx ] ); /* row number of Hessian matrix */
810  }
811 
812  A_idx = 4;
813  nC = (unsigned int)mxGetM( prhs[ A_idx ] ); /* row number of constraint matrix */
814 
815  lb_idx = 5;
816  ub_idx = 6;
817  lbA_idx = 7;
818  ubA_idx = 8;
819 
820 
821  /* ensure that data is given in double precision */
822  if ( ( ( H_idx >= 0 ) && ( mxIsDouble( prhs[H_idx] ) == 0 ) ) ||
823  ( mxIsDouble( prhs[g_idx] ) == 0 ) ||
824  ( mxIsDouble( prhs[A_idx] ) == 0 ) )
825  {
826  myMexErrMsgTxt( "ERROR (qpOASES_e): All data has to be provided in real_t precision!" );
827  return;
828  }
829 
830  /* check if supplied data contains 'NaN' or 'Inf' */
831  if (containsNaNorInf( prhs,H_idx,BT_FALSE ) == BT_TRUE)
832  return;
833 
834  if (containsNaNorInf( prhs,g_idx,BT_FALSE ) == BT_TRUE)
835  return;
836 
837  if (containsNaNorInf( prhs,A_idx,BT_FALSE ) == BT_TRUE)
838  return;
839 
840  if (containsNaNorInf( prhs,lb_idx,BT_TRUE ) == BT_TRUE)
841  return;
842 
843  if (containsNaNorInf( prhs,ub_idx,BT_TRUE ) == BT_TRUE)
844  return;
845 
846  if (containsNaNorInf( prhs,lbA_idx,BT_TRUE ) == BT_TRUE)
847  return;
848 
849  if (containsNaNorInf( prhs,ubA_idx,BT_TRUE ) == BT_TRUE)
850  return;
851 
852  /* Check that dimensions are consistent with existing QP instance */
853  if (nV != (unsigned int) QPInstance_getNV(globalQP) || nC != (unsigned int) QPInstance_getNC(globalQP))
854  {
855  myMexErrMsgTxt( "ERROR (qpOASES_e): QP dimensions must be constant during a sequence! Try creating a new QP instance instead." );
856  return;
857  }
858 
859  if ( ( H_idx >= 0 ) && ( ( mxGetN( prhs[ H_idx ] ) != nV ) || ( mxGetM( prhs[ H_idx ] ) != nV ) ) )
860  {
861  myMexErrMsgTxt( "ERROR (qpOASES_e): Hessian matrix dimension mismatch!" );
862  return;
863  }
864 
865  if ( ( mxGetN( prhs[ A_idx ] ) != 0 ) && ( mxGetN( prhs[ A_idx ] ) != nV ) )
866  {
867  myMexErrMsgTxt( "ERROR (qpOASES_e): Constraint matrix dimension mismatch!" );
868  return;
869  }
870 
871  if ( smartDimensionCheck( &g,nV,1, BT_FALSE,prhs,g_idx ) != SUCCESSFUL_RETURN )
872  return;
873 
874  if ( smartDimensionCheck( &lb,nV,1, BT_TRUE,prhs,lb_idx ) != SUCCESSFUL_RETURN )
875  return;
876 
877  if ( smartDimensionCheck( &ub,nV,1, BT_TRUE,prhs,ub_idx ) != SUCCESSFUL_RETURN )
878  return;
879 
880  if ( smartDimensionCheck( &lbA,nC,1, BT_TRUE,prhs,lbA_idx ) != SUCCESSFUL_RETURN )
881  return;
882 
883  if ( smartDimensionCheck( &ubA,nC,1, BT_TRUE,prhs,ubA_idx ) != SUCCESSFUL_RETURN )
884  return;
885 
886  /* default value for nWSR */
887  nWSRin = 5*(nV+nC);
888 
889  /* Check whether options are specified .*/
890  if ( nrhs > 9 )
891  if ( ( !mxIsEmpty( prhs[9] ) ) && ( mxIsStruct( prhs[9] ) ) )
892  setupOptions( &options,prhs[9],&nWSRin,&maxCpuTimeIn );
893 
894  /* make a deep-copy of the user-specified Hessian matrix (possibly sparse) */
895  if ( H_idx >= 0 )
896  setupHessianMatrix( prhs[H_idx],nV, &(globalQP->H) );
897 
898  /* make a deep-copy of the user-specified constraint matrix (possibly sparse) */
899  if ( ( nC > 0 ) && ( A_idx >= 0 ) )
900  setupConstraintMatrix( prhs[A_idx],nV,nC, &(globalQP->A) );
901 
902  /* Create output vectors and assign pointers to them. */
903  allocateOutputs( nlhs,plhs, nV,nC,1,-1 );
904 
905  /* Call qpOASES */
906  /*mex_SQProblem_hotstart( handle, &(globalQP->H),g,&(globalQP->A),
907  lb,ub,lbA,ubA,
908  nWSRin,maxCpuTimeIn,
909  &options,
910  nlhs,plhs
911  );*/
912  myMexErrMsgTxt( "ERROR (qpOASES_e): Hotstart with varying matrices not yet supported!" );
913 
914  return;
915  }
916 
917  /* 4) Solve current equality constrained QP. */
918  if ( ( strcmp( typeString,"e" ) == 0 ) || ( strcmp( typeString,"E" ) == 0 ) )
919  {
920  /* consistency checks */
921  if ( ( nlhs < 1 ) || ( nlhs > 4 ) )
922  {
923  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
924  return;
925  }
926 
927  if ( ( nrhs < 7 ) || ( nrhs > 8 ) )
928  {
929  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
930  return;
931  }
932 
933  if ( ( mxIsDouble( prhs[1] ) == false ) || ( mxIsScalar( prhs[1] ) == false ) )
934  {
935  myMexErrMsgTxt( "ERROR (qpOASES_e): Expecting a handle to QP object as second argument!\nType 'help qpOASES_sequence' for further information." );
936  return;
937  }
938 
939  /* get QP instance */
940  handle = (unsigned int)mxGetScalar( prhs[1] );
941  globalQP = getQPInstance( handle );
942  if ( globalQP == 0 )
943  {
944  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid handle to QP instance!" );
945  return;
946  }
947 
948  /* Check inputs dimensions and assign pointers to inputs. */
949  nRHS = (int)mxGetN(prhs[2]);
950  nV = QPInstance_getNV( globalQP );
951  nC = QPInstance_getNC( globalQP );
952 
953  g_idx = 2;
954  lb_idx = 3;
955  ub_idx = 4;
956  lbA_idx = 5;
957  ubA_idx = 6;
958 
959  /* check if supplied data contains 'NaN' or 'Inf' */
960  if (containsNaNorInf( prhs,g_idx,BT_FALSE ) == BT_TRUE)
961  return;
962 
963  if (containsNaNorInf( prhs,lb_idx,BT_TRUE ) == BT_TRUE)
964  return;
965 
966  if (containsNaNorInf( prhs,ub_idx,BT_TRUE ) == BT_TRUE)
967  return;
968 
969  if (containsNaNorInf( prhs,lbA_idx,BT_TRUE ) == BT_TRUE)
970  return;
971 
972  if (containsNaNorInf( prhs,ubA_idx,BT_TRUE ) == BT_TRUE)
973  return;
974 
975  if ( smartDimensionCheck( &g,nV,nRHS, BT_FALSE,prhs,g_idx ) != SUCCESSFUL_RETURN )
976  return;
977 
978  if ( smartDimensionCheck( &lb,nV,nRHS, BT_TRUE,prhs,lb_idx ) != SUCCESSFUL_RETURN )
979  return;
980 
981  if ( smartDimensionCheck( &ub,nV,nRHS, BT_TRUE,prhs,ub_idx ) != SUCCESSFUL_RETURN )
982  return;
983 
984  if ( smartDimensionCheck( &lbA,nC,nRHS, BT_TRUE,prhs,lbA_idx ) != SUCCESSFUL_RETURN )
985  return;
986 
987  if ( smartDimensionCheck( &ubA,nC,nRHS, BT_TRUE,prhs,ubA_idx ) != SUCCESSFUL_RETURN )
988  return;
989 
990  /* Check whether options are specified .*/
991  if ( ( nrhs == 8 ) && ( !mxIsEmpty( prhs[7] ) ) && ( mxIsStruct( prhs[7] ) ) )
992  {
993  nWSRin = 5*(nV+nC);
994  setupOptions( &options,prhs[7],&nWSRin,&maxCpuTimeIn );
995  QProblem_setOptions( &(globalQP->sqp),options );
996  }
997 
998  /* Create output vectors and assign pointers to them. */
999  plhs[0] = mxCreateDoubleMatrix( nV, nRHS, mxREAL );
1000  x_out = mxGetPr(plhs[0]);
1001  if (nlhs >= 2)
1002  {
1003  plhs[1] = mxCreateDoubleMatrix( nV+nC, nRHS, mxREAL );
1004  y_out = mxGetPr(plhs[1]);
1005 
1006  if (nlhs >= 3)
1007  {
1008  plhs[2] = mxCreateDoubleMatrix( nV, nRHS, mxREAL );
1009  workingSetB = mxGetPr(plhs[2]);
1010  QProblem_getWorkingSetBounds( &(globalQP->sqp),workingSetB );
1011 
1012  if ( nlhs >= 4 )
1013  {
1014  plhs[3] = mxCreateDoubleMatrix( nC, nRHS, mxREAL );
1015  workingSetC = mxGetPr(plhs[3]);
1016  QProblem_getWorkingSetConstraints( &(globalQP->sqp),workingSetC );
1017  }
1018  }
1019  }
1020 
1021  /* Solve equality constrained QP */
1022  returnvalue = QProblem_solveCurrentEQP( &(globalQP->sqp),nRHS,g,lb,ub,lbA,ubA, x_out,(y_out!=0) ? y_out : y_out_tmp );
1023 
1024  if (returnvalue != SUCCESSFUL_RETURN)
1025  {
1026  snprintf(msg, QPOASES_MAX_STRING_LENGTH, "ERROR (qpOASES_e): Couldn't solve current EQP (code %d)!", returnvalue);
1027  myMexErrMsgTxt(msg);
1028  return;
1029  }
1030 
1031  return;
1032  }
1033 
1034  /* 5) Cleanup. */
1035  if ( ( strcmp( typeString,"c" ) == 0 ) || ( strcmp( typeString,"C" ) == 0 ) )
1036  {
1037  /* consistency checks */
1038  if ( nlhs != 0 )
1039  {
1040  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of output arguments!\nType 'help qpOASES_sequence' for further information." );
1041  return;
1042  }
1043 
1044  if ( nrhs != 2 )
1045  {
1046  myMexErrMsgTxt( "ERROR (qpOASES_e): Invalid number of input arguments!\nType 'help qpOASES_sequence' for further information." );
1047  return;
1048  }
1049 
1050  if ( ( mxIsDouble( prhs[1] ) == false ) || ( mxIsScalar( prhs[1] ) == false ) )
1051  {
1052  myMexErrMsgTxt( "ERROR (qpOASES_e): Expecting a handle to QP object as second argument!\nType 'help qpOASES_sequence' for further information." );
1053  return;
1054  }
1055 
1056  /* Cleanup SQProblem instance. */
1057  /* nothing to do as all memory is static! */
1058 
1059  return;
1060  }
1061 
1062 }
1063 
1064 /*
1065  * end of file
1066  */
returnValue Bounds_setupBound(Bounds *_THIS, int number, SubjectToStatus _status)
Definition: Bounds.c:125
static int QProblemB_getNV(QProblemB *_THIS)
Definition: QProblemB.h:1172
void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
BooleanType containsNaNorInf(const mxArray *prhs[], int_t rhs_index, bool mayContainInf)
int QPInstance_getNV(QPInstance *_THIS)
static BooleanType qpOASES_isEqual(real_t x, real_t y, real_t TOL)
Definition: Utils.h:371
#define ST_LOWER
returnValue setupHessianMatrix(const mxArray *prhsH, int_t nV, SymmetricMatrix **H, sparse_int_t **Hir, sparse_int_t **Hjc, real_t **Hv)
Implements the online active set strategy for box-constrained QPs.
#define myMexErrMsgTxt
returnValue setupOptions(Options *options, const mxArray *optionsPtr, int &nWSRin)
Allows to pass back messages to the calling function.
int QPInstance_getNC(QPInstance *_THIS)
returnValue QProblem_initMW(QProblem *_THIS, DenseMatrix *_H, const real_t *const _g, DenseMatrix *_A, const real_t *const _lb, const real_t *const _ub, const real_t *const _lbA, const real_t *const _ubA, int *nWSR, real_t *const cputime, const real_t *const xOpt, const real_t *const yOpt, Bounds *const guessedBounds, Constraints *const guessedConstraints, const real_t *const _R)
Definition: QProblem.c:355
returnValue smartDimensionCheck(real_t **input, unsigned int m, unsigned int n, BooleanType emptyAllowed, const mxArray *prhs[], int idx)
returnValue Constraints_setupConstraint(Constraints *_THIS, int number, SubjectToStatus _status)
Definition: Constraints.c:127
returnValue convertFortranToC(const real_t *const A_for, int nV, int nC, real_t *const A)
#define PL_NONE
#define ST_INACTIVE
returnValue obtainOutputsSB(int k, QProblemB *qp, returnValue returnvalue, int _nWSRout, double _cpuTime, int nlhs, mxArray *plhs[], int nV, int handle)
int mex_SQProblem_init(int handle, DenseMatrix *H, real_t *g, DenseMatrix *A, const real_t *const lb, const real_t *const ub, const real_t *const lbA, const real_t *const ubA, int nWSRin, real_t maxCpuTimeIn, const double *const x0, Options *options, int nOutputs, mxArray *plhs[], const double *const guessedBounds, const double *const guessedConstraints, const double *const _R)
static int QProblem_getNV(QProblem *_THIS)
Definition: QProblem.h:1691
returnValue QProblem_solveCurrentEQP(QProblem *_THIS, const int n_rhs, const real_t *g_in, const real_t *lb_in, const real_t *ub_in, const real_t *lbA_in, const real_t *ubA_in, real_t *x_out, real_t *y_out)
Definition: QProblem.c:910
static QProblemB * globalQPB
USING_NAMESPACE_QPOASES int mex_QProblemB_init(int handle, DenseMatrix *H, real_t *g, const real_t *const lb, const real_t *const ub, int nWSRin, real_t maxCpuTimeIn, const double *const x0, Options *options, int nOutputs, mxArray *plhs[], const double *const guessedBounds, const double *const _R)
#define PL_HIGH
Interfaces matrix-vector operations tailored to general dense matrices.
void allocateOutputs(int nlhs, mxArray *plhs[], int nV, int nC=0, int nP=1)
static SQProblem * globalSQP
returnValue setupAuxiliaryInputs(const mxArray *auxInput, uint_t nV, uint_t nC, HessianType *hessianType, double **x0, double **guessedBounds, double **guessedConstraints, double **R)
int_t QProblemB_hotstart(const real_t *const g, const real_t *const lb, const real_t *const ub, int_t *const nWSR, real_t *const cputime, real_t *const x, real_t *const y, real_t *const obj, int_t *const status)
Provides a generic way to set and pass user-specified options.
Definition: options.hpp:65
int_t allocateQPInstance(int_t nV, int_t nC, HessianType hessianType, BooleanType isSimplyBounded, const Options *options)
#define PL_LOW
static returnValue QProblemB_setOptions(QProblemB *_THIS, Options _options)
Definition: QProblemB.h:1299
static const real_t QPOASES_INFTY
void obtainOutputs(int k, QProblemB *qp, returnValue returnvalue, int nWSRin, int nlhs, mxArray *plhs[], int nV, int nC=0)
static int QProblem_getNC(QProblem *_THIS)
Definition: QProblem.h:2061
#define BT_TRUE
Definition: acado_types.hpp:47
returnValue Options_setToDefault(Options *_THIS)
Definition: Options.c:112
returnValue QProblem_getWorkingSetConstraints(QProblem *_THIS, real_t *workingSetC)
Definition: QProblem.c:1022
#define HST_UNKNOWN
SymmetricMatrix * H
returnValue setupConstraintMatrix(const mxArray *prhsA, int_t nV, int_t nC, Matrix **A, sparse_int_t **Air, sparse_int_t **Ajc, real_t **Av)
#define QPOASES_MAX_STRING_LENGTH
#define BT_FALSE
Definition: acado_types.hpp:49
int mex_QProblem_hotstart(int handle, 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 nWSRin, real_t maxCpuTimeIn, Options *options, int nOutputs, mxArray *plhs[])
Manages working sets of bounds (= box constraints).
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)
#define ST_UPPER
double real_t
Definition: AD_test.c:10
int mex_QProblemB_hotstart(int handle, const real_t *const g, const real_t *const lb, const real_t *const ub, int nWSRin, real_t maxCpuTimeIn, Options *options, int nOutputs, mxArray *plhs[])
Implements the online active set strategy for QPs with general constraints.
QPInstance * getQPInstance(int_t handle)
static const real_t QPOASES_TOL
void ConstraintsCON(Constraints *_THIS, int _n)
Definition: Constraints.c:50
returnValue QProblemB_initMW(QProblemB *_THIS, DenseMatrix *_H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int *nWSR, real_t *const cputime, const real_t *const xOpt, const real_t *const yOpt, Bounds *const guessedBounds, const real_t *const _R)
Definition: QProblemB.c:273
#define R
static returnValue QProblem_setOptions(QProblem *_THIS, Options _options)
Definition: QProblem.h:1818
void BoundsCON(Bounds *_THIS, int _n)
Definition: Bounds.c:50
returnValue QProblem_getWorkingSetBounds(QProblem *_THIS, real_t *workingSetB)
Definition: QProblem.c:1001


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