cstr22.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 
00033 #include <acado_code_generation.hpp>
00034 
00035 const double k10 =  1.287e12;
00036 const double k20 =  1.287e12;
00037 const double k30 =  9.043e09;
00038 const double E1  =  -9758.3;
00039 const double E2  =  -9758.3;
00040 const double E3  =  -8560.0;
00041 const double H1  =      4.2;
00042 const double H2  =    -11.0;
00043 const double H3  =    -41.85;
00044 const double rho =      0.9342;
00045 const double Cp  =      3.01;
00046 const double kw  =   4032.0;
00047 const double AR  =      0.215;
00048 const double VR  =     10.0;
00049 const double mK  =      5.0;
00050 const double CPK =      2.0;
00051 
00052 const double cA0    =    5.1;
00053 const double theta0 =  104.9;
00054 
00055 const double FFs    =    14.19;  /* Feed Flow normed by VR: (dV/dt  / VR)*/
00056 const double QdotKs = -1113.50;
00057 
00058 const double cAs     =  2.1402105301746182e00;
00059 const double cBs     =  1.0903043613077321e00;
00060 const double thetas  =  1.1419108442079495e02;
00061 const double thetaKs =  1.1290659291045561e02;
00062 
00063 
00064 const double TIMEUNITS_PER_HOUR = 3600.0;
00065 
00066 
00067 const double P11 =   3278.78;   
00068 const double P21 =   1677.31;
00069 const double P31 =   681.02;
00070 const double P41 =   271.50;
00071 
00072 const double P12 =   1677.31;
00073 const double P22 =   919.78;
00074 const double P32 =   344.19;
00075 const double P42 =   137.27;
00076 
00077 const double P13 =   681.02;
00078 const double P23 =   344.19;
00079 const double P33 =   172.45;
00080 const double P43 =   65.53;
00081 
00082 const double P14 =   271.50;
00083 const double P24 =   137.27;
00084 const double P34 =   65.53;
00085 const double P44 =   29.28;
00086 
00087 
00088 const double R_OMEGA = 90.0;
00089 
00090 
00091 int main()
00092 {
00093         USING_NAMESPACE_ACADO
00094 
00095         // Define a Right-Hand-Side:
00096         DifferentialState cA, cB, theta, thetaK;
00097         Control           u("", 2, 1);
00098 
00099         DifferentialEquation f;
00100 
00101         IntermediateState k1, k2, k3;
00102 
00103         k1 = k10*exp(E1/(273.15 +theta));
00104         k2 = k20*exp(E2/(273.15 +theta));
00105         k3 = k30*exp(E3/(273.15 +theta));
00106 
00107         f << dot(cA) == (1/TIMEUNITS_PER_HOUR)*(u(0)*(cA0-cA) - k1*cA - k3*cA*cA);
00108         f << dot(cB) == (1/TIMEUNITS_PER_HOUR)* (- u(0)*cB + k1*cA - k2*cB);
00109         f << dot(theta) == (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));
00110         f << dot(thetaK) == (1/TIMEUNITS_PER_HOUR)*((1/(mK*CPK))*(u(1) + kw*AR*(theta-thetaK)));
00111 
00112         // Reference functions and weighting matrices:
00113         Function h, hN;
00114         h << cA << cB << theta << thetaK << u;
00115         hN << cA << cB << theta << thetaK;
00116 
00117         DMatrix W = eye<double>( h.getDim() );
00118         DMatrix WN = eye<double>( hN.getDim() );
00119 
00120         W(0, 0) = WN(0, 0) = sqrt(0.2);
00121         W(1, 1) = WN(1, 1) = sqrt(1.0);
00122         W(2, 2) = WN(2, 2) = sqrt(0.5);
00123         W(3, 3) = WN(3, 3) = sqrt(0.2);
00124 
00125         W(4, 4) = 0.5000;
00126         W(5, 5) = 0.0000005;
00127 
00128         //
00129         // Optimal Control Problem:
00130         //
00131         OCP ocp(0.0, 1500.0, 22);
00132 
00133         ocp.subjectTo( f );
00134 
00135         ocp.minimizeLSQ(W, h);
00136         ocp.minimizeLSQEndTerm(WN, hN);
00137 
00138         ocp.subjectTo( 3.0 <= u(0) <= 35.0 );
00139         ocp.subjectTo( -9000.0 <= u(1) <= 0.0 );
00140 
00141         // Export the code:
00142         OCPexport mpc(ocp);
00143 
00144         mpc.set( INTEGRATOR_TYPE , INT_RK4 );
00145         mpc.set( NUM_INTEGRATOR_STEPS , 23 );
00146         mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON );
00147         mpc.set( GENERATE_TEST_FILE,NO );
00148 
00149         if (mpc.exportCode("cstr22_export") != SUCCESSFUL_RETURN)
00150                 exit( EXIT_FAILURE );
00151 
00152         mpc.printDimensionsQP( );
00153 
00154         return EXIT_SUCCESS;
00155 }
00156 
00157 
00158 


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