cstr22.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 
34 
35 const double k10 = 1.287e12;
36 const double k20 = 1.287e12;
37 const double k30 = 9.043e09;
38 const double E1 = -9758.3;
39 const double E2 = -9758.3;
40 const double E3 = -8560.0;
41 const double H1 = 4.2;
42 const double H2 = -11.0;
43 const double H3 = -41.85;
44 const double rho = 0.9342;
45 const double Cp = 3.01;
46 const double kw = 4032.0;
47 const double AR = 0.215;
48 const double VR = 10.0;
49 const double mK = 5.0;
50 const double CPK = 2.0;
51 
52 const double cA0 = 5.1;
53 const double theta0 = 104.9;
54 
55 const double FFs = 14.19; /* Feed Flow normed by VR: (dV/dt / VR)*/
56 const double QdotKs = -1113.50;
57 
58 const double cAs = 2.1402105301746182e00;
59 const double cBs = 1.0903043613077321e00;
60 const double thetas = 1.1419108442079495e02;
61 const double thetaKs = 1.1290659291045561e02;
62 
63 
64 const double TIMEUNITS_PER_HOUR = 3600.0;
65 
66 
67 const double P11 = 3278.78;
68 const double P21 = 1677.31;
69 const double P31 = 681.02;
70 const double P41 = 271.50;
71 
72 const double P12 = 1677.31;
73 const double P22 = 919.78;
74 const double P32 = 344.19;
75 const double P42 = 137.27;
76 
77 const double P13 = 681.02;
78 const double P23 = 344.19;
79 const double P33 = 172.45;
80 const double P43 = 65.53;
81 
82 const double P14 = 271.50;
83 const double P24 = 137.27;
84 const double P34 = 65.53;
85 const double P44 = 29.28;
86 
87 
88 const double R_OMEGA = 90.0;
89 
90 
91 int main()
92 {
94 
95  // Define a Right-Hand-Side:
96  DifferentialState cA, cB, theta, thetaK;
97  Control u("", 2, 1);
98 
100 
101  IntermediateState k1, k2, k3;
102 
103  k1 = k10*exp(E1/(273.15 +theta));
104  k2 = k20*exp(E2/(273.15 +theta));
105  k3 = k30*exp(E3/(273.15 +theta));
106 
107  f << dot(cA) == (1/TIMEUNITS_PER_HOUR)*(u(0)*(cA0-cA) - k1*cA - k3*cA*cA);
108  f << dot(cB) == (1/TIMEUNITS_PER_HOUR)* (- u(0)*cB + k1*cA - k2*cB);
109  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));
110  f << dot(thetaK) == (1/TIMEUNITS_PER_HOUR)*((1/(mK*CPK))*(u(1) + kw*AR*(theta-thetaK)));
111 
112  // Reference functions and weighting matrices:
113  Function h, hN;
114  h << cA << cB << theta << thetaK << u;
115  hN << cA << cB << theta << thetaK;
116 
117  DMatrix W = eye<double>( h.getDim() );
118  DMatrix WN = eye<double>( hN.getDim() );
119 
120  W(0, 0) = WN(0, 0) = sqrt(0.2);
121  W(1, 1) = WN(1, 1) = sqrt(1.0);
122  W(2, 2) = WN(2, 2) = sqrt(0.5);
123  W(3, 3) = WN(3, 3) = sqrt(0.2);
124 
125  W(4, 4) = 0.5000;
126  W(5, 5) = 0.0000005;
127 
128  //
129  // Optimal Control Problem:
130  //
131  OCP ocp(0.0, 1500.0, 22);
132 
133  ocp.subjectTo( f );
134 
135  ocp.minimizeLSQ(W, h);
136  ocp.minimizeLSQEndTerm(WN, hN);
137 
138  ocp.subjectTo( 3.0 <= u(0) <= 35.0 );
139  ocp.subjectTo( -9000.0 <= u(1) <= 0.0 );
140 
141  // Export the code:
142  OCPexport mpc(ocp);
143 
144  mpc.set( INTEGRATOR_TYPE , INT_RK4 );
145  mpc.set( NUM_INTEGRATOR_STEPS , 23 );
147  mpc.set( GENERATE_TEST_FILE,NO );
148 
149  if (mpc.exportCode("cstr22_export") != SUCCESSFUL_RETURN)
150  exit( EXIT_FAILURE );
151 
152  mpc.printDimensionsQP( );
153 
154  return EXIT_SUCCESS;
155 }
156 
157 
158 
const double P14
Definition: cstr22.cpp:82
const double theta0
Definition: cstr22.cpp:53
const double P32
Definition: cstr22.cpp:74
Allows to setup and evaluate a general function based on SymbolicExpressions.
Definition: function_.hpp:59
const double R_OMEGA
Definition: cstr22.cpp:88
IntermediateState sqrt(const Expression &arg)
const double E1
Definition: cstr22.cpp:38
const double Cp
Definition: cstr22.cpp:45
const double P43
Definition: cstr22.cpp:80
const double P34
Definition: cstr22.cpp:84
int main()
Definition: cstr22.cpp:91
const double AR
Definition: cstr22.cpp:47
#define USING_NAMESPACE_ACADO
const double FFs
Definition: cstr22.cpp:55
const double P41
Definition: cstr22.cpp:70
const double P44
Definition: cstr22.cpp:85
const double H1
Definition: cstr22.cpp:41
const double QdotKs
Definition: cstr22.cpp:56
const double P21
Definition: cstr22.cpp:68
virtual returnValue exportCode(const std::string &dirName, const std::string &_realString="real_t", const std::string &_intString="int", int _precision=16)
Definition: ocp_export.cpp:68
returnValue subjectTo(const DifferentialEquation &differentialEquation_)
Definition: ocp.cpp:153
const double thetaKs
Definition: cstr22.cpp:61
const double cBs
Definition: cstr22.cpp:59
returnValue set(OptionsName name, int value)
Definition: options.cpp:126
const double thetas
Definition: cstr22.cpp:60
returnValue minimizeLSQ(const DMatrix &S, const Function &h, const DVector &r)
Definition: ocp.cpp:244
const double P13
Definition: cstr22.cpp:77
returnValue minimizeLSQEndTerm(const DMatrix &S, const Function &m, const DVector &r)
Definition: ocp.cpp:297
const double E3
Definition: cstr22.cpp:40
const double P22
Definition: cstr22.cpp:73
const double VR
Definition: cstr22.cpp:48
int getDim() const
const double P11
Definition: cstr22.cpp:67
const double TIMEUNITS_PER_HOUR
Definition: cstr22.cpp:64
const double H3
Definition: cstr22.cpp:43
const double k20
Definition: cstr22.cpp:36
#define NO
Definition: acado_types.hpp:53
const double cAs
Definition: cstr22.cpp:58
const double P23
Definition: cstr22.cpp:78
const double mK
Definition: cstr22.cpp:49
const double P24
Definition: cstr22.cpp:83
Data class for defining optimal control problems.
Definition: ocp.hpp:89
const double P12
Definition: cstr22.cpp:72
const double kw
Definition: cstr22.cpp:46
const double P31
Definition: cstr22.cpp:69
Expression dot(const Expression &arg)
const double P42
Definition: cstr22.cpp:75
const double P33
Definition: cstr22.cpp:79
const double cA0
Definition: cstr22.cpp:52
const double H2
Definition: cstr22.cpp:42
A user class for auto-generation of OCP solvers.
Definition: ocp_export.hpp:57
const double CPK
Definition: cstr22.cpp:50
returnValue printDimensionsQP()
Definition: ocp_export.cpp:464
const double E2
Definition: cstr22.cpp:39
IntermediateState exp(const Expression &arg)
const double rho
Definition: cstr22.cpp:44
const double k30
Definition: cstr22.cpp:37
const double k10
Definition: cstr22.cpp:35
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