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


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