cstr.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 
00035 #include <acado_integrators.hpp>
00036 #include <acado_gnuplot.hpp>
00037 
00038 
00039 const double k10 =  1.287e12;
00040 const double k20 =  1.287e12;
00041 const double k30 =  9.043e09;
00042 const double E1  =  -9758.3;
00043 const double E2  =  -9758.3;
00044 const double E3  =  -8560.0;
00045 const double H1  =      4.2;
00046 const double H2  =    -11.0;
00047 const double H3  =    -41.85;
00048 const double rho =      0.9342;
00049 const double Cp  =      3.01;
00050 const double kw  =   4032.0;
00051 const double AR  =      0.215;
00052 const double VR  =     10.0;
00053 const double mK  =      5.0;
00054 const double CPK =      2.0;
00055 
00056 const double cA0    =    5.1;
00057 const double theta0 =  104.9;
00058 
00059 const double FFs    =    14.19;  /* Feed Flow normed by VR: (dV/dt  / VR)*/
00060 const double QdotKs = -1113.50;
00061 
00062 const double cAs     =  2.1402105301746182e00;
00063 const double cBs     =  1.0903043613077321e00;
00064 const double thetas  =  1.1419108442079495e02;
00065 const double thetaKs =  1.1290659291045561e02;
00066 
00067 
00068 const double TIMEUNITS_PER_HOUR = 3600.0;
00069 
00070 
00071 const double R_OMEGA = 90.0;
00072 
00073 
00074 USING_NAMESPACE_ACADO
00075 
00076 
00077 IntermediateState cstrModel( const DifferentialState &x,
00078                              const Control           &u  ){
00079 
00080     IntermediateState rhs(4);
00081 
00082     IntermediateState cA     = x(0);
00083     IntermediateState cB     = x(1);
00084     IntermediateState theta  = x(2);
00085     IntermediateState thetaK = x(3);
00086 
00087     IntermediateState k1, k2, k3;
00088 
00089     k1 = k10*exp(E1/(273.15 +theta));
00090     k2 = k20*exp(E2/(273.15 +theta));
00091     k3 = k30*exp(E3/(273.15 +theta));
00092 
00093     rhs(0) = (1/TIMEUNITS_PER_HOUR)*(u(0)*(cA0-cA) - k1*cA - k3*cA*cA);
00094     rhs(1) = (1/TIMEUNITS_PER_HOUR)* (- u(0)*cB + k1*cA - k2*cB);
00095     rhs(2) = (1/TIMEUNITS_PER_HOUR)*(u(0)*(theta0-theta) - (1/(rho*Cp)) *(k1*cA*H1 + k2*cB*H2 + k3*cA*cA*H3)+(kw*AR/(rho*Cp*VR))*(thetaK -theta)); 
00096     rhs(3) = (1/TIMEUNITS_PER_HOUR)*((1/(mK*CPK))*(u(1) + kw*AR*(theta-thetaK)));
00097 
00098     return rhs;
00099 }
00100 
00101 
00102 
00103 int main( ){
00104 
00105 
00106     // Define a Right-Hand-Side:
00107     // -------------------------
00108     DifferentialState x("", 4, 1), P("", 4, 4);
00109     Control           u("", 2, 1);
00110 
00111     IntermediateState rhs = cstrModel( x, u );
00112 
00113     DMatrix Q = zeros<double>(4,4);
00114 
00115     Q(0,0) = 0.2;
00116     Q(1,1) = 1.0;
00117     Q(2,2) = 0.5;
00118     Q(3,3) = 0.2;
00119 
00120 
00121     DMatrix R = zeros<double>(2,2);
00122 
00123     R(0,0) = 0.5;
00124     R(1,1) = 5e-7;
00125 
00126     DifferentialEquation f;
00127     f << dot(x) == rhs;
00128     f << dot(P) == getRiccatiODE( rhs, x, u, P, Q, R );
00129 
00130 
00131 
00132     // Define an integrator:
00133     // ---------------------
00134 
00135     IntegratorRK45 integrator( f );
00136     integrator.set( INTEGRATOR_PRINTLEVEL, MEDIUM );
00137         integrator.set( PRINT_INTEGRATOR_PROFILE, YES );
00138         
00139     // Define an initial value:
00140     // ------------------------
00141     //double x_ss[4] = { 2.14, 1.09, 114.2, 112.9 };
00142         double x_start[20] = { 1.0, 0.5, 100.0, 100.0, 1.0, 0.0, 0.0, 0.0,
00143                                                    0.0, 1.0, 0.0, 0.0,
00144                                                    0.0, 0.0, 1.0, 0.0,
00145                                                    0.0, 0.0, 0.0, 1.0 };
00146 
00147         double u_start[2] = { 14.19, -1113.5 };
00148 //      double u_start[2] = { 10.00, -7000.0 };
00149 
00150         Grid timeInterval( 0.0, 5000.0, 100 );
00151 
00152     integrator.freezeAll();
00153     integrator.integrate( timeInterval, x_start, 0 ,0, u_start );
00154 
00155 
00156     // GET THE RESULTS
00157     // ---------------
00158 
00159     VariablesGrid differentialStates;
00160     integrator.getX( differentialStates );
00161 
00162         DVector PP = differentialStates.getLastVector();
00163         DMatrix PPP(4,4);
00164         for( int i=0; i<4; ++i )
00165                 for( int j=0; j<4; ++j )
00166                         PPP(i,j) = PP(4+i*4+j);
00167         PPP.print( "P1.txt","",PS_PLAIN );
00168 //      PPP.printToFile( "P2.txt","",PS_PLAIN );
00169 
00170     GnuplotWindow window;
00171         window.addSubplot( differentialStates(0), "cA [mol/l]" );
00172         window.addSubplot( differentialStates(1), "cB [mol/l]" );
00173         window.addSubplot( differentialStates(2), "theta [C]" );
00174         window.addSubplot( differentialStates(3), "thetaK [C]" );
00175 
00176         window.addSubplot( differentialStates(4 ), "P11" );
00177         window.addSubplot( differentialStates(9 ), "P22" );
00178         window.addSubplot( differentialStates(14), "P33" );
00179         window.addSubplot( differentialStates(19), "P44" );
00180                 
00181     window.plot();
00182 
00183     return 0;
00184 }
00185 
00186 
00187 


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