lsq_term.cpp
Go to the documentation of this file.
00001 /*
00002  *    This file is part of ACADO Toolkit.
00003  *
00004  *    ACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.
00005  *    Copyright (C) 2008-2014 by Boris Houska, Hans Joachim Ferreau,
00006  *    Milan Vukov, Rien Quirynen, KU Leuven.
00007  *    Developed within the Optimization in Engineering Center (OPTEC)
00008  *    under supervision of Moritz Diehl. All rights reserved.
00009  *
00010  *    ACADO Toolkit is free software; you can redistribute it and/or
00011  *    modify it under the terms of the GNU Lesser General Public
00012  *    License as published by the Free Software Foundation; either
00013  *    version 3 of the License, or (at your option) any later version.
00014  *
00015  *    ACADO Toolkit is distributed in the hope that it will be useful,
00016  *    but WITHOUT ANY WARRANTY; without even the implied warranty of
00017  *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00018  *    Lesser General Public License for more details.
00019  *
00020  *    You should have received a copy of the GNU Lesser General Public
00021  *    License along with ACADO Toolkit; if not, write to the Free Software
00022  *    Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
00023  *
00024  */
00025 
00026 
00033 #include <acado/objective/lsq_term.hpp>
00034 #include <acado/curve/curve.hpp>
00035 
00036 // #define SIM_DEBUG
00037 
00038 
00039 BEGIN_NAMESPACE_ACADO
00040 
00041 //
00042 // PUBLIC MEMBER FUNCTIONS:
00043 //
00044 
00045 
00046 LSQTerm::LSQTerm( )
00047         :ObjectiveElement(){
00048 
00049     S       = 0;
00050     r       = 0;
00051 
00052     S_temp  = 0;
00053     r_temp  = 0;
00054 
00055     S_h_res = 0;
00056 }
00057 
00058 
00059 LSQTerm::LSQTerm( const MatrixVariablesGrid *S_,
00060                   const Function&            h ,
00061                   const VariablesGrid       *r_  )
00062         :ObjectiveElement(){
00063 
00064     S       = 0;
00065     r       = 0;
00066     S_h_res = 0;
00067     fcn     = h;
00068 
00069     if( S_ != 0 ) S_temp = new MatrixVariablesGrid(*S_);
00070     else          S_temp = 0                           ;
00071 
00072     if( r_ != 0 ) r_temp = new VariablesGrid(*r_);
00073     else          r_temp = 0                     ;
00074 }
00075 
00076 
00077 LSQTerm::LSQTerm( const LSQTerm& rhs )
00078         :ObjectiveElement( rhs ){
00079 
00080     uint run1, run2;
00081 
00082     if( rhs.S_temp != 0 ) S_temp = new MatrixVariablesGrid(*rhs.S_temp);
00083     else                  S_temp = 0;
00084 
00085     if( rhs.r_temp != 0 ) r_temp = new VariablesGrid(*rhs.r_temp);
00086     else                  r_temp = 0;
00087 
00088 
00089     if( rhs.S != NULL ){
00090         S = new DMatrix[grid.getNumPoints()];
00091         for( run1 = 0; run1 < grid.getNumPoints(); run1++ )
00092             S[run1] = rhs.S[run1];
00093     }
00094     else S = NULL;
00095 
00096     if( rhs.r != NULL ){
00097         r = new DVector[grid.getNumPoints()];
00098         for( run1 = 0; run1 < grid.getNumPoints(); run1++ )
00099             r[run1] = rhs.r[run1];
00100     }
00101     else r = NULL;
00102 
00103     if( rhs.S_h_res != 0 ){
00104         S_h_res = new double*[grid.getNumPoints()];
00105         for( run1 = 0; run1 < grid.getNumPoints(); run1++ ){
00106             S_h_res[run1] = new double[fcn.getDim()];
00107             for( run2 = 0; (int) run2 < fcn.getDim(); run2++ ){
00108                 S_h_res[run1][run2] = rhs.S_h_res[run1][run2];
00109             }
00110         }
00111     }
00112 }
00113 
00114 
00115 LSQTerm::~LSQTerm( ){
00116 
00117     uint run1;
00118 
00119     if( S_temp != 0 )
00120         delete S_temp;
00121 
00122     if( r_temp != 0 )
00123         delete r_temp;
00124 
00125     if( S != 0 )
00126         delete[] S;
00127 
00128     if( r != 0 )
00129         delete[] r;
00130 
00131     if( S_h_res != 0 ){
00132         for( run1 = 0; run1 < grid.getNumPoints(); run1++ )
00133             delete[] S_h_res[run1];
00134         delete[] S_h_res;
00135     }
00136 }
00137 
00138 
00139 LSQTerm& LSQTerm::operator=( const LSQTerm& rhs ){
00140 
00141     uint run1, run2;
00142 
00143     if ( this != &rhs ){
00144 
00145 
00146         if( S_temp != 0 )
00147             delete S_temp;
00148 
00149         if( r_temp != 0 )
00150            delete[] r_temp;
00151 
00152         if( S!= NULL )
00153             delete[] S;
00154 
00155         if( r!= NULL )
00156             delete[] r;
00157 
00158         if( S_h_res != 0 ){
00159             for( run1 = 0; run1 < grid.getNumPoints(); run1++ )
00160                 delete[] S_h_res[run1];
00161             delete[] S_h_res;
00162         }
00163 
00164         ObjectiveElement::operator=(rhs);
00165 
00166         if( rhs.S_temp != 0 ) S_temp = new MatrixVariablesGrid(*rhs.S_temp);
00167         else                  S_temp = 0;
00168 
00169         if( rhs.r_temp != 0 ) r_temp = new VariablesGrid(*rhs.r_temp);
00170         else                  r_temp = 0;
00171 
00172         if( rhs.S != NULL ){
00173             S = new DMatrix[grid.getNumPoints()];
00174             for( run1 = 0; run1 < grid.getNumPoints(); run1++ )
00175                 S[run1] = rhs.S[run1];
00176         }
00177         else S = NULL;
00178 
00179         if( rhs.r != NULL ){
00180             r = new DVector[grid.getNumPoints()];
00181             for( run1 = 0; run1 < grid.getNumPoints(); run1++ )
00182                 r[run1] = rhs.r[run1];
00183         }
00184         else r = NULL;
00185 
00186         if( rhs.S_h_res != 0 ){
00187             S_h_res = new double*[grid.getNumPoints()];
00188             for( run1 = 0; run1 < grid.getNumPoints(); run1++ ){
00189                 S_h_res[run1] = new double[fcn.getDim()];
00190                 for( run2 = 0; (int) run2 < fcn.getDim(); run2++ ){
00191                     S_h_res[run1][run2] = rhs.S_h_res[run1][run2];
00192                 }
00193             }
00194         }
00195     }
00196     return *this;
00197 }
00198 
00199 
00200 
00201 returnValue LSQTerm::evaluate( const OCPiterate &x ){
00202 
00203     uint run1, run2, run3;
00204 
00205     DVector h_res;
00206 
00207     const uint nh = fcn.getDim();
00208     const uint N  = grid.getNumPoints();
00209 
00210     ObjectiveElement::init( x );
00211 
00212     obj = 0.0;
00213 
00214         double currentValue;
00215         VariablesGrid allValues( 1,grid );
00216 
00217     for( run1 = 0; run1 < N; run1++ ){
00218 
00219                 currentValue = 0.0;
00220 
00221         // EVALUATE THE LSQ-FUCNTION:
00222         // --------------------------
00223         z.setZ( run1, x );
00224         h_res = fcn.evaluate( z, (int) run1 );
00225 
00226         
00227         #ifdef SIM_DEBUG
00228         if( run1 == 0 || run1 == 1 ){
00229           
00230             h_res.print("hres"); 
00231             r[run1].print("reference");
00232           
00233         }
00234         #endif
00235         
00236         
00237 
00238         // EVALUATE THE OBJECTIVE:
00239         // -----------------------
00240 
00241         if( r != NULL )
00242             h_res -= r[run1];
00243 
00244         if( S != NULL ){
00245 
00246                 if ( !(S[run1].getNumCols() == nh && S[run1].getNumRows() == nh) )
00247                         return ACADOERRORTEXT(RET_ASSERTION,
00248                                         The weighting matrix in the LSQ objective has a wrong dimension.);
00249 
00250             for( run2 = 0; run2 < nh; run2++ ){
00251                 S_h_res[run1][run2] = 0.0;
00252                 for( run3 = 0; run3 < nh; run3++ )
00253                     S_h_res[run1][run2] += S[run1].operator()(run2,run3)*h_res(run3);
00254             }
00255 
00256             for( run2 = 0; run2 < nh; run2++ ){
00257                  currentValue += 0.5*h_res(run2)*S_h_res[run1][run2];
00258             }
00259         }
00260         else{
00261             for( run2 = 0; run2 < nh; run2++ ){
00262                 S_h_res[run1][run2] = h_res(run2);
00263                 currentValue += 0.5*h_res(run2)*h_res(run2);
00264             }
00265         }
00266 
00267                 allValues( run1,0 ) = currentValue;
00268     }
00269 
00270         DVector tmp(1);
00271         allValues.getIntegral( IM_CONSTANT,tmp );
00272         obj = tmp(0);
00273 
00274     return SUCCESSFUL_RETURN;
00275 }
00276 
00277 
00278 
00279 returnValue LSQTerm::evaluateSensitivities( BlockMatrix *hessian ){
00280 
00281     if( hessian == 0 ) return evaluateSensitivitiesGN(0);
00282 
00283     int run1, run2, run3, run4;
00284     const int N = grid.getNumPoints();
00285     const int nh = fcn.getDim();
00286 
00287     if( bSeed != 0 ){
00288 
00289         if( xSeed  != 0 || pSeed  != 0 || uSeed  != 0 || wSeed  != 0 ||
00290             xSeed2 != 0 || pSeed2 != 0 || uSeed2 != 0 || wSeed2 != 0 )
00291             return ACADOERROR( RET_WRONG_DEFINITION_OF_SEEDS );
00292 
00293         double *bseed   = new double [nh];
00294         double **J      = new double*[nh];
00295 
00296         for( run2 = 0; run2 < nh; run2++ )
00297              J[run2] = new double[fcn.getNumberOfVariables() +1];
00298 
00299         if( bSeed->getNumRows( 0, 0 ) != 1 ) return ACADOWARNING( RET_WRONG_DEFINITION_OF_SEEDS );
00300 
00301         DMatrix bseed_;
00302         bSeed->getSubBlock( 0, 0, bseed_);
00303 
00304         dBackward.init( 1, 5*N );
00305 
00306         DMatrix Dx ( 1, nx );
00307         DMatrix Dxa( 1, na );
00308         DMatrix Dp ( 1, np );
00309         DMatrix Du ( 1, nu );
00310         DMatrix Dw ( 1, nw );
00311 
00312         for( run1 = 0; run1 < N; run1++ ){
00313 
00314             Dx .setZero();
00315             Dxa.setZero();
00316             Dp .setZero();
00317             Du .setZero();
00318             Dw .setZero();
00319 
00320             for( run2 = 0; run2 < nh; run2++ ) bseed[run2] = 0;
00321 
00322             for( run2 = 0; run2 < nh; run2++ ){
00323                  for(run3 = 0; (int) run3 < fcn.getNumberOfVariables() +1; run3++ )
00324                      J[run2][run3] = 0.0;
00325 
00326                  bseed[run2] = 1.0;
00327                  fcn.AD_backward( run1, bseed, J[run2] );
00328                  bseed[run2] = 0.0;
00329 
00330                  for( run3 = 0; run3 < nx; run3++ ){
00331                       Dx( 0, run3 ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00332                  }
00333                  for( run3 = nx; run3 < nx+na; run3++ ){
00334                       Dxa( 0, run3-nx ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00335                  }
00336                  for( run3 = nx+na; run3 < nx+na+np; run3++ ){
00337                       Dp( 0, run3-nx-na ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00338                  }
00339                  for( run3 = nx+na+np; run3 < nx+na+np+nu; run3++ ){
00340                       Du( 0, run3-nx-na-np ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00341                  }
00342                  for( run3 = nx+na+np+nu; run3 < nx+na+np+nu+nw; run3++ ){
00343                       Dw( 0, run3-nx-na-np-nu ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00344                  }
00345             }
00346             if( nx > 0 ) dBackward.setDense( 0,     run1, Dx  );
00347             if( na > 0 ) dBackward.setDense( 0,   N+run1, Dxa );
00348             if( np > 0 ) dBackward.setDense( 0, 2*N+run1, Dp  );
00349             if( nu > 0 ) dBackward.setDense( 0, 3*N+run1, Du  );
00350             if( nw > 0 ) dBackward.setDense( 0, 4*N+run1, Dw  );
00351 
00352 
00353             // COMPUTATION OF THE EXACT HESSIAN:
00354             // ---------------------------------
00355 
00356             const int nnn = nx+na+np+nu+nw;
00357             DMatrix tmp( nh, nnn );
00358 
00359             for( run3 = 0; run3 < nnn; run3++ ){
00360                 for( run2 = 0; run2 < nh; run2++ ){
00361                     if( S != 0 ){
00362                         tmp( run2, run3 ) = 0.0;
00363                         for( run4 = 0; run4 < nh; run4++ ){
00364                             tmp( run2, run3 ) += S[run1].operator()(run2,run4)*J[run4][y_index[run3]];
00365                         }
00366                     }
00367                     else{
00368                         tmp( run2, run3 ) = J[run2][y_index[run3]];
00369                     }
00370                 }
00371             }
00372             DMatrix tmp2;
00373             int i,j;
00374             int *Sidx = new int[6];
00375             int *Hidx = new int[5];
00376 
00377             Sidx[0] = 0;
00378             Sidx[1] = nx;
00379             Sidx[2] = nx+na;
00380             Sidx[3] = nx+na+np;
00381             Sidx[4] = nx+na+np+nu;
00382             Sidx[5] = nx+na+np+nu+nw;
00383 
00384             Hidx[0] =     run1;
00385             Hidx[1] =   N+run1;
00386             Hidx[2] = 2*N+run1;
00387             Hidx[3] = 3*N+run1;
00388             Hidx[4] = 4*N+run1;
00389 
00390             for( i = 0; i < 5; i++ ){
00391                 for( j = 0; j < 5; j++ ){
00392 
00393                     tmp2.init(Sidx[i+1]-Sidx[i],Sidx[j+1]-Sidx[j]);
00394                     tmp2.setZero();
00395 
00396                     for( run3 = Sidx[i]; run3 < Sidx[i+1]; run3++ )
00397                         for( run4 = Sidx[j]; run4 < Sidx[j+1]; run4++ )
00398                             for( run2 = 0; run2 < nh; run2++ )
00399                                 tmp2(run3-Sidx[i],run4-Sidx[j]) += J[run2][y_index[run3]]*tmp(run2,run4);
00400 
00401                     if( tmp2.getDim() != 0 ) hessian->addDense(Hidx[i],Hidx[j],tmp2);
00402                 }
00403             }
00404             delete[] Sidx;
00405             delete[] Hidx;
00406         }
00407 
00408         for( run2 = 0; run2 < nh; run2++ )
00409             delete[] J[run2];
00410         delete[] J;
00411         delete[] bseed;
00412         return SUCCESSFUL_RETURN;
00413     }
00414     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00415 }
00416 
00417 
00418 returnValue LSQTerm::evaluateSensitivitiesGN( BlockMatrix *GNhessian ){
00419 
00420     int run1, run2, run3, run4;
00421     const int N = grid.getNumPoints();
00422     const int nh = fcn.getDim();
00423 
00424     if( bSeed != 0 ){
00425 
00426         if( xSeed  != 0 || pSeed  != 0 || uSeed  != 0 || wSeed  != 0 ||
00427             xSeed2 != 0 || pSeed2 != 0 || uSeed2 != 0 || wSeed2 != 0 )
00428             return ACADOERROR( RET_WRONG_DEFINITION_OF_SEEDS );
00429 
00430         double *bseed   = new double [nh];
00431         double **J      = new double*[nh];
00432 
00433         for( run2 = 0; run2 < nh; run2++ )
00434              J[run2] = new double[fcn.getNumberOfVariables() +1];
00435 
00436         if( bSeed->getNumRows( 0, 0 ) != 1 ) return ACADOWARNING( RET_WRONG_DEFINITION_OF_SEEDS );
00437 
00438         DMatrix bseed_;
00439         bSeed->getSubBlock( 0, 0, bseed_);
00440 
00441         dBackward.init( 1, 5*N );
00442 
00443         DMatrix Dx ( 1, nx );
00444         DMatrix Dxa( 1, na );
00445         DMatrix Dp ( 1, np );
00446         DMatrix Du ( 1, nu );
00447         DMatrix Dw ( 1, nw );
00448 
00449         for( run1 = 0; run1 < N; run1++ ){
00450 
00451             Dx .setZero();
00452             Dxa.setZero();
00453             Dp .setZero();
00454             Du .setZero();
00455             Dw .setZero();
00456 
00457             for( run2 = 0; run2 < nh; run2++ ) bseed[run2] = 0;
00458 
00459             if( fcn.ADisSupported() == BT_FALSE ){
00460 
00461                 double *fseed = new double[fcn.getNumberOfVariables()+1];
00462                 for( run3 = 0; (int) run3 < fcn.getNumberOfVariables()+1; run3++ )
00463                      fseed[run3] = 0.0;
00464 
00465                 for( run3 = 0; (int) run3 < fcn.getNumberOfVariables()+1; run3++ ){
00466                      fseed[run3] = 1.0;
00467                      fcn.AD_forward( run1, fseed, bseed );
00468                      fseed[run3] = 0.0;
00469                      for( run2 = 0; run2 < nh; run2++ )
00470                          J[run2][run3] = bseed[run2];
00471                 }
00472                 delete[] fseed;
00473             }
00474 
00475             for( run2 = 0; run2 < nh; run2++ ){
00476 
00477                  if( fcn.ADisSupported() == BT_TRUE ){
00478                      for(run3 = 0; (int) run3 < fcn.getNumberOfVariables() +1; run3++ )
00479                          J[run2][run3] = 0.0;
00480                      bseed[run2] = 1.0;
00481                      fcn.AD_backward( run1, bseed, J[run2] );
00482                      bseed[run2] = 0.0;
00483                  }
00484 
00485                  for( run3 = 0; run3 < nx; run3++ ){
00486                       Dx( 0, run3 ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00487                  }
00488                  for( run3 = nx; run3 < nx+na; run3++ ){
00489                       Dxa( 0, run3-nx ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00490                  }
00491                  for( run3 = nx+na; run3 < nx+na+np; run3++ ){
00492                       Dp( 0, run3-nx-na ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00493                  }
00494                  for( run3 = nx+na+np; run3 < nx+na+np+nu; run3++ ){
00495                       Du( 0, run3-nx-na-np ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00496                  }
00497                  for( run3 = nx+na+np+nu; run3 < nx+na+np+nu+nw; run3++ ){
00498                       Dw( 0, run3-nx-na-np-nu ) += bseed_(0,0)*J[run2][y_index[run3]]*S_h_res[run1][run2];
00499                  }
00500             }
00501             if( nx > 0 ) dBackward.setDense( 0,     run1, Dx  );
00502             if( na > 0 ) dBackward.setDense( 0,   N+run1, Dxa );
00503             if( np > 0 ) dBackward.setDense( 0, 2*N+run1, Dp  );
00504             if( nu > 0 ) dBackward.setDense( 0, 3*N+run1, Du  );
00505             if( nw > 0 ) dBackward.setDense( 0, 4*N+run1, Dw  );
00506 
00507             // COMPUTE GAUSS-NEWTON HESSIAN APPROXIMATION IF REQUESTED:
00508             // --------------------------------------------------------
00509 
00510             if( GNhessian != 0 ){
00511 
00512                 const int nnn = nx+na+np+nu+nw;
00513                 DMatrix tmp( nh, nnn );
00514 
00515                 for( run3 = 0; run3 < nnn; run3++ ){
00516                     for( run2 = 0; run2 < nh; run2++ ){
00517                         if( S != 0 ){
00518                             tmp( run2, run3 ) = 0.0;
00519                             for( run4 = 0; run4 < nh; run4++ ){
00520                                 tmp( run2, run3 ) += S[run1].operator()(run2,run4)*J[run4][y_index[run3]];
00521                             }
00522                         }
00523                         else{
00524                             tmp( run2, run3 ) = J[run2][y_index[run3]];
00525                         }
00526                     }
00527                 }
00528                 DMatrix tmp2;
00529                 int i,j;
00530                 int *Sidx = new int[6];
00531                 int *Hidx = new int[5];
00532 
00533                 Sidx[0] = 0;
00534                 Sidx[1] = nx;
00535                 Sidx[2] = nx+na;
00536                 Sidx[3] = nx+na+np;
00537                 Sidx[4] = nx+na+np+nu;
00538                 Sidx[5] = nx+na+np+nu+nw;
00539 
00540                 Hidx[0] =     run1;
00541                 Hidx[1] =   N+run1;
00542                 Hidx[2] = 2*N+run1;
00543                 Hidx[3] = 3*N+run1;
00544                 Hidx[4] = 4*N+run1;
00545 
00546                 for( i = 0; i < 5; i++ ){
00547                     for( j = 0; j < 5; j++ ){
00548 
00549                         tmp2.init(Sidx[i+1]-Sidx[i],Sidx[j+1]-Sidx[j]);
00550                         tmp2.setZero();
00551 
00552                         for( run3 = Sidx[i]; run3 < Sidx[i+1]; run3++ )
00553                             for( run4 = Sidx[j]; run4 < Sidx[j+1]; run4++ )
00554                                 for( run2 = 0; run2 < nh; run2++ )
00555                                     tmp2(run3-Sidx[i],run4-Sidx[j]) += J[run2][y_index[run3]]*tmp(run2,run4);
00556 
00557                         if( tmp2.getDim() != 0 ) GNhessian->addDense(Hidx[i],Hidx[j],tmp2);
00558                     }
00559                 }
00560                 delete[] Sidx;
00561                 delete[] Hidx;
00562             }
00563         }
00564 
00565         for( run2 = 0; run2 < nh; run2++ )
00566             delete[] J[run2];
00567         delete[] J;
00568         delete[] bseed;
00569         return SUCCESSFUL_RETURN;
00570     }
00571 
00572     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00573 }
00574 
00575 returnValue LSQTerm::getWeigthingtMatrix(const unsigned _index, DMatrix& _matrix) const
00576 {
00577         if ( S_temp )
00578         {
00579                 _matrix= S_temp->getMatrix( _index );
00580 
00581                 return SUCCESSFUL_RETURN;
00582         }
00583 
00584         return RET_INITIALIZE_FIRST;
00585 }
00586 
00587 returnValue LSQTerm::setReference( const VariablesGrid &ref ){
00588     uint run1;
00589     const uint N  = grid.getNumPoints();
00590     //ASSERT( N == ref.getNumPoints() );
00591 //      printf("setReference!!!!\n");
00592     if( r == 0 ) r = new DVector[N];
00593     if ( N == ref.getNumPoints() ) {
00594       for( run1 = 0; run1 < N; run1++ )
00595           r[run1] = ref.getVector(run1);
00596 //        r[run1].print( "ref[run1]" );
00597     } else {
00598       Curve tmp;tmp.add(ref);
00599       for( run1 = 0; run1 < N; run1++ ) {
00600           tmp.evaluate(grid.getTime(run1)+ref.getFirstTime(), r[run1]);
00601 //        printf( "time = %e\n", grid.getTime(run1)+ref.getFirstTime() );
00602 //        r[run1].print( "ref[run1]" );
00603       }
00604     }
00605     return SUCCESSFUL_RETURN;
00606 }
00607 
00608 
00609 CLOSE_NAMESPACE_ACADO
00610 
00611 // end of file.


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