hydroscal.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 
00027 
00038 #include <acado_integrators.hpp>
00039 #include "hydroscal_model.hpp"
00040 #include <acado_gnuplot.hpp>
00041 
00042 
00043 void ffcn_model( double *x, double *f, void *user_data ){
00044 
00045     int i;
00046 
00047     double *xd = new double[NXD];
00048     double *xa = new double[NXA];
00049     double *u  = new double[ NU];
00050     double *p  = new double[ NP];
00051 
00052     for( i = 0; i < NXD; i++ ) xd[i] = x[         1+i ];
00053     for( i = 0; i < NXA; i++ ) xa[i] = x[     NXD+1+i ];
00054     for( i = 0; i <  NU; i++ )  u[i] = x[ NXA+NXD+1+i ];
00055 
00056     p[ 0] = 1.5458567140000001E-01;
00057     p[ 1] = 1.7499999999999999E-01;
00058     p[ 2] = 3.4717208398678062E-01;
00059     p[ 3] = 6.1895708603484367E-01;
00060     p[ 4] = 1.6593025789999999E-01;
00061     p[ 5] = 5.0695122527590109E-01;
00062     p[ 6] = 8.5000000000000000E+00;
00063     p[ 7] = 1.7000000000000001E-01;
00064     p[ 8] = 9.3885430857029321E+04;
00065     p[ 9] = 2.5000000000000000E+02;
00066     p[10] = 1.4026000000000000E+01;
00067     p[11] = 3.2000000000000001E-01;
00068     p[12] = 7.1054000000000002E+01;
00069     p[13] = 4.7163089489100003E+01;
00070     p[14] = 4.1833910753991770E+00;
00071     p[15] = 2.4899344810136301E+00;
00072     p[16] = 1.8760537088149468E+02;
00073 
00074     ffcn( &x[0], xd, xa, u, p, f );
00075     gfcn( &x[0], xd, xa, u, p, &(f[NXD]) );
00076 
00077     delete[] xd;
00078     delete[] xa;
00079     delete[]  u;
00080     delete[]  p;
00081 }
00082 
00083 
00084 
00085 
00086 int main( ){
00087 
00088     USING_NAMESPACE_ACADO
00089 
00090         const int  nx  =  82;  // the number of differential states
00091         const int  nxa = 122;  // the number of algebraic states
00092         const int  nu  =   2;  // the number of controls
00093         //const int  np  =   0;  // the number of parameters
00094         //const int  nw  =   0;  // the number of disturbances
00095 
00096     TIME t;
00097     DifferentialState x("", nx, 1);
00098     AlgebraicState z("", nxa, 1);
00099     Control u("", nu, 1);
00100 
00101 
00102     IntermediateState is(1+nx+nxa+nu);
00103     is(0) = t;
00104     for (int i=0; i < nx; ++i)  is(1+i)        = x(i);
00105     for (int i=0; i < nxa; ++i) is(1+nx+i)     = z(i);
00106     for (int i=0; i < nu; ++i)  is(1+nx+nxa+i) = u(i);
00107 
00108     CFunction hydroscalModel( nx+nxa, ffcn_model );
00109 
00110 
00111     // Define a Right-Hand-Side:
00112     // -------------------------
00113 
00114     DifferentialEquation f;
00115     f << hydroscalModel(is);
00116 
00117 
00118     // DEFINE AN INTEGRATOR:
00119     // ---------------------
00120     IntegratorBDF integrator( f );
00121 
00122 
00123     // DEFINE INITIAL VALUES:
00124     // ----------------------
00125 
00126     double xd_init[NXD] = { 2.1936116177990631E-01,
00127                        3.3363028623863722E-01,
00128                        3.7313133250625952E-01,
00129                        3.9896472354654333E-01,
00130                        4.1533719381260475E-01,
00131                        4.2548399372287182E-01,
00132                        4.3168379354213621E-01,
00133                        4.3543569751236455E-01,
00134                        4.3768918647214428E-01,
00135                        4.3903262905928286E-01,
00136                        4.3982597315656735E-01,
00137                        4.4028774979047969E-01,
00138                        4.4055002518902953E-01,
00139                        4.4069238917008052E-01,
00140                        4.4076272408112094E-01,
00141                        4.4078980543461005E-01,
00142                        4.4079091412311144E-01,
00143                        4.4077642312834125E-01,
00144                        4.4075255679998443E-01,
00145                        4.4072304911231042E-01,
00146                        4.4069013958173919E-01,
00147                        6.7041926189645151E-01,
00148                        7.3517997375758948E-01,
00149                        7.8975978943631409E-01,
00150                        8.3481725159539033E-01,
00151                        8.7125377077380739E-01,
00152                        9.0027275078767721E-01,
00153                        9.2312464536394301E-01,
00154                        9.4096954980798608E-01,
00155                        9.5481731262797742E-01,
00156                        9.6551271145368878E-01,
00157                        9.7374401773010488E-01,
00158                        9.8006186072166701E-01,
00159                        9.8490109485675337E-01,
00160                        9.8860194771099286E-01,
00161                        9.9142879342008328E-01,
00162                        9.9358602331847468E-01,
00163                        9.9523105632238640E-01,
00164                        9.9648478785701988E-01,
00165                        9.9743986301741971E-01,
00166                        9.9816716097314861E-01,
00167                        9.9872084014280071E-01,
00168                        3.8633811956730968E+00,
00169                        3.9322260498028840E+00,
00170                        3.9771965626392531E+00,
00171                        4.0063070333869728E+00,
00172                        4.0246026844143410E+00,
00173                        4.0358888958821835E+00,
00174                        4.0427690398786789E+00,
00175                        4.0469300433477020E+00,
00176                        4.0494314648020326E+00,
00177                        4.0509267560029381E+00,
00178                        4.0518145583397631E+00,
00179                        4.0523364846379799E+00,
00180                        4.0526383977460299E+00,
00181                        4.0528081437632766E+00,
00182                        4.0528985491134542E+00,
00183                        4.0529413510270169E+00,
00184                        4.0529556049324462E+00,
00185                        4.0529527471448805E+00,
00186                        4.0529396392278008E+00,
00187                        4.0529203970496912E+00,
00188                        3.6071164950918582E+00,
00189                        3.7583754503438387E+00,
00190                        3.8917148481441974E+00,
00191                        4.0094300698741563E+00,
00192                        4.1102216725798293E+00,
00193                        4.1944038520620675E+00,
00194                        4.2633275166560596E+00,
00195                        4.3188755452109175E+00,
00196                        4.3630947909857642E+00,
00197                        4.3979622247841386E+00,
00198                        4.4252580012497740E+00,
00199                        4.4465128947193868E+00,
00200                        4.4630018314791968E+00,
00201                        4.4757626150015568E+00,
00202                        4.4856260094946823E+00,
00203                        4.4932488551808500E+00,
00204                        4.4991456959629330E+00,
00205                        4.5037168116896273E+00,
00206                        4.5072719605639726E+00,
00207                        4.5100498969782414E+00  };
00208 
00209 
00210     double xa_init[NXA] = { 8.7651079143636981E+00,
00211                        8.7871063316432316E+00,
00212                        8.7893074703670067E+00,
00213                        8.7901954544445342E+00,
00214                        8.7901233416606477E+00,
00215                        8.7894020661781447E+00,
00216                        8.7882641216255362E+00,
00217                        8.7868655382627203E+00,
00218                        8.7853059232818165E+00,
00219                        8.7836472367940104E+00,
00220                        8.7819274715696096E+00,
00221                        8.7801697317787344E+00,
00222                        8.7783879979338462E+00,
00223                        8.7765907033291164E+00,
00224                        8.7747829241037341E+00,
00225                        8.7729677102977046E+00,
00226                        8.7711468912374286E+00,
00227                        8.7693215615475513E+00,
00228                        8.7674923739534876E+00,
00229                        8.7656597155017142E+00,
00230                        2.7825469403413372E+00,
00231                        2.8224111125799740E+00,
00232                        2.8351257821612172E+00,
00233                        2.8455862495713884E+00,
00234                        2.8539999172723634E+00,
00235                        2.8606290594307993E+00,
00236                        2.8657653801220269E+00,
00237                        2.8696861889639877E+00,
00238                        2.8726352758900391E+00,
00239                        2.8748174364382795E+00,
00240                        2.8763998227654772E+00,
00241                        2.8775162576841131E+00,
00242                        2.8782724559458406E+00,
00243                        2.8787511355838511E+00,
00244                        2.8790165741126224E+00,
00245                        2.8791184656798956E+00,
00246                        2.8790950843473126E+00,
00247                        2.8789758246804231E+00,
00248                        2.8787832131565576E+00,
00249                        2.8785344845386325E+00,
00250                        3.7489688386445703E+00,
00251                        3.7511699771858589E+00,
00252                        3.7520579611269311E+00,
00253                        3.7519858482265618E+00,
00254                        3.7512645726312401E+00,
00255                        3.7501266279652898E+00,
00256                        3.7487280444903774E+00,
00257                        3.7471684294005221E+00,
00258                        3.7455097428065072E+00,
00259                        3.7437899774766037E+00,
00260                        3.7420322375793442E+00,
00261                        3.7402505036278120E+00,
00262                        3.7384532089192324E+00,
00263                        3.7366454295969547E+00,
00264                        3.7348302157041928E+00,
00265                        3.7330093965681632E+00,
00266                        3.7311840668122449E+00,
00267                        3.7293548791598456E+00,
00268                        3.7275222206556560E+00,
00269                        3.5295879437000068E+00,
00270                        3.5694521158072119E+00,
00271                        3.5821667852381145E+00,
00272                        3.5926272524800611E+00,
00273                        3.6010409200004330E+00,
00274                        3.6076700619776987E+00,
00275                        3.6128063825021988E+00,
00276                        3.6167271912042991E+00,
00277                        3.6196762780219980E+00,
00278                        3.6218584384893231E+00,
00279                        3.6234408247540211E+00,
00280                        3.6245572596202216E+00,
00281                        3.6253134578357198E+00,
00282                        3.6257921374340887E+00,
00283                        3.6260575759313443E+00,
00284                        3.6261594674751652E+00,
00285                        3.6261360861254119E+00,
00286                        3.6260168264456856E+00,
00287                        3.6258242149122157E+00,
00288                        3.6255754862872984E+00,
00289                        3.5278596344996789E+00,
00290                        8.7075189603180618E+01,
00291                        8.2548857813137090E+01,
00292                        8.1085116711116342E+01,
00293                        8.0140698658642663E+01,
00294                        7.9532219332963521E+01,
00295                        7.9135751980236464E+01,
00296                        7.8870294691608407E+01,
00297                        7.8684803169784061E+01,
00298                        7.8547757165561293E+01,
00299                        7.8439916843235665E+01,
00300                        7.8349617512390665E+01,
00301                        7.8269815515229979E+01,
00302                        7.8196267858564511E+01,
00303                        7.8126422374424024E+01,
00304                        7.8058745287858954E+01,
00305                        7.7992315317564561E+01,
00306                        7.7926579216690257E+01,
00307                        7.7861204749145912E+01,
00308                        7.7795992344269862E+01,
00309                        7.7730822041668659E+01,
00310                        7.7665621642015878E+01,
00311                        7.1094961608415730E+01,
00312                        6.9448805116206330E+01,
00313                        6.8122261394548488E+01,
00314                        6.7060799125769435E+01,
00315                        6.6217795308026254E+01,
00316                        6.5550027436041674E+01,
00317                        6.5020432750221772E+01,
00318                        6.4598581400619508E+01,
00319                        6.4260125467265169E+01,
00320                        6.3985893352644759E+01,
00321                        6.3760944540013256E+01,
00322                        6.3573715428857163E+01,
00323                        6.3415297789173543E+01,
00324                        6.3278851294230762E+01,
00325                        6.3159135609293749E+01,
00326                        6.3052142835899517E+01,
00327                        6.2954811408060124E+01,
00328                        6.2864804764641939E+01,
00329                        6.2780340868928761E+01,
00330                        6.2700061296306565E+01,
00331                        6.2622930929692828E+01  };
00332 
00333     double u_init[ NU] = { 4.1833910982822058E+00, 2.4899344742988991E+00 };
00334 
00335     double t_start    =    0.0;
00336     double t_end      =  120.0;
00337 
00338 
00339     // START THE INTEGRATION:
00340     // ----------------------
00341 
00342     integrator.set( INTEGRATOR_PRINTLEVEL, MEDIUM );
00343     integrator.set( INTEGRATOR_TOLERANCE, 1e-6 );
00344     integrator.set( ABSOLUTE_TOLERANCE  , 1e-2 );
00345         integrator.set( PRINT_INTEGRATOR_PROFILE, YES );
00346     //integrator.set( LINEAR_ALGEBRA_SOLVER, SPARSE_LU );
00347 
00348     Grid tt( t_start, t_end, 100 );
00349 
00350     integrator.integrate( tt, xd_init, xa_init, 0, u_init );
00351 
00352     integrator.printRunTimeProfile();
00353 
00354 
00355     // GET THE RESULTS
00356     // ---------------
00357 
00358     VariablesGrid differentialStates;
00359     VariablesGrid algebraicStates   ;
00360     VariablesGrid intermediateStates;
00361 
00362     integrator.getX ( differentialStates );
00363     integrator.getXA( algebraicStates    );
00364     integrator.getI ( intermediateStates );
00365 
00366     GnuplotWindow window;
00367         window.addSubplot( differentialStates(0) );
00368         window.addSubplot( algebraicStates   (0) );
00369 
00370     window.plot();
00371 
00372 
00373     return 0;
00374 }
00375 
00376 
00377 


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