fed_batch_bioreactor_ws.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 
00048 #include "acado_optimal_control.hpp"
00049 #include <acado_gnuplot.hpp>
00050 
00051 
00052 int main( ){
00053 
00054     USING_NAMESPACE_ACADO
00055 
00056     // INTRODUCE FIXED PARAMETERS:
00057     // ---------------------------
00058     #define  Csin       2.8
00059 
00060 
00061     // INTRODUCE THE VARIABLES:
00062     // -------------------------
00063     DifferentialState     x1,x2,x3,x4,x5;
00064     IntermediateState     mu,sigma,pif;
00065     Control               u           ;
00066     Parameter             tf          ;
00067     DifferentialEquation  f(0.0,tf)   ;
00068 
00069 
00070     // DEFINE A DIFFERENTIAL EQUATION:
00071     // -------------------------------
00072     mu    = 0.125*x2/x4;
00073     sigma = mu/0.135;
00074     pif   = (-384.0*mu*mu + 134.0*mu);
00075 
00076     f << dot(x1) ==  mu*x1;
00077     f << dot(x2) == -sigma*x1 + u*Csin;
00078     f << dot(x3) ==  pif*x1;
00079     f << dot(x4) ==  u;
00080     f << dot(x5) ==  0.001*(u*u + 0.01*tf*tf);
00081 
00082     // DEFINE AN OPTIMAL CONTROL PROBLEM:
00083     // ----------------------------------
00084     OCP ocp( 0.0, tf, 50 );
00085     ocp.minimizeMayerTerm(0, -x3/tf          ); // Solve productivity optimal problem (Note: - due to maximization, small regularisation term)
00086     ocp.minimizeMayerTerm(1, -x3/(Csin*x4-x2)); // Solve yield optimal problem (Note: Csin = x2(t=0)/x4(t=0); - due to maximization, small regularisation term)
00087 
00088     ocp.subjectTo( f );
00089 
00090     ocp.subjectTo( AT_START, x1 ==   0.1           );
00091     ocp.subjectTo( AT_START, x2 ==  14.0           );
00092     ocp.subjectTo( AT_START, x3 ==   0.0           );
00093     ocp.subjectTo( AT_START, x4 ==   5.0           );
00094     ocp.subjectTo( AT_START, x5 ==   0.0           );
00095 
00096     ocp.subjectTo(  0.0 <= x1 <=   15.0  );
00097     ocp.subjectTo(  0.0 <= x2 <=   30.0  );
00098     ocp.subjectTo( -0.1 <= x3 <= 1000.0  );
00099     ocp.subjectTo(  5.0 <= x4 <=   20.0  );
00100     ocp.subjectTo( 20.0 <= tf <=   40.0  );
00101     ocp.subjectTo(  0.0 <= u  <=    2.0  );
00102 
00103 
00104     // DEFINE A MULTI-OBJECTIVE ALGORITHM AND SOLVE THE OCP:
00105     // -----------------------------------------------------
00106     MultiObjectiveAlgorithm algorithm(ocp);
00107 
00108     algorithm.set( PARETO_FRONT_GENERATION    , PFG_WEIGHTED_SUM );
00109     algorithm.set( PARETO_FRONT_DISCRETIZATION, 21               );
00110     algorithm.set( HESSIAN_APPROXIMATION, EXACT_HESSIAN );
00111     algorithm.set( KKT_TOLERANCE, 1e-7 );
00112 
00113     // Generate Pareto set
00114     algorithm.solve();
00115 
00116     algorithm.getWeights("fed_batch_bioreactor_ws_weights.txt");
00117     algorithm.getAllDifferentialStates("fed_batch_bioreactor_ws_states.txt");
00118     algorithm.getAllControls("fed_batch_bioreactor_ws_controls.txt");
00119     algorithm.getAllParameters("fed_batch_bioreactor_ws_parameters.txt");
00120 
00121     // VISUALIZE THE RESULTS IN A GNUPLOT WINDOW:
00122     // ------------------------------------------
00123     VariablesGrid paretoFront;
00124     algorithm.getParetoFront( paretoFront );
00125 
00126     GnuplotWindow window1;
00127     window1.addSubplot( paretoFront, "Pareto Front (yield versus productivity)", "-PRODUCTIVTY", "-YIELD", PM_POINTS );
00128     window1.plot( );
00129 
00130 
00131     // PRINT INFORMATION ABOUT THE ALGORITHM:
00132     // --------------------------------------
00133     algorithm.printInfo();
00134 
00135 
00136     // SAVE INFORMATION:
00137     // -----------------
00138     paretoFront.print();
00139 
00140     return 0;
00141 }
00142 


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