hydroscal_model.hpp
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 
56 //#define PSEUDO_STATES
57 /* problem setup */
58 
59 /* #define NMOS 2*/
60 
61 #define NMOS 2
62 #define NP 17
63 #define NRC 0
64 #define NRCE 0
65 
66 #define NPR 0
67 #define NLSQ 4
68 
69 #ifdef PSEUDO_STATES
70 #define NXD 84
71 #else
72 #define NXD 82
73 #endif
74 
75 #define NXA 122
76 #define NU 2
77 #define NW 1
78 
79 /* model parameters */
80 
81 #define qF 1
82 #define Nfeed 20
83 
84 #define A1 23.48
85 #define B1 3626.6
86 #define C1 -34.29
87 
88 #define A2 22.437
89 #define B2 3166.4
90 #define C2 -80.15
91 
92 #define Rconst 8.3147
93 
94 #define T14s (70)
95 #define T28s (88)
96 
97 #define QT14 1
98 #define QT28 1
99 
100 #define R11 (2/2)
101 #define R22 (0.1/2)
102 #define RPENALTY (0.1)
103 
104 
105 typedef struct {
106 
107  double x[42];
108  double n[42];
109  double L[42];
110  double V[42];
111  double Temp[42];
112 
113  double refvol[42];
114  double Pres[42];
115  double P1[42];
116  double P2[42];
117  double y[42];
118 
119  double F;
120  double xF;
121 
122 
123  double nvolB;
124  double nvolD;
125  double nvolM;
126  double nvolK;
127  double flowwidth;
128 
129  double alphastrip;
130  double alpharect;
131  double Ptop;
132  double DPstrip;
133  double DPrect;
134  double Tfeed;
135  double Tcond;
136 
137 } Parameters;
138 
140 
141 
142 
143 
144 static double T_x(double T, double x)
145  /*
146  Calculates derivative of T with respect to x,
147  according to implicit function theorem for
148  0=F=x*P1(T)+(1-x)*P2(T)-P
149  */
150 {
151  double P1,P2,P1_T,P2_T, F_T, F_x, T_x;
152 
153  P1 = exp(A1-B1/(C1+T));
154  P1_T = P1 * B1/(C1+T)/(C1+T);
155 
156  P2 = exp(A2-B2/(C2+T));
157  P2_T = P2 * B2/(C2+T)/(C2+T);
158 
159  F_T=x*P1_T+(1-x)*P2_T;
160  F_x=P1-P2;
161 
162  T_x=- 1/F_T*F_x;
163  return T_x;
164 }
165 
166 
167 static void enthalpies_1(double Temp, double Pres, double *hL1, double *hV1, double *hL1_T)
168  /*
169  gives enthalpies of pure liquid/gaseous Methanol at Temperature Temp and Pressure Pres
170  */
171 
172 {
173  const double h11 = 18.31 ;
174  const double h21 = 1.713E-2 ;
175  const double h31 = 6.399E-5 ;
176  const double Tc1 = 512.6 ;
177  const double Pc1 = 8.096E6 ;
178  const double OMEGA1 = 0.557 ;
179 
180  double TR1, PR1, Dhv1;
181 
182  TR1=Temp/Tc1;
183  PR1=Pres/Pc1;
184  Dhv1 = Rconst*Tc1*sqrt(1-PR1/pow(TR1,3))*(6.09648-1.28862*TR1+
185  1.016*pow(TR1,7)+OMEGA1*(15.6875-13.4721*TR1+2.615*pow(TR1,7)));
186  *hL1=(h11*(Temp-273.15)+h21*pow(Temp-273.15,2)+h31*pow(Temp-273.15,3))*4.186;
187  *hV1=*hL1+Dhv1;
188  *hL1_T=(h11+h21*2*(Temp-273.15)+h31*3*pow(Temp-273.15,2))*4.186;
189 }
190 
191 static void enthalpies_2(double Temp, double Pres, double *hL2, double *hV2, double *hL2_T)
192  /*
193  gives enthalpies of pure liquid/gaseous n-Propanol at Temperature Temp and Pressure Pres
194  */
195 
196 {
197  const double h12 = 31.92 ;
198  const double h22 = 4.49E-2 ;
199  const double h32 = 9.663E-5 ;
200  const double Tc2 = 536.7 ;
201  const double Pc2 = 5.166E6 ;
202  const double OMEGA2 = 0.612 ;
203 
204  double TR2, PR2, Dhv2;
205 
206  TR2=Temp/Tc2;
207  PR2=Pres/Pc2;
208  Dhv2 = Rconst*Tc2*sqrt(1-PR2/pow(TR2,3))*(6.09648-1.28862*TR2+
209  1.016*pow(TR2,7)+OMEGA2*(15.6875-13.4721*TR2+2.615*pow(TR2,7)));
210  *hL2=(h12*(Temp-273.15)+h22*pow(Temp-273.15,2)+h32*pow(Temp-273.15,3))*4.186;
211  *hV2=*hL2+Dhv2;
212  *hL2_T=(h12+h22*2*(Temp-273.15)+h32*3*pow(Temp-273.15,2))*4.186;
213 }
214 
215 
216 
217 static void enthalpies(double Temp, double Pres, double x, double y,
218  double *hL, double *hV, double *hL_x_total)
219  /*
220  gives enthalpies of mixed liquid/vapour
221  - and (total) derivative of liquid -
222  at Temperature Temp and Pressure Pres
223  */
224 
225 {
226  double hL1, hV1, hL1_T, hL2, hV2, hL2_T, hL_x, hL_T;
227  enthalpies_1(Temp, Pres, &hL1,&hV1, &hL1_T);
228  enthalpies_2(Temp, Pres, &hL2,&hV2, &hL2_T);
229  *hL=hL1*x+hL2*(1-x);
230  *hV=hV1*y+hV2*(1-y);
231  hL_x=hL1-hL2;
232  hL_T=hL1_T*x+hL2_T*(1-x);
233  *hL_x_total=hL_x
234  +hL_T*T_x(Temp,x)
235  ;
236 }
237 
238 
239 static double litre_per_kmol(double TK, double x_m)
240  /* gives molar Volume in
241  litre / kmol
242  from
243  Temp in Kelvin,
244  x_m the Methanol concentration
245  */
246 
247 {
248  double d_m, vm, d_p, vp, vol_p, vol_m, vol_sum, v_mix;//, F;
249  d_m = 2.288/ pow(0.2685,(1+ pow((1 - TK/512.4),0.2453)));
250  vm = 1/d_m;
251 
252  d_p = 1.235/ pow(0.27136, (1+ pow((1- TK/536.4),0.24)));
253  vp = 1/d_p;
254 
255  vol_m = x_m*vm;
256  vol_p = (1-x_m)*vp;
257  vol_sum = vol_m + vol_p;
258  v_mix= vol_sum*1000;
259 
260  return v_mix;
261 }
262 
263 
264 static double ramp(double x)
265 {
266  /*
267  smooth version of the "__/" function 1/2 ( x + |x| )
268  */
269  const double R=20;
270  double xo;
271  if (x<-R) xo=0;
272  else if (x<R) xo=0.5*(x+log(2*cosh(x)));
273  else xo=x;
274 
275  return xo;
276 
277 }
278 static double kmol_per_sec_outflow(double n, double TK, double x_m, double refvol,
279  double flowwidth)
280  /* gives Tray outflow in
281  kmol / sec
282  from
283  n molar tray holdup
284  Temp in Kelvin,
285  x_m the Methanol concentration
286  refvol reference volume in litre
287  */
288 
289 {
290  double volumeholdup, volumeoutflow, outflow, l_per_kmol;
291  const double alpha=500;
292  l_per_kmol=litre_per_kmol(TK, x_m);
293  volumeholdup=l_per_kmol * n;
294  volumeoutflow = flowwidth*(
295  pow(1/alpha*ramp(alpha*(volumeholdup-refvol)),1.5)
296  /* -1/pow(alpha,1.5)*ramp(-alpha*(volumeholdup-refvol)) */
297  );
298  outflow=volumeoutflow / l_per_kmol;
299 
300  /*
301  acadoFPrintf(stderr,"%g ",refvol/volumeholdup);
302  */
303 
304  return outflow;
305 }
306 
307 
308 
309 static void insert(double *xd,
310  double *xa,
311  double *u,
312  double *p
313 )
314  /*
315  Extracts variables out of xd, xa, u, p, puts them into
316  par.x, par.Temp, par.V, par.L, etc.
317 
318 
319  Attention: par.V[41] and par.L[0] are only specified in prepare(), as they need y.
320 
321  */
322 {
323  double Lc, Vc;
324  double Q;//, R;
325  double L_lh,F_lh;
326  //double xC;
327  double holdup = 0.0;
328  double dummy, hL, hV, deltaH, Qloss;
329  long i;
330  extern Parameters par;
331 
332  L_lh = u[0];
333  Q = u[1];
334 
335  par.alpharect = p[2];
336  par.alphastrip = p[3];
337 
338  Qloss = p[5];
339 
340  par.nvolB = p[6];
341  par.nvolD = p[7];
342  par.nvolM = p[0];
343  par.nvolK = p[0];
344  par.flowwidth = p[4];
345 
346 
347  par.Ptop = p[8];
348  par.DPstrip = p[9];
349  par.DPrect = p[9];
350 
351 #ifdef PSEUDO_STATES
352  F_lh = xd[82];
353  par.xF = xd[83];
354 #else
355  F_lh = p[10];
356  par.xF = p[11];
357 #endif
358 
359 
360  par.Tfeed = p[12] +273.15;
361  par.Tcond = p[13] +273.15;
362 
363  /* Let's just put the variables in a nicer form */
364 
365  for (i=0; i<= 39; i++)
366  {
367  par.L[i+1]=xa[i];
368  par.V[i+1]=xa[40+i];
369  par.Temp[i]=xa[80+i];
370  }
371  par.Temp[40]=xa[120];
372  par.Temp[41]=xa[121];
373 
374  for (i=0; i<= 41; i++)
375  par.x[i]=xd[i];
376 
377  for (i=1; i<= 40; i++)
378  par.n[i]=xd[41+i];
379 
380 
381  /* Pressure */
382  par.Pres[41]=par.Ptop;
383  for (i=41; i>=1; i--)
384  {
385  if (i>Nfeed)
386  {par.Pres[i-1]=par.Pres[i]+par.DPrect;}
387  else
388  {par.Pres[i-1]=par.Pres[i]+par.DPstrip;}
389  }
390 
391  /* vapor concentrations */
392  for (i=0; i<= 41; i++)
393  {
394  par.P1[i] = exp(A1-B1/(C1+par.Temp[i]));
395  par.P2[i] = exp(A2-B2/(C2+par.Temp[i]));
396  par.y[i]=par.P1[i]*par.x[i]/par.Pres[i];
397  }
398  /* Tray efficiency */
399  for (i=1; i<= Nfeed; i++)
400  par.y[i]=par.alphastrip*par.y[i]+(1-par.alphastrip)*par.y[i-1];
401 
402  for (i=Nfeed+1; i<= 40; i++)
403  par.y[i]=par.alpharect*par.y[i]+(1-par.alpharect)*par.y[i-1];
404 
405 
406  par.y[41]=par.x[41]; /* Condenser outflow out of column is liquid */
407 
408  /* recalculate input fluxes from litres/hour into kmol/sec */
409  par.F = F_lh / (litre_per_kmol(par.Tfeed, par.xF)*3600); /* [kmol/s] */
410  Lc = L_lh / (litre_per_kmol(par.Tcond, par.x[41])*3600); /* [kmol/s] */
411  /* Lc = L_lh / (litre_per_kmol(par.Temp[41], par.x[41])*3600); */
412  /* Lc = R/(1+R) * par.V[40]; */
413  par.L[41]=Lc;
414 
415  /* calculate vapour flow */
416  i=0;
417  enthalpies(par.Temp[i], par.Pres[i], par.x[i], par.y[i], &hL,&hV, &dummy);
418  deltaH=hV-hL;
419  Vc = (Q-Qloss)/deltaH;
420  par.V[0]=Vc;
421 
422  for (i=0; i<= 41; i++)
423  {
424  if (i==0) holdup=par.nvolB;
425  else if (i<Nfeed) holdup=par.nvolK;
426  if (i==Nfeed) holdup=par.nvolM;
427  else if (i<41) holdup=par.nvolK;
428  else if (i==41) holdup=par.nvolD;
429 
430  par.refvol[i]=holdup;
431  }
432  par.n[0] =par.refvol[0]/litre_per_kmol(par.Temp[0], par.x[0]);
433  par.n[41]=par.refvol[41]/litre_per_kmol(par.Temp[41], par.x[41]);
434 
435  /* Volume of Reboiler is fixed */
436  par.L[0]=1/litre_per_kmol(par.Temp[0], par.x[0])
437  * ( litre_per_kmol(par.Temp[0], par.x[1]) * par.L[1]
438  - litre_per_kmol(par.Temp[0], par.y[0]) * par.V[0]
439  );
440 
441  /* Volume of Condenser is fixed */
442  par.V[41]=1/litre_per_kmol(par.Temp[41], par.y[41])
443  * ( litre_per_kmol(par.Temp[41], par.y[40]) * par.V[40]
444  - litre_per_kmol(par.Temp[41], par.x[41]) * par.L[41]
445  );
446 
447 }
448 
449 static void diffeq(
450  double *dx,
451  double *dn
452 )
453  /*
454  Calculates dx[42] and dn[40] from
455  par.x, par.Temp, par.V, par.L, par.y
456 
457  */
458 {
459 
460  extern Parameters par;
461  long i;
462  double Vmol, dVmol_x;
463 
464  /* Reboiler with fixed volume */
465  i=0;
466  Vmol=litre_per_kmol(par.Temp[i], par.x[i]);
467  dVmol_x=litre_per_kmol(par.Temp[i], 1.0)-litre_per_kmol(par.Temp[i], 0.0);
468 
469  dx[i] = 1 / (par.n[i]*(1 + dVmol_x * par.x[i] / Vmol) )
470  * (par.L[i+1]*par.x[i+1] - par.V[i]*par.y[i] - par.L[i]*par.x[i]);
471 
472  /* Stripping + Rectifying + Feed */
473 
474  for (i=1; i<=40; i++)
475  {
476  dx[i] = -(1/par.n[i])*par.V[i]*(par.y[i]-par.x[i]);
477  dn[i-1] = -par.V[i]-par.L[i];
478 
479  dx[i] += (1/par.n[i])*par.L[i+1]*(par.x[i+1]-par.x[i]);
480  dn[i-1] += par.L[i+1];
481 
482  dx[i] += (1/par.n[i])*par.V[i-1]*(par.y[i-1]-par.x[i]);
483  dn[i-1] += par.V[i-1];
484 
485  if (i==Nfeed)
486  {
487  dx[i] += (1/par.n[i])*par.F*(par.xF-par.x[i]);
488  dn[i-1] += par.F;
489  }
490  }
491 
492  /* Condenser with fixed volume */
493  i=41;
494  Vmol=litre_per_kmol(par.Temp[i], par.x[i]);
495  dVmol_x=litre_per_kmol(par.Temp[i], 1.0)-litre_per_kmol(par.Temp[i], 0.0);
496 
497  dx[i] = 1 / (par.n[i]*(1 + dVmol_x * par.x[i] / Vmol) )
498  * (par.V[i-1]*par.y[i-1] - par.V[i]*par.y[i] - par.L[i]*par.x[i]);
499 }
500 
501 
502 static void ffcn( double *t, double *xd, double *xa, double *u,
503  double *p, double *rhs ){
504 
505  long i;
506 #ifdef PSEUDO_STATES
507  double xdcopy[84];
508 #else
509  double xdcopy[82];
510 #endif
511  double xacopy[122];
512  /* scaling */
513  for(i=0;i<42;i++)
514  xdcopy[i]=xd[i];
515  for(i=42;i<82;i++)
516  xdcopy[i]=xd[i]*1e-3;
517 #ifdef PSEUDO_STATES
518  xdcopy[82]=xd[82];
519  xdcopy[83]=xd[83];
520 #endif
521  for(i=0;i<80;i++)
522  xacopy[i]=xa[i]*1e-5;
523  for(i=80;i<122;i++)
524  xacopy[i]=xa[i]+273.15;
525 
526  insert(xdcopy, xacopy, u, p);
527  diffeq(rhs, &rhs[42]);
528 
529  /* scaling */
530  for(i=42;i<82;i++)
531  rhs[i]=rhs[i]/1e-3;
532 
533 #ifdef PSEUDO_STATES
534  rhs[82]=0;
535  rhs[83]=0;
536 #endif
537 
538 }
539 
540 
541 
542 static void gfcn(double *t, double *xd, double *xa, double *u,
543  double *p, double *rhs ){
544 
545  extern Parameters par;
546 
547  long i;
548  double hL_x[42], hL[42], hV[42];
549  double dx[42],dn[42];
550  double Pfeed, yfeed, P1, P2, dummy;
551  double hLfeed, hVfeed;
552 
553 #ifdef PSEUDO_STATES
554  double xdcopy[84];
555 #else
556  double xdcopy[82];
557 #endif
558  double xacopy[122];
559 
560  /* scaling */
561  for(i=0;i<42;i++)
562  xdcopy[i]=xd[i];
563  for(i=42;i<82;i++)
564  xdcopy[i]=xd[i]*1e-3;
565 #ifdef PSEUDO_STATES
566  xdcopy[82]=xd[82];
567  xdcopy[83]=xd[83];
568 #endif
569 
570  for(i=0;i<80;i++)
571  xacopy[i]=xa[i]*1e-5;
572 
573  for(i=80;i<122;i++)
574  xacopy[i]=xa[i]+273.15;
575 
576 
577 
578  insert(xdcopy, xacopy, u, p);
579  diffeq(dx, dn);
580 
581  /* enthalpies */
582  for (i=0; i<= 41; i++)
583  {
584  enthalpies(par.Temp[i], par.Pres[i], par.x[i], par.y[i], &hL[i],&hV[i], &hL_x[i]);
585  }
586 
587  /* entalphy of the feed */
588 
589  P1 = exp(A1-B1/(C1+par.Tfeed));
590  P2 = exp(A2-B2/(C2+par.Tfeed));
591  Pfeed=P1*par.xF+(1-par.xF)*P2;
592  yfeed=P1*par.xF/Pfeed;
593 
594  enthalpies(par.Tfeed, Pfeed, par.xF, yfeed, &hLfeed,&hVfeed, &dummy);
595 
596  /* enthalphy of the condenser reflux, when Temperature different from equilibrium */
597  i=41;
598  par.Temp[i]=par.Tcond;
599  enthalpies(par.Temp[i], par.Pres[i], par.x[i], par.y[i], &hL[i],&hV[i], &hL_x[i]);
600 
601 
602  /* ++++++++++++++++++++ Algebraic equations ++++++++++++++++++++++ */
603 
604 
605  /* Stripping + Rectifying + Feed - algebraic */
606 
607  for (i=1; i<=40; i++)
608  {
609  rhs[i-1] = par.L[i]-kmol_per_sec_outflow(par.n[i], par.Temp[i], par.x[i],
610  par.refvol[i], par.flowwidth);
611  /*
612  rhs[40+i-1] = par.V[i-1]*hV[i-1]
613  - par.V[i]*hV[i]
614  + par.L[i+1]*hL[i+1]
615  - par.L[i]*hL[i]
616  - par.n[i]*hL_x[i]*dx[i]
617  - dn[i-1]*hL[i];
618  if (i==Nfeed)
619  {
620  rhs[40+i-1] += par.F*hLfeed + (1-qF)*hVfeed;
621  }
622  */
623 
624  rhs[40+i-1] = par.V[i-1]*(hV[i-1] - hL[i])
625  - par.V[i]*(hV[i] -hL[i])
626  + par.L[i+1]*(hL[i+1]-hL[i])
627  - par.n[i]*hL_x[i]*dx[i];
628  if (i==Nfeed)
629  {
630  rhs[40+i-1] += par.F*(hLfeed - hL[i]) + (1-qF)*hVfeed;
631  }
632 
633  }
634 
635  /* Temperatures - algebraic */
636  for (i=0; i<= 41; i++)
637  rhs[80+i]=1-par.P1[i]/par.Pres[i]*par.x[i]-(1-par.x[i])*par.P2[i]/par.Pres[i];
638 
639  /* scaling */
640  for(i=0;i<40;i++)
641  rhs[i]=rhs[i]/1e-5;
642 }
643 
static double ramp(double x)
#define B1
IntermediateState sqrt(const Expression &arg)
USING_NAMESPACE_ACADO typedef TaylorVariable< Interval > T
#define B2
static void enthalpies(double Temp, double Pres, double x, double y, double *hL, double *hV, double *hL_x_total)
double Temp[42]
#define Nfeed
double Pres[42]
#define Rconst
static void enthalpies_1(double Temp, double Pres, double *hL1, double *hV1, double *hL1_T)
static void diffeq(double *dx, double *dn)
IntermediateState pow(const Expression &arg1, const Expression &arg2)
double refvol[42]
#define A1
double P1[42]
double n[42]
#define qF
static double T_x(double T, double x)
#define A2
static void gfcn(double *t, double *xd, double *xa, double *u, double *p, double *rhs)
static void ffcn(double *t, double *xd, double *xa, double *u, double *p, double *rhs)
void rhs(const real_t *x, real_t *f)
static Parameters par
#define L
double L[42]
static double kmol_per_sec_outflow(double n, double TK, double x_m, double refvol, double flowwidth)
double P2[42]
#define C1
static void enthalpies_2(double Temp, double Pres, double *hL2, double *hV2, double *hL2_T)
#define C2
static double litre_per_kmol(double TK, double x_m)
double x[42]
IntermediateState exp(const Expression &arg)
double y[42]
double V[42]
#define R
static void insert(double *xd, double *xa, double *u, double *p)
IntermediateState log(const Expression &arg)


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