39 const double k10 = 1.287e12;
40 const double k20 = 1.287e12;
41 const double k30 = 9.043e09;
42 const double E1 = -9758.3;
43 const double E2 = -9758.3;
44 const double E3 = -8560.0;
45 const double H1 = 4.2;
46 const double H2 = -11.0;
47 const double H3 = -41.85;
48 const double rho = 0.9342;
49 const double Cp = 3.01;
50 const double kw = 4032.0;
51 const double AR = 0.215;
52 const double VR = 10.0;
53 const double mK = 5.0;
54 const double CPK = 2.0;
56 const double cA0 = 5.1;
59 const double FFs = 14.19;
62 const double cAs = 2.1402105301746182e00;
63 const double cBs = 1.0903043613077321e00;
64 const double thetas = 1.1419108442079495e02;
65 const double thetaKs = 1.1290659291045561e02;
113 DMatrix Q = zeros<double>(4,4);
142 double x_start[20] = { 1.0, 0.5, 100.0, 100.0, 1.0, 0.0, 0.0, 0.0,
145 0.0, 0.0, 0.0, 1.0 };
147 double u_start[2] = { 14.19, -1113.5 };
150 Grid timeInterval( 0.0, 5000.0, 100 );
153 integrator.
integrate( timeInterval, x_start, 0 ,0, u_start );
160 integrator.
getX( differentialStates );
164 for(
int i=0; i<4; ++i )
165 for(
int j=0; j<4; ++j )
166 PPP(i,j) = PP(4+i*4+j);
171 window.
addSubplot( differentialStates(0),
"cA [mol/l]" );
172 window.
addSubplot( differentialStates(1),
"cB [mol/l]" );
173 window.
addSubplot( differentialStates(2),
"theta [C]" );
174 window.
addSubplot( differentialStates(3),
"thetaK [C]" );
176 window.
addSubplot( differentialStates(4 ),
"P11" );
177 window.
addSubplot( differentialStates(9 ),
"P22" );
178 window.
addSubplot( differentialStates(14),
"P33" );
179 window.
addSubplot( differentialStates(19),
"P44" );
returnValue getX(DVector &xEnd) const
Expression getRiccatiODE(const Expression &rhs, const DifferentialState &x, const Control &u, const DifferentialState &P, const DMatrix &Q, const DMatrix &R)
virtual returnValue plot(PlotFrequency _frequency=PLOT_IN_ANY_CASE)
returnValue set(OptionsName name, int value)
#define USING_NAMESPACE_ACADO
Provides a time grid consisting of vector-valued optimization variables at each grid point...
Allows to conveniently handle (one-dimensional) grids consisting of time points.
returnValue addSubplot(PlotWindowSubplot &_subplot)
const double TIMEUNITS_PER_HOUR
virtual returnValue print(std::ostream &_stream=std::cout, const std::string &_name=DEFAULT_LABEL, const std::string &_startString=DEFAULT_START_STRING, const std::string &_endString=DEFAULT_END_STRING, uint _width=DEFAULT_WIDTH, uint _precision=DEFAULT_PRECISION, const std::string &_colSeparator=DEFAULT_COL_SEPARATOR, const std::string &_rowSeparator=DEFAULT_ROW_SEPARATOR) const
DVector getLastVector() const
USING_NAMESPACE_ACADO IntermediateState cstrModel(const DifferentialState &x, const Control &u)
virtual returnValue freezeAll()
void rhs(const real_t *x, real_t *f)
Expression dot(const Expression &arg)
Implements the Runge-Kutta-45 scheme for integrating ODEs.
IntermediateState exp(const Expression &arg)
Provides an interface to Gnuplot for plotting algorithmic outputs.
returnValue integrate(double t0, double tend, double *x0, double *xa=0, double *p=0, double *u=0, double *w=0)
Allows to setup and evaluate differential equations (ODEs and DAEs) based on SymbolicExpressions.