00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00038 #include <qpOASES/SQProblem.hpp>
00039
00040
00041 using namespace qpOASES;
00042
00043 #include <qpOASES_matlab_utils.cpp>
00044
00045
00046
00047 static SQProblem* globalSQP = 0;
00048 static SymmetricMatrix* globalSQP_H = 0;
00049 static Matrix* globalSQP_A = 0;
00050 static long* globalSQP_Hdiag = 0;
00051
00052
00053
00054
00055
00056 void allocateGlobalSQProblemInstance( int nV, int nC, Options* options
00057 )
00058 {
00059 globalSQP = new SQProblem( nV,nC );
00060 globalSQP->setOptions( *options );
00061
00062 return;
00063 }
00064
00065
00066
00067
00068
00069 void deleteGlobalSQProblemInstance( )
00070 {
00071 if ( globalSQP != 0 )
00072 {
00073 delete globalSQP;
00074 globalSQP = 0;
00075 }
00076
00077 return;
00078 }
00079
00080
00081
00082
00083
00084 void deleteGlobalSQProblemMatrices( )
00085 {
00086 if ( globalSQP_H != 0 )
00087 {
00088 delete globalSQP_H;
00089 globalSQP_H = 0;
00090 }
00091
00092 if ( globalSQP_A != 0 )
00093 {
00094 delete globalSQP_A;
00095 globalSQP_A = 0;
00096 }
00097
00098 if ( globalSQP_Hdiag != 0 )
00099 {
00100 delete[] globalSQP_Hdiag;
00101 globalSQP_Hdiag = 0;
00102 }
00103
00104 return;
00105 }
00106
00107
00108
00109
00110
00111 void initVM( int nV, int nC,
00112 SymmetricMatrix *H, real_t* g, Matrix *A,
00113 const real_t* const lb, const real_t* const ub, const real_t* const lbA, const real_t* const ubA,
00114 int nWSR, const real_t* const x0, Options* options,
00115 int nOutputs, mxArray* plhs[]
00116 )
00117 {
00118
00119 allocateGlobalSQProblemInstance( nV,nC,options );
00120
00121
00122 returnValue returnvalue;
00123
00124 if ( x0 == 0 )
00125 returnvalue = globalSQP->init( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
00126 else
00127 returnvalue = globalSQP->init( H,g,A,lb,ub,lbA,ubA, nWSR,0, x0,0,0,0 );
00128
00129
00130 obtainOutputs( 0,globalSQP,returnvalue,nWSR,
00131 nOutputs,plhs,0,0 );
00132
00133 return;
00134 }
00135
00136
00137
00138
00139
00140 void hotstartVM( SymmetricMatrix *H, real_t* g, Matrix *A,
00141 const real_t* const lb, const real_t* const ub, const real_t* const lbA, const real_t* const ubA,
00142 int nWSR, Options* options,
00143 int nOutputs, mxArray* plhs[]
00144 )
00145 {
00146
00147 globalSQP->setOptions( *options );
00148 returnValue returnvalue = globalSQP->hotstart( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
00149
00150
00151 obtainOutputs( 0,globalSQP,returnvalue,nWSR,
00152 nOutputs,plhs,0,0 );
00153
00154 return;
00155 }
00156
00157
00158
00159
00160
00161
00162 void mexFunction( int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[] )
00163 {
00164 unsigned int i, j;
00165
00166
00167 char* typeString;
00168 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;
00169
00170 Options options;
00171 options.printLevel = PL_LOW;
00172 #ifdef __DEBUG__
00173 options.printLevel = PL_HIGH;
00174 #endif
00175 #ifdef __SUPPRESSANYOUTPUT__
00176 options.printLevel = PL_NONE;
00177 #endif
00178
00179
00180 unsigned int nV=0, nC=0;
00181
00182
00183
00184
00185 if ( ( nrhs < 8 ) || ( nrhs > 10 ) )
00186 if ( nrhs != 1 )
00187 mexErrMsgTxt( "ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
00188
00189
00190 if ( mxIsChar( prhs[0] ) != 1 )
00191 mexErrMsgTxt( "ERROR (qpOASES): First input argument must be a string!" );
00192
00193 typeString = (char*) mxGetPr( prhs[0] );
00194
00195
00196
00197
00198
00199 if ( ( strcmp( typeString,"i" ) == 0 ) || ( strcmp( typeString,"I" ) == 0 ) ||
00200 ( strcmp( typeString,"h" ) == 0 ) || ( strcmp( typeString,"H" ) == 0 ) )
00201 {
00202
00203 if ( ( nlhs < 1 ) || ( nlhs > 5 ) )
00204 mexErrMsgTxt( "ERROR (qpOASES): Invalid number of output arguments!\nType 'help qpOASES_sequenceVM' for further information." );
00205
00206 if ( ( nrhs < 8 ) || ( nrhs > 10 ) )
00207 mexErrMsgTxt( "ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
00208
00209
00210 if ( ( mxIsDouble( prhs[1] ) == 0 ) ||
00211 ( mxIsDouble( prhs[2] ) == 0 ) ||
00212 ( mxIsDouble( prhs[3] ) == 0 ) )
00213 mexErrMsgTxt( "ERROR (qpOASES): All data has to be provided in real_t precision!" );
00214
00215
00216
00217
00218
00219
00220
00221 nV = mxGetM( prhs[1] );
00222 nC = mxGetM( prhs[3] );
00223
00224 if ( ( mxGetN( prhs[1] ) != nV ) || ( ( mxGetN( prhs[3] ) != 0 ) && ( mxGetN( prhs[3] ) != nV ) ) )
00225 mexErrMsgTxt( "ERROR (qpOASES): Input dimension mismatch!" );
00226
00227 if ( smartDimensionCheck( &g,nV,1, BT_FALSE,prhs,2 ) != SUCCESSFUL_RETURN )
00228 return;
00229
00230 if ( smartDimensionCheck( &lb,nV,1, BT_TRUE,prhs,4 ) != SUCCESSFUL_RETURN )
00231 return;
00232
00233 if ( smartDimensionCheck( &ub,nV,1, BT_TRUE,prhs,5 ) != SUCCESSFUL_RETURN )
00234 return;
00235
00236 if ( smartDimensionCheck( &lbA,nC,1, BT_TRUE,prhs,6 ) != SUCCESSFUL_RETURN )
00237 return;
00238
00239 if ( smartDimensionCheck( &ubA,nC,1, BT_TRUE,prhs,7 ) != SUCCESSFUL_RETURN )
00240 return;
00241
00242
00243 int nWSRin = 5*(nV+nC);
00244
00245
00246 if ( ( ( strcmp( typeString,"i" ) == 0 ) ) || ( strcmp( typeString,"I" ) == 0 ) )
00247 {
00248 if ( nrhs > 8 )
00249 {
00250 if ( smartDimensionCheck( &x0,nV,1, BT_TRUE,prhs,8 ) != SUCCESSFUL_RETURN )
00251 return;
00252
00253 if ( nrhs > 9 )
00254 if ( ( !mxIsEmpty( prhs[9] ) ) && ( mxIsStruct( prhs[9] ) ) )
00255 setupOptions( &options,prhs[9],nWSRin );
00256 }
00257 }
00258 else
00259 {
00260 if ( nrhs > 9 )
00261 mexErrMsgTxt( "ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
00262
00263 if ( nrhs > 8 )
00264 if ( ( !mxIsEmpty( prhs[8] ) ) && ( mxIsStruct( prhs[8] ) ) )
00265 setupOptions( &options,prhs[8],nWSRin );
00266 }
00267
00268 deleteGlobalSQProblemMatrices( );
00269
00270
00271 if ( mxIsSparse( prhs[1] ) != 0 )
00272 {
00273 long *ir = (long *)mxGetIr(prhs[1]);
00274 long *jc = (long *)mxGetJc(prhs[1]);
00275 real_t *v = (real_t*)mxGetPr(prhs[1]);
00276
00277 SymSparseMat *sH;
00278 globalSQP_H = sH = new SymSparseMat(nV, nV, ir, jc, v);
00279 globalSQP_Hdiag = sH->createDiagInfo();
00280 }
00281 else
00282 {
00283 H_for = (real_t*) mxGetPr( prhs[1] );
00284 H_mem = new real_t[nV*nV];
00285 for( int i=0; i<nV*nV; ++i )
00286 H_mem[i] = H_for[i];
00287 globalSQP_H = new SymDenseMat( nV, nV, nV, H_mem );
00288 globalSQP_H->doFreeMemory();
00289 }
00290
00291
00292
00293 if ( nC > 0 )
00294 {
00295
00296 if ( mxIsSparse( prhs[3] ) != 0 )
00297 {
00298 long *ir = (long *)mxGetIr(prhs[3]);
00299 long *jc = (long *)mxGetJc(prhs[3]);
00300 real_t *v = (real_t*)mxGetPr(prhs[3]);
00301
00302 globalSQP_A = new SparseMatrix(nC, nV, ir, jc, v);
00303 }
00304 else
00305 {
00306
00307
00308 A_for = (real_t*) mxGetPr( prhs[3] );
00309 A_mem = new real_t[nC*nV];
00310 convertFortranToC( A_for,nV,nC, A_mem );
00311 globalSQP_A = new DenseMatrix(nC, nV, nV, A_mem );
00312 globalSQP_A->doFreeMemory();
00313 }
00314 }
00315
00316
00317 allocateOutputs( nlhs,plhs, nV,nC );
00318
00319
00320 if ( ( ( strcmp( typeString,"i" ) == 0 ) ) || ( strcmp( typeString,"I" ) == 0 ) )
00321 {
00322 deleteGlobalSQProblemInstance( );
00323
00324 initVM( nV,nC,
00325 globalSQP_H,g,globalSQP_A,
00326 lb,ub,lbA,ubA,
00327 nWSRin,x0,&options,
00328 nlhs,plhs
00329 );
00330 }
00331 else
00332 {
00333 if ( globalSQP == 0 )
00334 mexErrMsgTxt( "ERROR (qpOASES): QP needs to be initialised first!" );
00335
00336 if ( ( (int)nV != globalSQP->getNV( ) ) || ( (int)nC != globalSQP->getNC( ) ) )
00337 mexErrMsgTxt( "ERROR (qpOASES): QP dimensions must be constant during a sequence!" );
00338
00339
00340 globalSQP->resetMatrixPointers( );
00341
00342 hotstartVM( globalSQP_H,g,globalSQP_A,
00343 lb,ub,lbA,ubA,
00344 nWSRin,&options,
00345 nlhs,plhs
00346 );
00347 }
00348
00349 return;
00350 }
00351
00352
00353 if ( ( strcmp( typeString,"c" ) == 0 ) || ( strcmp( typeString,"C" ) == 0 ) )
00354 {
00355
00356 if ( nlhs != 0 )
00357 mexErrMsgTxt( "ERROR (qpOASES): Invalid number of output arguments!\nType 'help qpOASES_sequenceVM' for further information." );
00358
00359 if ( nrhs != 1 )
00360 mexErrMsgTxt( "ERROR (qpOASES): Invalid number of input arguments!\nType 'help qpOASES_sequenceVM' for further information." );
00361
00362
00363 deleteGlobalSQProblemInstance( );
00364 deleteGlobalSQProblemMatrices( );
00365 return;
00366 }
00367 }
00368
00369
00370
00371
00372