qpOASES_sequenceVM.cpp
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-2011 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/SQProblem.hpp>
39 
40 
41 using namespace qpOASES;
42 
43 #include <qpOASES_matlab_utils.cpp>
44 
45 
46 /* global pointer to QP object */
47 static SQProblem* globalSQP = 0;
49 static Matrix* globalSQP_A = 0;
50 static long* globalSQP_Hdiag = 0;
51 
52 
53 /*
54  * a l l o c a t e G l o b a l S Q P r o b l e m I n s t a n c e
55  */
57  )
58 {
59  globalSQP = new SQProblem( nV,nC );
60  globalSQP->setOptions( *options );
61 
62  return;
63 }
64 
65 
66 /*
67  * d e l e t e G l o b a l S Q P r o b l e m I n s t a n c e
68  */
70 {
71  if ( globalSQP != 0 )
72  {
73  delete globalSQP;
74  globalSQP = 0;
75  }
76 
77  return;
78 }
79 
80 
81 /*
82  * d e l e t e G l o b a l S Q P r o b l e m M a t r i c e s
83  */
85 {
86  if ( globalSQP_H != 0 )
87  {
88  delete globalSQP_H;
89  globalSQP_H = 0;
90  }
91 
92  if ( globalSQP_A != 0 )
93  {
94  delete globalSQP_A;
95  globalSQP_A = 0;
96  }
97 
98  if ( globalSQP_Hdiag != 0 )
99  {
100  delete[] globalSQP_Hdiag;
101  globalSQP_Hdiag = 0;
102  }
103 
104  return;
105 }
106 
107 
108 /*
109  * i n i t V M
110  */
111 void initVM( int nV, int nC,
113  const real_t* const lb, const real_t* const ub, const real_t* const lbA, const real_t* const ubA,
114  int nWSR, const real_t* const x0, Options* options,
115  int nOutputs, mxArray* plhs[]
116  )
117 {
118  /* 1) Setup initial QP. */
119  allocateGlobalSQProblemInstance( nV,nC,options );
120 
121  /* 2) Solve initial QP. */
122  returnValue returnvalue;
123 
124  if ( x0 == 0 )
125  returnvalue = globalSQP->init( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
126  else
127  returnvalue = globalSQP->init( H,g,A,lb,ub,lbA,ubA, nWSR,0, x0,0,0,0 );
128 
129  /* 3) Assign lhs arguments. */
130  obtainOutputs( 0,globalSQP,returnvalue,nWSR,
131  nOutputs,plhs,0,0 );
132 
133  return;
134 }
135 
136 
137 /*
138  * h o t s t a r t V M
139  */
141  const real_t* const lb, const real_t* const ub, const real_t* const lbA, const real_t* const ubA,
142  int nWSR, Options* options,
143  int nOutputs, mxArray* plhs[]
144  )
145 {
146  /* 1) Solve QP. */
147  globalSQP->setOptions( *options );
148  returnValue returnvalue = globalSQP->hotstart( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
149 
150  /* 2) Assign lhs arguments. */
151  obtainOutputs( 0,globalSQP,returnvalue,nWSR,
152  nOutputs,plhs,0,0 );
153 
154  return;
155 }
156 
157 
158 
159 /*
160  * m e x F u n c t i o n
161  */
162 void mexFunction( int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[] )
163 {
164  unsigned int i, j;
165 
166  /* inputs */
167  char* typeString;
168  real_t *H_for=0, *H_mem=0, *g=0, *A_for=0, *A_mem=0, *lb=0, *ub=0, *lbA=0, *ubA=0, *x0=0;
169 
171  options.printLevel = PL_LOW;
172  #ifdef __DEBUG__
173  options.printLevel = PL_HIGH;
174  #endif
175  #ifdef __SUPPRESSANYOUTPUT__
176  options.printLevel = PL_NONE;
177  #endif
178 
179  /* dimensions */
180  unsigned int nV=0, nC=0;
181 
182 
183  /* I) CONSISTENCY CHECKS: */
184  /* 1) Ensure that qpOASES is called with a feasible number of input arguments. */
185  if ( ( nrhs < 8 ) || ( nrhs > 10 ) )
186  if ( nrhs != 1 )
187  mexErrMsgTxt( "ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
188 
189  /* 2) Ensure that first input is a string (and if so, read it). */
190  if ( mxIsChar( prhs[0] ) != 1 )
191  mexErrMsgTxt( "ERROR (qpOASES): First input argument must be a string!" );
192 
193  typeString = (char*) mxGetPr( prhs[0] );
194 
195 
196  /* II) SELECT RESPECTIVE QPOASES FUNCTION CALL: */
197  /* 1) Init (without or with initial guess for primal solution) OR
198  * 2) Hotstart. */
199  if ( ( strcmp( typeString,"i" ) == 0 ) || ( strcmp( typeString,"I" ) == 0 ) ||
200  ( strcmp( typeString,"h" ) == 0 ) || ( strcmp( typeString,"H" ) == 0 ) )
201  {
202  /* consistency checks */
203  if ( ( nlhs < 1 ) || ( nlhs > 5 ) )
204  mexErrMsgTxt( "ERROR (qpOASES): Invalid number of output arguments!\nType 'help qpOASES_sequenceVM' for further information." );
205 
206  if ( ( nrhs < 8 ) || ( nrhs > 10 ) )
207  mexErrMsgTxt( "ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
208 
209  /* ensure that data is given in real_t precision */
210  if ( ( mxIsDouble( prhs[1] ) == 0 ) ||
211  ( mxIsDouble( prhs[2] ) == 0 ) ||
212  ( mxIsDouble( prhs[3] ) == 0 ) )
213  mexErrMsgTxt( "ERROR (qpOASES): All data has to be provided in real_t precision!" );
214 
215  /* ensure that matrices are stored in dense format */
216 // if ( ( mxIsSparse( prhs[1] ) != 0 ) || ( mxIsSparse( prhs[3] ) != 0 ) )
217 // mexErrMsgTxt( "ERROR (qpOASES): Matrices must not be stored in sparse format!" );
218 
219 
220  /* Check inputs dimensions and assign pointers to inputs. */
221  nV = mxGetM( prhs[1] ); /* row number of Hessian matrix */
222  nC = mxGetM( prhs[3] ); /* row number of constraint matrix */
223 
224  if ( ( mxGetN( prhs[1] ) != nV ) || ( ( mxGetN( prhs[3] ) != 0 ) && ( mxGetN( prhs[3] ) != nV ) ) )
225  mexErrMsgTxt( "ERROR (qpOASES): Input dimension mismatch!" );
226 
227  if ( smartDimensionCheck( &g,nV,1, BT_FALSE,prhs,2 ) != SUCCESSFUL_RETURN )
228  return;
229 
230  if ( smartDimensionCheck( &lb,nV,1, BT_TRUE,prhs,4 ) != SUCCESSFUL_RETURN )
231  return;
232 
233  if ( smartDimensionCheck( &ub,nV,1, BT_TRUE,prhs,5 ) != SUCCESSFUL_RETURN )
234  return;
235 
236  if ( smartDimensionCheck( &lbA,nC,1, BT_TRUE,prhs,6 ) != SUCCESSFUL_RETURN )
237  return;
238 
239  if ( smartDimensionCheck( &ubA,nC,1, BT_TRUE,prhs,7 ) != SUCCESSFUL_RETURN )
240  return;
241 
242  /* default value for nWSR */
243  int nWSRin = 5*(nV+nC);
244 
245  /* Check whether x0 and options are specified .*/
246  if ( ( ( strcmp( typeString,"i" ) == 0 ) ) || ( strcmp( typeString,"I" ) == 0 ) )
247  {
248  if ( nrhs > 8 )
249  {
250  if ( smartDimensionCheck( &x0,nV,1, BT_TRUE,prhs,8 ) != SUCCESSFUL_RETURN )
251  return;
252 
253  if ( nrhs > 9 )
254  if ( ( !mxIsEmpty( prhs[9] ) ) && ( mxIsStruct( prhs[9] ) ) )
255  setupOptions( &options,prhs[9],nWSRin );
256  }
257  }
258  else /* hotstart */
259  {
260  if ( nrhs > 9 )
261  mexErrMsgTxt( "ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
262 
263  if ( nrhs > 8 )
264  if ( ( !mxIsEmpty( prhs[8] ) ) && ( mxIsStruct( prhs[8] ) ) )
265  setupOptions( &options,prhs[8],nWSRin );
266  }
267 
269 
270  /* check for sparsity */
271  if ( mxIsSparse( prhs[1] ) != 0 )
272  {
273  long *ir = (long *)mxGetIr(prhs[1]);
274  long *jc = (long *)mxGetJc(prhs[1]);
275  real_t *v = (real_t*)mxGetPr(prhs[1]);
276  // mind pointer offsets due to 1-based indexing in Matlab
277  SymSparseMat *sH;
278  globalSQP_H = sH = new SymSparseMat(nV, nV, ir, jc, v);
280  }
281  else
282  {
283  H_for = (real_t*) mxGetPr( prhs[1] );
284  H_mem = new real_t[nV*nV];
285  for( int i=0; i<nV*nV; ++i )
286  H_mem[i] = H_for[i];
287  globalSQP_H = new SymDenseMat( nV, nV, nV, H_mem );
288  globalSQP_H->doFreeMemory();
289  }
290 
291  /* Convert constraint matrix A from FORTRAN to C style
292  * (not necessary for H as it should be symmetric!). */
293  if ( nC > 0 )
294  {
295  /* Check for sparsity. */
296  if ( mxIsSparse( prhs[3] ) != 0 )
297  {
298  long *ir = (long *)mxGetIr(prhs[3]);
299  long *jc = (long *)mxGetJc(prhs[3]);
300  real_t *v = (real_t*)mxGetPr(prhs[3]);
301  // mind pointer offsets due to 1-based indexing in Matlab
302  globalSQP_A = new SparseMatrix(nC, nV, ir, jc, v);
303  }
304  else
305  {
306  /* Convert constraint matrix A from FORTRAN to C style
307  * (not necessary for H as it should be symmetric!). */
308  A_for = (real_t*) mxGetPr( prhs[3] );
309  A_mem = new real_t[nC*nV];
310  convertFortranToC( A_for,nV,nC, A_mem );
311  globalSQP_A = new DenseMatrix(nC, nV, nV, A_mem );
312  globalSQP_A->doFreeMemory();
313  }
314  }
315 
316  /* Create output vectors and assign pointers to them. */
317  allocateOutputs( nlhs,plhs, nV,nC );
318 
319  /* Call qpOASES */
320  if ( ( ( strcmp( typeString,"i" ) == 0 ) ) || ( strcmp( typeString,"I" ) == 0 ) )
321  {
323 
324  initVM( nV,nC,
325  globalSQP_H,g,globalSQP_A,
326  lb,ub,lbA,ubA,
327  nWSRin,x0,&options,
328  nlhs,plhs
329  );
330  }
331  else /* hotstart */
332  {
333  if ( globalSQP == 0 )
334  mexErrMsgTxt( "ERROR (qpOASES): QP needs to be initialised first!" );
335 
336  if ( ( (int)nV != globalSQP->getNV( ) ) || ( (int)nC != globalSQP->getNC( ) ) )
337  mexErrMsgTxt( "ERROR (qpOASES): QP dimensions must be constant during a sequence!" );
338 
339  /* QUICK HACK TO BE REMOVED! */
340  globalSQP->resetMatrixPointers( );
341 
342  hotstartVM( globalSQP_H,g,globalSQP_A,
343  lb,ub,lbA,ubA,
344  nWSRin,&options,
345  nlhs,plhs
346  );
347  }
348 
349  return;
350  }
351 
352  /* 3) Cleanup. */
353  if ( ( strcmp( typeString,"c" ) == 0 ) || ( strcmp( typeString,"C" ) == 0 ) )
354  {
355  /* consistency checks */
356  if ( nlhs != 0 )
357  mexErrMsgTxt( "ERROR (qpOASES): Invalid number of output arguments!\nType 'help qpOASES_sequenceVM' for further information." );
358 
359  if ( nrhs != 1 )
360  mexErrMsgTxt( "ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
361 
362  /* Cleanup global SQProblem instance. */
365  return;
366  }
367 }
368 
369 
370 /*
371  * end of file
372  */
Interfaces matrix-vector operations tailored to symmetric sparse matrices.
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)
Implements the online active set strategy for QPs with varying matrices.
static long * globalSQP_Hdiag
returnValue setupOptions(Options *options, const mxArray *optionsPtr, int &nWSRin)
Allows to pass back messages to the calling function.
Interfaces matrix-vector operations tailored to symmetric dense matrices.
int getNV() const
returnValue smartDimensionCheck(real_t **input, unsigned int m, unsigned int n, BooleanType emptyAllowed, const mxArray *prhs[], int idx)
returnValue convertFortranToC(const real_t *const A_for, int nV, int nC, real_t *const A)
void initVM(int nV, int nC, SymmetricMatrix *H, real_t *g, Matrix *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 x0, Options *options, int nOutputs, mxArray *plhs[])
#define PL_NONE
returnValue setOptions(const Options &_options)
void deleteGlobalSQProblemInstance()
#define PL_HIGH
Interfaces matrix-vector operations tailored to general dense matrices.
void allocateGlobalSQProblemInstance(int nV, int nC, Options *options)
void hotstartVM(SymmetricMatrix *H, real_t *g, Matrix *A, const real_t *const lb, const real_t *const ub, const real_t *const lbA, const real_t *const ubA, int nWSR, Options *options, int nOutputs, mxArray *plhs[])
void allocateOutputs(int nlhs, mxArray *plhs[], int nV, int nC=0, int nP=1)
Interfaces matrix-vector operations tailored to general sparse matrices.
static SQProblem * globalSQP
Provides a generic way to set and pass user-specified options.
Definition: options.hpp:65
void deleteGlobalSQProblemMatrices()
Abstract base class for interfacing tailored matrix-vector operations.
#define PL_LOW
#define v
int getNC() const
void obtainOutputs(int k, QProblemB *qp, returnValue returnvalue, int nWSRin, int nlhs, mxArray *plhs[], int nV, int nC=0)
#define BT_TRUE
Definition: acado_types.hpp:47
static SymmetricMatrix * globalSQP_H
#define BT_FALSE
Definition: acado_types.hpp:49
static Matrix * globalSQP_A
double real_t
Definition: AD_test.c:10
void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
Abstract base class for interfacing matrix-vector operations tailored to symmetric matrices...
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)


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