process.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 
33 #ifndef ACADO_TOOLKIT_PROCESS_HPP
34 #define ACADO_TOOLKIT_PROCESS_HPP
35 
36 
39 
40 #include <acado/noise/noise.hpp>
43 #include <acado/curve/curve.hpp>
46 
47 
49 
50 
51 
71 class Process : public SimulationBlock
72 {
73  //
74  // PUBLIC MEMBER FUNCTIONS:
75  //
76  public:
77 
80  Process( );
81 
92  Process( const DynamicSystem& _dynamicSystem,
93  IntegratorType _integratorType = INT_UNKNOWN
94  );
95 
100  Process( const Process& rhs
101  );
102 
105  virtual ~Process( );
106 
111  Process& operator=( const Process& rhs
112  );
113 
114 
123  returnValue setDynamicSystem( const DynamicSystem& _dynamicSystem,
124  IntegratorType _integratorType = INT_UNKNOWN
125  );
126 
137  returnValue addDynamicSystemStage( const DynamicSystem& _dynamicSystem,
138  IntegratorType _integratorType = INT_UNKNOWN
139  );
140 
141 
148  returnValue setActuator( const Actuator& _actuator
149  );
150 
157  returnValue setSensor( const Sensor& _sensor
158  );
159 
160 
167  returnValue setProcessDisturbance( const Curve& _processDisturbance
168  );
169 
177  returnValue setProcessDisturbance( const VariablesGrid& _processDisturbance
178  );
179 
187  returnValue setProcessDisturbance( const char* _processDisturbance
188  );
189 
190 
198  returnValue initializeStartValues( const DVector& _xStart,
199  const DVector& _xaStart = emptyConstVector
200  );
201 
209  );
210 
211 
232  virtual returnValue init( double _startTime = 0.0,
233  const DVector& _xStart = emptyConstVector,
234  const DVector& _uStart = emptyConstVector,
235  const DVector& _pStart = emptyConstVector
236  );
237 
238 
250  virtual returnValue step( const VariablesGrid& _u,
252  );
253 
265  virtual returnValue step( const VariablesGrid& _u,
266  const DVector& _p
267  );
268 
282  virtual returnValue step( double startTime,
283  double endTime,
284  const DVector& _u,
285  const DVector& _p = emptyConstVector
286  );
287 
288 
300  virtual returnValue run( const VariablesGrid& _u,
302  );
303 
315  virtual returnValue run( const VariablesGrid& _u,
316  const DVector& _p
317  );
318 
332  virtual returnValue run( double startTime,
333  double endTime,
334  const DVector& _u,
335  const DVector& _p = emptyConstVector
336  );
337 
338 
345  inline returnValue getY( VariablesGrid& _y
346  ) const;
347 
348 
355  inline uint getNU( uint stageIdx = 0
356  ) const;
357 
364  inline uint getNP( uint stageIdx = 0
365  ) const;
366 
373  inline uint getNW( uint stageIdx = 0
374  ) const;
375 
382  inline uint getNY( uint stageIdx = 0
383  ) const;
384 
385 
390  inline uint getNumStages( ) const;
391 
392 
400  inline BooleanType isODE( uint stageIdx = 0
401  ) const;
402 
410  inline BooleanType isDAE( uint stageIdx = 0
411  ) const;
412 
413 
421  inline BooleanType isDiscretized( uint stageIdx = 0
422  ) const;
423 
431  inline BooleanType isContinuous( uint stageIdx = 0
432  ) const;
433 
434 
440  inline BooleanType hasActuator( ) const;
441 
447  inline BooleanType hasSensor( ) const;
448 
454  inline BooleanType hasProcessDisturbance( ) const;
455 
456 
463  virtual returnValue replot( PlotFrequency _frequency = PLOT_IN_ANY_CASE
464  );
465 
466 
467 
468  //
469  // PROTECTED MEMBER FUNCTIONS:
470  //
471  protected:
472 
477  virtual returnValue setupOptions( );
478 
483  virtual returnValue setupLogging( );
484 
485 
492  inline uint getNX( uint stageIdx = 0
493  ) const;
494 
501  inline uint getNXA( uint stageIdx = 0
502  ) const;
503 
504 
515  returnValue addStage( const DynamicSystem &dynamicSystem_,
516  const Grid &stageIntervals,
517  const IntegratorType &integratorType_ = INT_UNKNOWN
518  );
519 
520 
525  returnValue clear( );
526 
527 
538  const VariablesGrid& _p,
539  const VariablesGrid& _w
540  );
541 
542 
554  const VariablesGrid& _p
555  ) const;
556 
557 
574  const VariablesGrid* _x,
575  const DVector& _xComponents,
576  const VariablesGrid* _xa,
577  const VariablesGrid* _p,
578  const VariablesGrid* _u,
579  const VariablesGrid* _w,
580  VariablesGrid* _output
581  ) const;
582 
592  const DVector& _xComponents,
593  VariablesGrid& _output
594  ) const;
595 
596 
597  //
598  // PROTECTED MEMBERS:
599  //
600  protected:
601 
604 
615 
616  double lastTime;
617 
618 
619  IntegratorType integratorType; // sorry -- quick hack.
620 
621 };
622 
623 
625 
626 
627 
628 #include <acado/process/process.ipp>
629 
630 
631 #endif // ACADO_TOOLKIT_PROCESS_HPP
632 
633 
634 /*
635  * end of file
636  */
VariablesGrid y
Definition: process.hpp:614
Actuator * actuator
Definition: process.hpp:610
Curve * processDisturbance
Definition: process.hpp:612
returnValue setActuator(const Actuator &_actuator)
Definition: process.cpp:254
BooleanType isDAE(uint stageIdx=0) const
IntegratorType integratorType
Definition: process.hpp:619
Allows to setup and evaluate output functions based on SymbolicExpressions.
Definition: output_fcn.hpp:55
returnValue getY(VariablesGrid &_y) const
returnValue addStage(const DynamicSystem &dynamicSystem_, const Grid &stageIntervals, const IntegratorType &integratorType_=INT_UNKNOWN)
Definition: process.cpp:778
Stores a DifferentialEquation together with an OutputFcn.
BooleanType hasActuator() const
virtual returnValue setupOptions()
Definition: process.cpp:711
Process()
Definition: process.cpp:50
Discretizes a DifferentialEquation by means of single or multiple shooting.
returnValue projectToComponents(const VariablesGrid &_x, const DVector &_xComponents, VariablesGrid &_output) const
Definition: process.cpp:1028
Provides a time grid consisting of vector-valued optimization variables at each grid point...
Allows to pass back messages to the calling function.
uint getNU(uint stageIdx=0) const
BEGIN_NAMESPACE_ACADO typedef unsigned int uint
Definition: acado_types.hpp:42
Allows to conveniently handle (one-dimensional) grids consisting of time points.
Definition: grid.hpp:58
Allows to simulate the behaviour of sensors within the Process.
Definition: sensor.hpp:54
BooleanType hasProcessDisturbance() const
virtual returnValue step(const VariablesGrid &_u, const VariablesGrid &_p=emptyVariablesGrid)
Definition: process.cpp:508
virtual returnValue setupLogging()
Definition: process.cpp:745
Sensor * sensor
Definition: process.hpp:611
virtual returnValue replot(PlotFrequency _frequency=PLOT_IN_ANY_CASE)
Definition: process.cpp:678
#define CLOSE_NAMESPACE_ACADO
returnValue initializeStartValues(const DVector &_xStart, const DVector &_xaStart=emptyConstVector)
Definition: process.cpp:330
uint getNW(uint stageIdx=0) const
PlotFrequency
returnValue calculateOutput(OutputFcn &_outputFcn, const VariablesGrid *_x, const DVector &_xComponents, const VariablesGrid *_xa, const VariablesGrid *_p, const VariablesGrid *_u, const VariablesGrid *_w, VariablesGrid *_output) const
Definition: process.cpp:992
uint nDynSys
Definition: process.hpp:605
uint getNX(uint stageIdx=0) const
DynamicSystem ** dynamicSystems
Definition: process.hpp:606
CLOSE_NAMESPACE_ACADO static BEGIN_NAMESPACE_ACADO VariablesGrid emptyVariablesGrid
returnValue initializeAlgebraicStates(const DVector &_xaStart)
Definition: process.cpp:345
double lastTime
Definition: process.hpp:616
static const DVector emptyConstVector
Definition: vector.hpp:336
Process & operator=(const Process &rhs)
Definition: process.cpp:150
BooleanType hasSensor() const
IntegratorType
uint getNXA(uint stageIdx=0) const
returnValue addDynamicSystemStage(const DynamicSystem &_dynamicSystem, IntegratorType _integratorType=INT_UNKNOWN)
Definition: process.cpp:238
uint getNP(uint stageIdx=0) const
Allows to work with piecewise-continous function defined over a scalar time interval.
Definition: curve.hpp:52
void rhs(const real_t *x, real_t *f)
returnValue checkInputConsistency(const VariablesGrid &_u, const VariablesGrid &_p) const
Definition: process.cpp:957
virtual returnValue run(const VariablesGrid &_u, const VariablesGrid &_p=emptyVariablesGrid)
Definition: process.cpp:632
ShootingMethod * integrationMethod
Definition: process.hpp:608
DVector x
Definition: process.hpp:602
virtual ~Process()
Definition: process.cpp:144
returnValue setProcessDisturbance(const Curve &_processDisturbance)
Definition: process.cpp:289
Base class for building-blocks of the SimulationEnvironment.
uint getNumStages() const
BooleanType isODE(uint stageIdx=0) const
returnValue clear()
Definition: process.cpp:797
Simulates the process to be controlled based on a dynamic model.
Definition: process.hpp:71
#define BEGIN_NAMESPACE_ACADO
uint getNY(uint stageIdx=0) const
BooleanType isContinuous(uint stageIdx=0) const
Allows to simulate the behaviour of actuators within the Process.
Definition: actuator.hpp:54
BooleanType isDiscretized(uint stageIdx=0) const
DVector xa
Definition: process.hpp:603
returnValue simulate(const VariablesGrid &_u, const VariablesGrid &_p, const VariablesGrid &_w)
Definition: process.cpp:827
returnValue setDynamicSystem(const DynamicSystem &_dynamicSystem, IntegratorType _integratorType=INT_UNKNOWN)
Definition: process.cpp:204
returnValue setSensor(const Sensor &_sensor)
Definition: process.cpp:271
virtual returnValue init(double _startTime=0.0, const DVector &_xStart=emptyConstVector, const DVector &_uStart=emptyConstVector, const DVector &_pStart=emptyConstVector)
Definition: process.cpp:353


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