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


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