process.hpp
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 
00033 #ifndef ACADO_TOOLKIT_PROCESS_HPP
00034 #define ACADO_TOOLKIT_PROCESS_HPP
00035 
00036 
00037 #include <acado/utils/acado_utils.hpp>
00038 #include <acado/simulation_environment/simulation_block.hpp>
00039 
00040 #include <acado/noise/noise.hpp>
00041 #include <acado/transfer_device/actuator.hpp>
00042 #include <acado/transfer_device/sensor.hpp>
00043 #include <acado/curve/curve.hpp>
00044 #include <acado/dynamic_system/dynamic_system.hpp>
00045 #include <acado/dynamic_discretization/shooting_method.hpp>
00046 
00047 
00048 BEGIN_NAMESPACE_ACADO
00049 
00050 
00051 
00071 class Process : public SimulationBlock
00072 {
00073         //
00074         //  PUBLIC MEMBER FUNCTIONS:
00075         //
00076         public:
00077 
00080         Process( );
00081 
00092                 Process(        const DynamicSystem& _dynamicSystem,
00093                                         IntegratorType _integratorType = INT_UNKNOWN
00094                                         );
00095 
00100         Process(        const Process& rhs
00101                                         );
00102 
00105         virtual ~Process( );
00106 
00111         Process& operator=(     const Process& rhs
00112                                                         );
00113 
00114 
00123                 returnValue setDynamicSystem(   const DynamicSystem& _dynamicSystem,
00124                                                                                 IntegratorType _integratorType = INT_UNKNOWN
00125                                                                                 );
00126 
00137                 returnValue addDynamicSystemStage(      const DynamicSystem& _dynamicSystem,
00138                                                                                         IntegratorType _integratorType = INT_UNKNOWN
00139                                                                                         );
00140 
00141 
00148                 returnValue setActuator(        const Actuator& _actuator
00149                                                                         );
00150 
00157                 returnValue setSensor(  const Sensor& _sensor
00158                                                                 );
00159 
00160 
00167                 returnValue setProcessDisturbance(      const Curve& _processDisturbance
00168                                                                                         );
00169 
00177                 returnValue setProcessDisturbance(      const VariablesGrid& _processDisturbance
00178                                                                                         );
00179 
00187                 returnValue setProcessDisturbance(      const char* _processDisturbance
00188                                                                                         );
00189 
00190 
00198                 returnValue initializeStartValues(      const DVector& _xStart,
00199                                                                                         const DVector& _xaStart = emptyConstVector
00200                                                                                         );
00201 
00208                 returnValue initializeAlgebraicStates(  const DVector& _xaStart
00209                                                                                                 );
00210 
00211 
00232         virtual returnValue init(       double _startTime = 0.0,
00233                                                                         const DVector& _xStart = emptyConstVector,
00234                                                                         const DVector& _uStart = emptyConstVector,
00235                                                                         const DVector& _pStart = emptyConstVector
00236                                                                         );
00237 
00238 
00250         virtual returnValue step(       const VariablesGrid& _u,
00251                                                                         const VariablesGrid& _p = emptyVariablesGrid
00252                                                                         );
00253 
00265         virtual returnValue step(       const VariablesGrid& _u,
00266                                                                         const DVector& _p
00267                                                                         );
00268 
00282         virtual returnValue step(       double startTime,
00283                                                                         double endTime,
00284                                                                         const DVector& _u,
00285                                                                         const DVector& _p = emptyConstVector
00286                                                                         );
00287 
00288 
00300         virtual returnValue run(        const VariablesGrid& _u,
00301                                                                         const VariablesGrid& _p = emptyVariablesGrid
00302                                                                         );
00303 
00315         virtual returnValue run(        const VariablesGrid& _u,
00316                                                                         const DVector& _p
00317                                                                         );
00318 
00332         virtual returnValue run(        double startTime,
00333                                                                         double endTime,
00334                                                                         const DVector& _u,
00335                                                                         const DVector& _p = emptyConstVector
00336                                                                         );
00337 
00338 
00345         inline returnValue getY(        VariablesGrid& _y
00346                                                                         ) const;
00347 
00348 
00355                 inline uint getNU(      uint stageIdx = 0
00356                                                         ) const;
00357 
00364                 inline uint getNP(      uint stageIdx = 0
00365                                                         ) const;
00366 
00373                 inline uint getNW(      uint stageIdx = 0
00374                                                         ) const;
00375 
00382                 inline uint getNY(      uint stageIdx = 0
00383                                                         ) const;
00384 
00385 
00390                 inline uint getNumStages( ) const;
00391 
00392 
00400                 inline BooleanType isODE(       uint stageIdx = 0
00401                                                                         ) const;
00402 
00410                 inline BooleanType isDAE(       uint stageIdx = 0
00411                                                                         ) const;
00412 
00413 
00421                 inline BooleanType isDiscretized(       uint stageIdx = 0
00422                                                                                         ) const;
00423 
00431                 inline BooleanType isContinuous(        uint stageIdx = 0
00432                                                                                         ) const;
00433 
00434 
00440                 inline BooleanType hasActuator( ) const;
00441 
00447                 inline BooleanType hasSensor( ) const;
00448 
00454                 inline BooleanType hasProcessDisturbance( ) const;
00455 
00456 
00463                 virtual returnValue replot(     PlotFrequency _frequency = PLOT_IN_ANY_CASE
00464                                                                         );
00465 
00466 
00467 
00468         //
00469         //  PROTECTED MEMBER FUNCTIONS:
00470         //
00471         protected:
00472 
00477                 virtual returnValue setupOptions( );
00478 
00483                 virtual returnValue setupLogging( );
00484 
00485 
00492                 inline uint getNX(      uint stageIdx = 0
00493                                                         ) const;
00494 
00501                 inline uint getNXA(     uint stageIdx = 0
00502                                                         ) const;
00503 
00504 
00515         returnValue addStage(   const DynamicSystem  &dynamicSystem_,
00516                                                                 const Grid           &stageIntervals,
00517                                                                 const IntegratorType &integratorType_ = INT_UNKNOWN
00518                                                                 );
00519 
00520 
00525                 returnValue clear( );
00526 
00527 
00537                 returnValue simulate(   const VariablesGrid& _u,
00538                                                                 const VariablesGrid& _p,
00539                                                                 const VariablesGrid& _w
00540                                                                 );
00541 
00542 
00553                 returnValue checkInputConsistency(      const VariablesGrid& _u,
00554                                                                                         const VariablesGrid& _p
00555                                                                                         ) const;
00556 
00557 
00573                 returnValue calculateOutput(    OutputFcn& _outputFcn,
00574                                                                                 const VariablesGrid* _x,
00575                                                                                 const DVector& _xComponents,
00576                                                                                 const VariablesGrid* _xa,
00577                                                                                 const VariablesGrid* _p,
00578                                                                                 const VariablesGrid* _u,
00579                                                                                 const VariablesGrid* _w,
00580                                                                                 VariablesGrid* _output
00581                                                                                 ) const;
00582 
00591                 returnValue projectToComponents(        const VariablesGrid& _x,
00592                                                                                         const DVector& _xComponents,
00593                                                                                         VariablesGrid& _output
00594                                                                                         ) const;
00595 
00596 
00597         //
00598         //  PROTECTED MEMBERS:
00599         //
00600         protected:
00601 
00602                 DVector x;
00603                 DVector xa;
00604 
00605                 uint nDynSys;                                                           
00606                 DynamicSystem** dynamicSystems;                         
00608                 ShootingMethod* integrationMethod;                      
00610                 Actuator* actuator;                                                     
00611                 Sensor* sensor;                                                         
00612                 Curve* processDisturbance;                                      
00614                 VariablesGrid y;
00615 
00616                 double lastTime;
00617 
00618 
00619                 IntegratorType integratorType;  // sorry -- quick hack.
00620 
00621 };
00622 
00623 
00624 CLOSE_NAMESPACE_ACADO
00625 
00626 
00627 
00628 #include <acado/process/process.ipp>
00629 
00630 
00631 #endif  // ACADO_TOOLKIT_PROCESS_HPP
00632 
00633 
00634 /*
00635  *      end of file
00636  */


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