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