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_optimal_control.hpp>
00036 #include <acado_gnuplot.hpp>
00037 
00038 
00039 
00040 const double k10 =  1.287e12;
00041 const double k20 =  1.287e12;
00042 const double k30 =  9.043e09;
00043 const double E1  =  -9758.3;
00044 const double E2  =  -9758.3;
00045 const double E3  =  -8560.0;
00046 const double H1  =      4.2;
00047 const double H2  =    -11.0;
00048 const double H3  =    -41.85;
00049 const double rho =      0.9342;
00050 const double Cp  =      3.01;
00051 const double kw  =   4032.0;
00052 const double AR  =      0.215;
00053 const double VR  =     10.0;
00054 const double mK  =      5.0;
00055 const double CPK =      2.0;
00056 
00057 const double cA0    =    5.1;
00058 const double theta0 =  104.9;
00059 
00060 const double FFs    =    14.19;  /* Feed Flow normed by VR: (dV/dt  / VR)*/
00061 const double QdotKs = -1113.50;
00062 
00063 const double cAs     =  2.1402105301746182e00;
00064 const double cBs     =  1.0903043613077321e00;
00065 const double thetas  =  1.1419108442079495e02;
00066 const double thetaKs =  1.1290659291045561e02;
00067 
00068 
00069 const double TIMEUNITS_PER_HOUR = 3600.0;
00070 
00071 
00072 const double P11 =   3278.78;   
00073 const double P21 =   1677.31;
00074 const double P31 =   681.02;
00075 const double P41 =   271.50;
00076 
00077 const double P12 =   1677.31;
00078 const double P22 =   919.78;
00079 const double P32 =   344.19;
00080 const double P42 =   137.27;
00081 
00082 const double P13 =   681.02;
00083 const double P23 =   344.19;
00084 const double P33 =   172.45;
00085 const double P43 =   65.53;
00086 
00087 const double P14 =   271.50;
00088 const double P24 =   137.27;
00089 const double P34 =   65.53;
00090 const double P44 =   29.28;
00091 
00092 
00093 const double R_OMEGA = 90.0;
00094 
00095 
00096 
00097 int main( ){
00098 
00099     USING_NAMESPACE_ACADO
00100 
00101 
00102     // Define a Right-Hand-Side:
00103     // -------------------------
00104 
00105     DifferentialState cA, cB, theta, thetaK;
00106         Control u("", 2, 1);
00107 
00108     DifferentialEquation f;
00109 
00110     IntermediateState k1, k2, k3;
00111 
00112         k1 = k10*exp(E1/(273.15 +theta));
00113         k2 = k20*exp(E2/(273.15 +theta));
00114         k3 = k30*exp(E3/(273.15 +theta));
00115 
00116         f << dot(cA) == (1/TIMEUNITS_PER_HOUR)*(u(0)*(cA0-cA) - k1*cA - k3*cA*cA); 
00117         f << dot(cB) == (1/TIMEUNITS_PER_HOUR)* (- u(0)*cB + k1*cA - k2*cB); 
00118         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)); 
00119         f << dot(thetaK) == (1/TIMEUNITS_PER_HOUR)*((1/(mK*CPK))*(u(1) + kw*AR*(theta-thetaK)));
00120 
00121 
00122 
00123     // DEFINE LEAST SQUARE FUNCTION:
00124     // -----------------------------
00125     Function h;
00126 
00127     h << cA;
00128     h << cB;
00129         h << theta;
00130         h << thetaK;
00131         h << u(0);
00132         h << u(1);
00133 
00134     DMatrix S = eye<double>(6);
00135     DVector r = zeros<double>(6);
00136 
00137         S(0,0) = 0.2;
00138         S(1,1) = 1.0;
00139         S(2,2) = 0.5;
00140         S(3,3) = 0.2;
00141 
00142         S(4,4) = 0.5000;
00143         S(5,5) = 0.0000005;
00144 
00145         r(0) = 2.14;
00146         r(1) = 1.09;
00147         r(2) = 114.2;
00148         r(3) = 112.9;
00149         r(4) = 14.19;
00150         r(5) = -1113.5;
00151         
00152 
00153     // DEFINE AN OPTIMAL CONTROL PROBLEM:
00154     // ----------------------------------
00155 //     const double t_start = 0.0   ;
00156 //     const double t_end   = 1500;
00157 
00158         
00159  double times[11];
00160 //     double times[10];
00161     int run1;
00162     for( run1 = 0; run1 < 10; run1++ )
00163         times[run1] = run1*80.0;
00164 
00165  times[10] = 1500.0;
00166  Grid grid( 11, times );
00167 //     Grid grid( 10, times );
00168 
00169 
00170 //     double times[23];
00171 //     int run1;
00172 //     for( run1 = 0; run1 < 22; run1++ )
00173 //         times[run1] = run1*20.0;
00174 // 
00175 //     times[22] = 1500.0;
00176 //     Grid grid( 23, times );
00177 
00178 
00179     OCP ocp( grid );
00180 //     OCP ocp( t_start, t_end, 22 );
00181 //        OCP ocp( t_start, t_end, 75 );
00182 
00183         ocp.minimizeLSQ( S, h, r );
00184 
00185         ocp.subjectTo( f );
00186 
00187         ocp.subjectTo( AT_START, cA     == 1.0 );
00188         ocp.subjectTo( AT_START, cB     == 0.5 );
00189         ocp.subjectTo( AT_START, theta  == 100.0 );
00190         ocp.subjectTo( AT_START, thetaK == 100.0 );
00191 
00192         ocp.subjectTo( 3.0     <= u(0) <= 35.0 );
00193         ocp.subjectTo( -9000.0 <= u(1) <= 0.0 );
00194 
00195         
00196         VariablesGrid cstr75states;
00197         VariablesGrid cstr75controls;
00198 
00199         cstr75states.read( "cstr75_states.txt" );
00200         cstr75controls.read( "cstr75_controls.txt" );
00201 
00202     // Additionally, flush a plotting object
00203     GnuplotWindow window1;
00204       window1.addSubplot( cA,     "cA [mol/l]","","",PM_LINES,0,1500 );
00205           window1.addData( 0,cstr75states(0) );
00206           
00207     GnuplotWindow window2;
00208           window2.addSubplot( cB,     "cB [mol/l]","","",PM_LINES,0,1500 );
00209           window2.addData( 0,cstr75states(1) );
00210           
00211     GnuplotWindow window3;
00212           window3.addSubplot( theta,  "theta [C]","","",PM_LINES,0,1500 );
00213           window3.addData( 0,cstr75states(2) );
00214           
00215         GnuplotWindow window4;
00216       window4.addSubplot( thetaK, "thetaK [C]","","",PM_LINES,0,1500 );
00217           window4.addData( 0,cstr75states(3) );
00218           
00219     GnuplotWindow window5;
00220           window5.addSubplot( u(0), "u1","","",PM_LINES,0,1500 );
00221           window5.addData( 0,cstr75controls(0) );
00222           
00223     GnuplotWindow window6;
00224           window6.addSubplot( u(1), "u2","","",PM_LINES,0,1500 );
00225           window6.addData( 0,cstr75controls(1) );
00226 
00227 
00228     GnuplotWindow window;
00229       window.addSubplot( cA,     "cA [mol/l]","","",PM_LINES,0,1500 );
00230           window.addSubplot( cB,     "cB [mol/l]","","",PM_LINES,0,1500 );
00231           window.addSubplot( theta,  "theta [C]","","",PM_LINES,0,1500 );
00232       window.addSubplot( thetaK, "thetaK [C]","","",PM_LINES,0,1500 );
00233           window.addSubplot( u(0), "u1","","",PM_LINES,0,1500 );
00234           window.addSubplot( u(1), "u2","","",PM_LINES,0,1500 );
00235 
00236         window.addData( 0,cstr75states(0) );
00237         window.addData( 1,cstr75states(1) );
00238         window.addData( 2,cstr75states(2) );
00239         window.addData( 3,cstr75states(3) );
00240         window.addData( 4,cstr75controls(0) );
00241         window.addData( 5,cstr75controls(1) );
00242 
00243 
00244     // DEFINE AN OPTIMIZATION ALGORITHM AND SOLVE THE OCP:
00245     // ---------------------------------------------------
00246     OptimizationAlgorithm algorithm(ocp);
00247 
00248 //     algorithm << window;
00249 
00250 //  algorithm.set( HESSIAN_APPROXIMATION, EXACT_HESSIAN );
00251         algorithm.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON );
00252 
00253         algorithm.set( INTEGRATOR_TOLERANCE, 1e-6 );
00254         algorithm.set( KKT_TOLERANCE, 1e-4 );
00255 //      algorithm.set( GLOBALIZATION_STRATEGY, GS_FULLSTEP );
00256 //      algorithm.set( MAX_NUM_ITERATIONS, 1 );
00257     algorithm.set( PRINT_SCP_METHOD_PROFILE, YES );
00258         
00259         VariablesGrid uStart( 2,0.0,2000.0,2 );
00260         uStart( 0,0 ) = 14.19;
00261         uStart( 0,1 ) = -1113.5;
00262         uStart( 1,0 ) = 14.19;
00263         uStart( 1,1 ) = -1113.5;
00264 
00265         algorithm.initializeControls( uStart );
00266 
00267         algorithm << window1;
00268         algorithm << window2;
00269         algorithm << window3;
00270         algorithm << window4;
00271         algorithm << window5;
00272         algorithm << window6;
00273 
00274         algorithm << window;
00275         algorithm.solve();
00276 //      algorithm.solve();
00277 
00278 //      algorithm.getDifferentialStates( "cstr75_states.txt" );
00279 //      algorithm.getControls( "cstr75_controls.txt" );
00280 //      algorithm.getDifferentialStates( "cstr10_states.txt" );
00281 //      algorithm.getControls( "cstr10_controls.txt" );
00282 
00283     return 0;
00284 }
00285 
00286 
00287 


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