examples/ocp/cstr.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ACADO Toolkit.
3  *
4  * ACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.
5  * Copyright (C) 2008-2014 by Boris Houska, Hans Joachim Ferreau,
6  * Milan Vukov, Rien Quirynen, KU Leuven.
7  * Developed within the Optimization in Engineering Center (OPTEC)
8  * under supervision of Moritz Diehl. All rights reserved.
9  *
10  * ACADO Toolkit is free software; you can redistribute it and/or
11  * modify it under the terms of the GNU Lesser General Public
12  * License as published by the Free Software Foundation; either
13  * version 3 of the License, or (at your option) any later version.
14  *
15  * ACADO Toolkit is distributed in the hope that it will be useful,
16  * but WITHOUT ANY WARRANTY; without even the implied warranty of
17  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
18  * Lesser General Public License for more details.
19  *
20  * You should have received a copy of the GNU Lesser General Public
21  * License along with ACADO Toolkit; if not, write to the Free Software
22  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
23  *
24  */
25 
26 
27 
36 #include <acado_gnuplot.hpp>
37 
38 
39 
40 const double k10 = 1.287e12;
41 const double k20 = 1.287e12;
42 const double k30 = 9.043e09;
43 const double E1 = -9758.3;
44 const double E2 = -9758.3;
45 const double E3 = -8560.0;
46 const double H1 = 4.2;
47 const double H2 = -11.0;
48 const double H3 = -41.85;
49 const double rho = 0.9342;
50 const double Cp = 3.01;
51 const double kw = 4032.0;
52 const double AR = 0.215;
53 const double VR = 10.0;
54 const double mK = 5.0;
55 const double CPK = 2.0;
56 
57 const double cA0 = 5.1;
58 const double theta0 = 104.9;
59 
60 const double FFs = 14.19; /* Feed Flow normed by VR: (dV/dt / VR)*/
61 const double QdotKs = -1113.50;
62 
63 const double cAs = 2.1402105301746182e00;
64 const double cBs = 1.0903043613077321e00;
65 const double thetas = 1.1419108442079495e02;
66 const double thetaKs = 1.1290659291045561e02;
67 
68 
69 const double TIMEUNITS_PER_HOUR = 3600.0;
70 
71 
72 const double P11 = 3278.78;
73 const double P21 = 1677.31;
74 const double P31 = 681.02;
75 const double P41 = 271.50;
76 
77 const double P12 = 1677.31;
78 const double P22 = 919.78;
79 const double P32 = 344.19;
80 const double P42 = 137.27;
81 
82 const double P13 = 681.02;
83 const double P23 = 344.19;
84 const double P33 = 172.45;
85 const double P43 = 65.53;
86 
87 const double P14 = 271.50;
88 const double P24 = 137.27;
89 const double P34 = 65.53;
90 const double P44 = 29.28;
91 
92 
93 const double R_OMEGA = 90.0;
94 
95 
96 
97 int main( ){
98 
100 
101 
102  // Define a Right-Hand-Side:
103  // -------------------------
104 
105  DifferentialState cA, cB, theta, thetaK;
106  Control u("", 2, 1);
107 
109 
110  IntermediateState k1, k2, k3;
111 
112  k1 = k10*exp(E1/(273.15 +theta));
113  k2 = k20*exp(E2/(273.15 +theta));
114  k3 = k30*exp(E3/(273.15 +theta));
115 
116  f << dot(cA) == (1/TIMEUNITS_PER_HOUR)*(u(0)*(cA0-cA) - k1*cA - k3*cA*cA);
117  f << dot(cB) == (1/TIMEUNITS_PER_HOUR)* (- u(0)*cB + k1*cA - k2*cB);
118  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));
119  f << dot(thetaK) == (1/TIMEUNITS_PER_HOUR)*((1/(mK*CPK))*(u(1) + kw*AR*(theta-thetaK)));
120 
121 
122 
123  // DEFINE LEAST SQUARE FUNCTION:
124  // -----------------------------
125  Function h;
126 
127  h << cA;
128  h << cB;
129  h << theta;
130  h << thetaK;
131  h << u(0);
132  h << u(1);
133 
134  DMatrix S = eye<double>(6);
135  DVector r = zeros<double>(6);
136 
137  S(0,0) = 0.2;
138  S(1,1) = 1.0;
139  S(2,2) = 0.5;
140  S(3,3) = 0.2;
141 
142  S(4,4) = 0.5000;
143  S(5,5) = 0.0000005;
144 
145  r(0) = 2.14;
146  r(1) = 1.09;
147  r(2) = 114.2;
148  r(3) = 112.9;
149  r(4) = 14.19;
150  r(5) = -1113.5;
151 
152 
153  // DEFINE AN OPTIMAL CONTROL PROBLEM:
154  // ----------------------------------
155 // const double t_start = 0.0 ;
156 // const double t_end = 1500;
157 
158 
159  double times[11];
160 // double times[10];
161  int run1;
162  for( run1 = 0; run1 < 10; run1++ )
163  times[run1] = run1*80.0;
164 
165  times[10] = 1500.0;
166  Grid grid( 11, times );
167 // Grid grid( 10, times );
168 
169 
170 // double times[23];
171 // int run1;
172 // for( run1 = 0; run1 < 22; run1++ )
173 // times[run1] = run1*20.0;
174 //
175 // times[22] = 1500.0;
176 // Grid grid( 23, times );
177 
178 
179  OCP ocp( grid );
180 // OCP ocp( t_start, t_end, 22 );
181 // OCP ocp( t_start, t_end, 75 );
182 
183  ocp.minimizeLSQ( S, h, r );
184 
185  ocp.subjectTo( f );
186 
187  ocp.subjectTo( AT_START, cA == 1.0 );
188  ocp.subjectTo( AT_START, cB == 0.5 );
189  ocp.subjectTo( AT_START, theta == 100.0 );
190  ocp.subjectTo( AT_START, thetaK == 100.0 );
191 
192  ocp.subjectTo( 3.0 <= u(0) <= 35.0 );
193  ocp.subjectTo( -9000.0 <= u(1) <= 0.0 );
194 
195 
196  VariablesGrid cstr75states;
197  VariablesGrid cstr75controls;
198 
199  cstr75states.read( "cstr75_states.txt" );
200  cstr75controls.read( "cstr75_controls.txt" );
201 
202  // Additionally, flush a plotting object
203  GnuplotWindow window1;
204  window1.addSubplot( cA, "cA [mol/l]","","",PM_LINES,0,1500 );
205  window1.addData( 0,cstr75states(0) );
206 
207  GnuplotWindow window2;
208  window2.addSubplot( cB, "cB [mol/l]","","",PM_LINES,0,1500 );
209  window2.addData( 0,cstr75states(1) );
210 
211  GnuplotWindow window3;
212  window3.addSubplot( theta, "theta [C]","","",PM_LINES,0,1500 );
213  window3.addData( 0,cstr75states(2) );
214 
215  GnuplotWindow window4;
216  window4.addSubplot( thetaK, "thetaK [C]","","",PM_LINES,0,1500 );
217  window4.addData( 0,cstr75states(3) );
218 
219  GnuplotWindow window5;
220  window5.addSubplot( u(0), "u1","","",PM_LINES,0,1500 );
221  window5.addData( 0,cstr75controls(0) );
222 
223  GnuplotWindow window6;
224  window6.addSubplot( u(1), "u2","","",PM_LINES,0,1500 );
225  window6.addData( 0,cstr75controls(1) );
226 
227 
228  GnuplotWindow window;
229  window.addSubplot( cA, "cA [mol/l]","","",PM_LINES,0,1500 );
230  window.addSubplot( cB, "cB [mol/l]","","",PM_LINES,0,1500 );
231  window.addSubplot( theta, "theta [C]","","",PM_LINES,0,1500 );
232  window.addSubplot( thetaK, "thetaK [C]","","",PM_LINES,0,1500 );
233  window.addSubplot( u(0), "u1","","",PM_LINES,0,1500 );
234  window.addSubplot( u(1), "u2","","",PM_LINES,0,1500 );
235 
236  window.addData( 0,cstr75states(0) );
237  window.addData( 1,cstr75states(1) );
238  window.addData( 2,cstr75states(2) );
239  window.addData( 3,cstr75states(3) );
240  window.addData( 4,cstr75controls(0) );
241  window.addData( 5,cstr75controls(1) );
242 
243 
244  // DEFINE AN OPTIMIZATION ALGORITHM AND SOLVE THE OCP:
245  // ---------------------------------------------------
246  OptimizationAlgorithm algorithm(ocp);
247 
248 // algorithm << window;
249 
250 // algorithm.set( HESSIAN_APPROXIMATION, EXACT_HESSIAN );
251  algorithm.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON );
252 
253  algorithm.set( INTEGRATOR_TOLERANCE, 1e-6 );
254  algorithm.set( KKT_TOLERANCE, 1e-4 );
255 // algorithm.set( GLOBALIZATION_STRATEGY, GS_FULLSTEP );
256 // algorithm.set( MAX_NUM_ITERATIONS, 1 );
257  algorithm.set( PRINT_SCP_METHOD_PROFILE, YES );
258 
259  VariablesGrid uStart( 2,0.0,2000.0,2 );
260  uStart( 0,0 ) = 14.19;
261  uStart( 0,1 ) = -1113.5;
262  uStart( 1,0 ) = 14.19;
263  uStart( 1,1 ) = -1113.5;
264 
265  algorithm.initializeControls( uStart );
266 
267  algorithm << window1;
268  algorithm << window2;
269  algorithm << window3;
270  algorithm << window4;
271  algorithm << window5;
272  algorithm << window6;
273 
274  algorithm << window;
275  algorithm.solve();
276 // algorithm.solve();
277 
278 // algorithm.getDifferentialStates( "cstr75_states.txt" );
279 // algorithm.getControls( "cstr75_controls.txt" );
280 // algorithm.getDifferentialStates( "cstr10_states.txt" );
281 // algorithm.getControls( "cstr10_controls.txt" );
282 
283  return 0;
284 }
285 
286 
287 
const double cAs
Allows to setup and evaluate a general function based on SymbolicExpressions.
Definition: function_.hpp:59
const double P22
const double cBs
const double H1
returnValue initializeControls(const char *fileName)
const double P44
const double P43
const double kw
User-interface to formulate and solve optimal control problems and static NLPs.
#define USING_NAMESPACE_ACADO
const double P21
Provides a time grid consisting of vector-valued optimization variables at each grid point...
const double QdotKs
const double P31
const double P33
Allows to conveniently handle (one-dimensional) grids consisting of time points.
Definition: grid.hpp:58
int main()
const double Cp
returnValue subjectTo(const DifferentialEquation &differentialEquation_)
Definition: ocp.cpp:153
const double theta0
const double VR
returnValue addSubplot(PlotWindowSubplot &_subplot)
const double CPK
const double E2
const double AR
const double mK
const double P34
const double P41
returnValue set(OptionsName name, int value)
Definition: options.cpp:126
returnValue minimizeLSQ(const DMatrix &S, const Function &h, const DVector &r)
Definition: ocp.cpp:244
#define YES
Definition: acado_types.hpp:51
const double k10
const double H2
const double cA0
const double P12
const double E3
const double E1
const double P32
const double thetaKs
const double R_OMEGA
const double H3
Data class for defining optimal control problems.
Definition: ocp.hpp:89
virtual returnValue addData(uint idx, const VariablesGrid &_newData)
Expression dot(const Expression &arg)
returnValue read(std::istream &stream)
const double P42
const double P13
const double P23
const double k20
const double FFs
const double TIMEUNITS_PER_HOUR
const double P11
const double P24
const double k30
IntermediateState exp(const Expression &arg)
const double rho
Provides an interface to Gnuplot for plotting algorithmic outputs.
const double P14
virtual returnValue solve()
const double thetas
Allows to setup and evaluate differential equations (ODEs and DAEs) based on SymbolicExpressions.


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Mon Jun 10 2019 12:34:31