qpOASES_sequenceVM.cpp
Go to the documentation of this file.
00001 /*
00002  *      This file is part of qpOASES.
00003  *
00004  *      qpOASES -- An Implementation of the Online Active Set Strategy.
00005  *      Copyright (C) 2007-2011 by Hans Joachim Ferreau, Andreas Potschka,
00006  *      Christian Kirches et al. All rights reserved.
00007  *
00008  *      qpOASES is free software; you can redistribute it and/or
00009  *      modify it under the terms of the GNU Lesser General Public
00010  *      License as published by the Free Software Foundation; either
00011  *      version 2.1 of the License, or (at your option) any later version.
00012  *
00013  *      qpOASES is distributed in the hope that it will be useful,
00014  *      but WITHOUT ANY WARRANTY; without even the implied warranty of
00015  *      MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
00016  *      See the GNU Lesser General Public License for more details.
00017  *
00018  *      You should have received a copy of the GNU Lesser General Public
00019  *      License along with qpOASES; if not, write to the Free Software
00020  *      Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
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 /* global pointer to QP object */
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  *      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
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  *      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
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  *      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
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  *      i n i t V M
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         /* 1) Setup initial QP. */
00119         allocateGlobalSQProblemInstance( nV,nC,options );
00120 
00121         /* 2) Solve initial QP. */
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         /* 3) Assign lhs arguments. */
00130         obtainOutputs(  0,globalSQP,returnvalue,nWSR,
00131                                         nOutputs,plhs,0,0 );
00132 
00133         return;
00134 }
00135 
00136 
00137 /*
00138  *      h o t s t a r t V M
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         /* 1) Solve QP. */
00147         globalSQP->setOptions( *options );
00148         returnValue returnvalue = globalSQP->hotstart( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
00149 
00150         /* 2) Assign lhs arguments. */
00151         obtainOutputs(  0,globalSQP,returnvalue,nWSR,
00152                                         nOutputs,plhs,0,0 );
00153 
00154         return;
00155 }
00156 
00157 
00158 
00159 /*
00160  *      m e x F u n c t i o n
00161  */
00162 void mexFunction( int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[] )
00163 {
00164         unsigned int i, j;
00165 
00166         /* inputs */
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         /* dimensions */
00180         unsigned int nV=0, nC=0;
00181 
00182 
00183         /* I) CONSISTENCY CHECKS: */
00184         /* 1) Ensure that qpOASES is called with a feasible number of input arguments. */
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         /* 2) Ensure that first input is a string (and if so, read it). */
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         /* II) SELECT RESPECTIVE QPOASES FUNCTION CALL: */
00197         /* 1) Init (without or with initial guess for primal solution) OR
00198          * 2) Hotstart. */
00199         if ( ( strcmp( typeString,"i" ) == 0 ) || ( strcmp( typeString,"I" ) == 0 ) ||
00200                  ( strcmp( typeString,"h" ) == 0 ) || ( strcmp( typeString,"H" ) == 0 ) )
00201         {
00202                 /* consistency checks */
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                 /* ensure that data is given in real_t precision */
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                 /* ensure that matrices are stored in dense format */
00216 //              if ( ( mxIsSparse( prhs[1] ) != 0 ) || ( mxIsSparse( prhs[3] ) != 0 ) )
00217 //                      mexErrMsgTxt( "ERROR (qpOASES): Matrices must not be stored in sparse format!" );
00218 
00219 
00220                 /* Check inputs dimensions and assign pointers to inputs. */
00221                 nV = mxGetM( prhs[1] ); /* row number of Hessian matrix */
00222                 nC = mxGetM( prhs[3] ); /* row number of constraint matrix */
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                 /* default value for nWSR */
00243                 int nWSRin = 5*(nV+nC);
00244 
00245                 /* Check whether x0 and options are specified .*/
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 /* hotstart */
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                 /* check for sparsity */
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                         // mind pointer offsets due to 1-based indexing in Matlab
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                 /* Convert constraint matrix A from FORTRAN to C style
00292                  * (not necessary for H as it should be symmetric!). */
00293                 if ( nC > 0 )
00294                 {
00295                         /* Check for sparsity. */
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                                 // mind pointer offsets due to 1-based indexing in Matlab
00302                                 globalSQP_A = new SparseMatrix(nC, nV, ir, jc, v);
00303                         }
00304                         else
00305                         {
00306                                 /* Convert constraint matrix A from FORTRAN to C style
00307                                 * (not necessary for H as it should be symmetric!). */
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                 /* Create output vectors and assign pointers to them. */
00317                 allocateOutputs( nlhs,plhs, nV,nC );
00318 
00319                 /* Call qpOASES */
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 /* hotstart */
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                         /* QUICK HACK TO BE REMOVED! */
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         /* 3) Cleanup. */
00353         if ( ( strcmp( typeString,"c" ) == 0 ) || ( strcmp( typeString,"C" ) == 0 ) )
00354         {
00355                 /* consistency checks */
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                 /* Cleanup global SQProblem instance. */
00363                 deleteGlobalSQProblemInstance( );
00364                 deleteGlobalSQProblemMatrices( );
00365                 return;
00366         }
00367 }
00368 
00369 
00370 /*
00371  *      end of file
00372  */


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 11:59:50