Public Member Functions | Protected Member Functions | Protected Attributes

Simulates the process to be controlled based on a dynamic model. More...

#include <process.hpp>

Inheritance diagram for Process:
Inheritance graph
[legend]

List of all members.

Public Member Functions

returnValue addDynamicSystemStage (const DynamicSystem &_dynamicSystem, IntegratorType _integratorType=INT_UNKNOWN)
uint getNP (uint stageIdx=0) const
uint getNU (uint stageIdx=0) const
uint getNumStages () const
uint getNW (uint stageIdx=0) const
uint getNY (uint stageIdx=0) const
returnValue getY (VariablesGrid &_y) const
BooleanType hasActuator () const
BooleanType hasProcessDisturbance () const
BooleanType hasSensor () const
virtual returnValue init (double _startTime=0.0, const DVector &_xStart=emptyConstVector, const DVector &_uStart=emptyConstVector, const DVector &_pStart=emptyConstVector)
returnValue initializeAlgebraicStates (const DVector &_xaStart)
returnValue initializeStartValues (const DVector &_xStart, const DVector &_xaStart=emptyConstVector)
BooleanType isContinuous (uint stageIdx=0) const
BooleanType isDAE (uint stageIdx=0) const
BooleanType isDiscretized (uint stageIdx=0) const
BooleanType isODE (uint stageIdx=0) const
Processoperator= (const Process &rhs)
 Process ()
 Process (const DynamicSystem &_dynamicSystem, IntegratorType _integratorType=INT_UNKNOWN)
 Process (const Process &rhs)
virtual returnValue replot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
virtual returnValue run (const VariablesGrid &_u, const VariablesGrid &_p=emptyVariablesGrid)
virtual returnValue run (const VariablesGrid &_u, const DVector &_p)
virtual returnValue run (double startTime, double endTime, const DVector &_u, const DVector &_p=emptyConstVector)
returnValue setActuator (const Actuator &_actuator)
returnValue setDynamicSystem (const DynamicSystem &_dynamicSystem, IntegratorType _integratorType=INT_UNKNOWN)
returnValue setProcessDisturbance (const Curve &_processDisturbance)
returnValue setProcessDisturbance (const VariablesGrid &_processDisturbance)
returnValue setProcessDisturbance (const char *_processDisturbance)
returnValue setSensor (const Sensor &_sensor)
virtual returnValue step (const VariablesGrid &_u, const VariablesGrid &_p=emptyVariablesGrid)
virtual returnValue step (const VariablesGrid &_u, const DVector &_p)
virtual returnValue step (double startTime, double endTime, const DVector &_u, const DVector &_p=emptyConstVector)
virtual ~Process ()

Protected Member Functions

returnValue addStage (const DynamicSystem &dynamicSystem_, const Grid &stageIntervals, const IntegratorType &integratorType_=INT_UNKNOWN)
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
returnValue checkInputConsistency (const VariablesGrid &_u, const VariablesGrid &_p) const
returnValue clear ()
uint getNX (uint stageIdx=0) const
uint getNXA (uint stageIdx=0) const
returnValue projectToComponents (const VariablesGrid &_x, const DVector &_xComponents, VariablesGrid &_output) const
virtual returnValue setupLogging ()
virtual returnValue setupOptions ()
returnValue simulate (const VariablesGrid &_u, const VariablesGrid &_p, const VariablesGrid &_w)

Protected Attributes

Actuatoractuator
DynamicSystem ** dynamicSystems
ShootingMethodintegrationMethod
IntegratorType integratorType
double lastTime
uint nDynSys
CurveprocessDisturbance
Sensorsensor
DVector x
DVector xa
VariablesGrid y

Detailed Description

Simulates the process to be controlled based on a dynamic model.

The class Process is one of the two main building-blocks within the SimulationEnvironment and complements the Controller. It simulates the process to be controlled based on a dynamic model.

The Process simulates the dynamic model based on the controls, and optionally parameters, passed. Before using these inputs, they can be transformed by an Actuator. After the simulation, the outputs can be transformed by a Sensor. That way, actuator/sensor delays or noise can be introduced to yield more realistic simulation results. Moreover, in case the dynamic model depends on Disturbances, their values are specified by the user by assigning the processDisturbance member.

Author:
Hans Joachim Ferreau, Boris Houska

Definition at line 71 of file process.hpp.


Constructor & Destructor Documentation

Default constructor.

Definition at line 50 of file process.cpp.

Process::Process ( const DynamicSystem _dynamicSystem,
IntegratorType  _integratorType = INT_UNKNOWN 
)

Constructor which takes the dynamic system and the type of the integrator used for simulation.

Parameters:
[in]_dynamicSystemDynamic system to be used for simulation.
[in]_integratorTypeType of integrator to be used for simulation.
Note:
This constructor takes the dynamic system of the first model stage, multi-stage models can be simulated by adding further dynamic systems (however, this feature is not functional yet!).

Definition at line 71 of file process.cpp.

Process::Process ( const Process rhs)

Copy constructor (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 100 of file process.cpp.

Process::~Process ( ) [virtual]

Destructor.

Definition at line 144 of file process.cpp.


Member Function Documentation

returnValue Process::addDynamicSystemStage ( const DynamicSystem _dynamicSystem,
IntegratorType  _integratorType = INT_UNKNOWN 
)

Assigns new dynamic system stage to be used for simulation.

Parameters:
[in]_dynamicSystemDynamic system to be used for simulation.
[in]_integratorTypeType of integrator to be used for simulation.
Note:
Multi-stage models are not yet supported!
Returns:
SUCCESSFUL_RETURN,
RET_NOT_YET_IMPLEMENTED

Definition at line 238 of file process.cpp.

returnValue Process::addStage ( const DynamicSystem dynamicSystem_,
const Grid stageIntervals,
const IntegratorType integratorType_ = INT_UNKNOWN 
) [protected]

Internally adds a new dynamic system stage to be used for simulation.

Parameters:
[in]_dynamicSystemDynamic system to be used for simulation.
[in]stageIntervalsDummy grid.
[in]_integratorTypeType of integrator to be used for simulation.
Note:
Multi-stage models are not yet supported!
Returns:
SUCCESSFUL_RETURN

Definition at line 778 of file process.cpp.

returnValue Process::calculateOutput ( OutputFcn _outputFcn,
const VariablesGrid _x,
const DVector _xComponents,
const VariablesGrid _xa,
const VariablesGrid _p,
const VariablesGrid _u,
const VariablesGrid _w,
VariablesGrid _output 
) const [protected]

Calculates the process output based on the simulated states by evaluating the output function of the dynamic system.

Parameters:
[in]_xDifferential states.
[in]_xComponentsGlobal components of differential states actually used.
[in]_xaAlgebraic states.
[in]_pParameters.
[in]_uControls.
[in]_wDisturbances.
[in]_pParameters.
[out]_outputTime-varying process output.
Returns:
SUCCESSFUL_RETURN,
RET_INVALID_ARGUMENTS

Definition at line 992 of file process.cpp.

returnValue Process::checkInputConsistency ( const VariablesGrid _u,
const VariablesGrid _p 
) const [protected]

Checks consistency of the given inputs (dimensions, time grids etc.).

Parameters:
[in]_uTime-varying controls.
[in]_pTime-varying parameters.
Returns:
SUCCESSFUL_RETURN,
RET_CONTROL_DIMENSION_MISMATCH,
RET_PARAMETER_DIMENSION_MISMATCH,
RET_INVALID_ARGUMENTS

Definition at line 957 of file process.cpp.

returnValue Process::clear ( ) [protected]

Clears all dynamic systems and all members.

Returns:
SUCCESSFUL_RETURN

Definition at line 797 of file process.cpp.

uint Process::getNP ( uint  stageIdx = 0) const [inline]

Returns number of parameter signals (at given stage) expected by the process.

Parameters:
[in]stageIdxIndex of stage.
Returns:
Number of parameter signals (at given stage)
uint Process::getNU ( uint  stageIdx = 0) const [inline]

Returns number of control signals (at given stage) expected by the process.

Parameters:
[in]stageIdxIndex of stage.
Returns:
Number of control signals (at given stage)
uint Process::getNumStages ( ) const [inline]

Returns number of stages of the dynamic model.

Returns:
Number of stages of the dynamic model
uint Process::getNW ( uint  stageIdx = 0) const [inline]

Returns number of disturbances (at given stage) used within the process.

Parameters:
[in]stageIdxIndex of stage.
Returns:
Number of disturbances (at given stage)
uint Process::getNX ( uint  stageIdx = 0) const [inline, protected]

Returns number of differential states (at given stage) of the dynamic model.

Parameters:
[in]stageIdxIndex of stage.
Returns:
Number of differential states
uint Process::getNXA ( uint  stageIdx = 0) const [inline, protected]

Returns number of algebraic states (at given stage) of the dynamic model.

Parameters:
[in]stageIdxIndex of stage.
Returns:
Number of algebraic states
uint Process::getNY ( uint  stageIdx = 0) const [inline]

Returns number of process outputs (at given stage).

Parameters:
[in]stageIdxIndex of stage.
Returns:
Number of process outputs (at given stage)
returnValue Process::getY ( VariablesGrid _y) const [inline]

Returns output of the process.

Parameters:
[out]_yOutput of the process.
Returns:
SUCCESSFUL_RETURN
BooleanType Process::hasActuator ( ) const [inline]

Returns whether process comprises an actuator.

Returns:
BT_TRUE iff process comprises an actuator,
BT_FALSE otherwise

Returns whether process comprises a process disturbance.

Returns:
BT_TRUE iff process comprises a process disturbance,
BT_FALSE otherwise
BooleanType Process::hasSensor ( ) const [inline]

Returns whether process comprises a sensor.

Returns:
BT_TRUE iff process comprises a sensor,
BT_FALSE otherwise
returnValue Process::init ( double  _startTime = 0.0,
const DVector _xStart = emptyConstVector,
const DVector _uStart = emptyConstVector,
const DVector _pStart = emptyConstVector 
) [virtual]

Initializes the simulation with given start values and performs a number of consistency checks.

Parameters:
[in]_startTimeStart time of simulation.
[in]_xStartInitial value for differential states.
[in]_uStartInitial value for controls.
[in]_pStartInitial value for parameters.
Returns:
SUCCESSFUL_RETURN,
RET_PROCESS_INIT_FAILED,
RET_NO_DYNAMICSYSTEM_SPECIFIED,
RET_DIFFERENTIAL_STATE_DIMENSION_MISMATCH,
RET_ALGEBRAIC_STATE_DIMENSION_MISMATCH,
RET_CONTROL_DIMENSION_MISMATCH,
RET_PARAMETER_DIMENSION_MISMATCH,
RET_DISTURBANCE_DIMENSION_MISMATCH,
RET_WRONG_DISTURBANCE_HORIZON,
RET_INCOMPATIBLE_ACTUATOR_SAMPLING_TIME,
RET_INCOMPATIBLE_SENSOR_SAMPLING_TIME

Definition at line 353 of file process.cpp.

Initializes simulation with given start value for algebraic states.

Parameters:
[in]_xaStartInitial value for algebraic states.
Returns:
SUCCESSFUL_RETURN

Definition at line 345 of file process.cpp.

returnValue Process::initializeStartValues ( const DVector _xStart,
const DVector _xaStart = emptyConstVector 
)

Initializes simulation with given start values.

Parameters:
[in]_xStartInitial value for differential states.
[in]_xaStartInitial value for algebraic states.
Returns:
SUCCESSFUL_RETURN

Definition at line 330 of file process.cpp.

BooleanType Process::isContinuous ( uint  stageIdx = 0) const [inline]

Returns whether dynamic model (at given stage) is continuous in time.

Parameters:
[in]stageIdxIndex of stage.
Returns:
BT_TRUE iff dynamic model is continuous in time,
BT_FALSE otherwise
BooleanType Process::isDAE ( uint  stageIdx = 0) const [inline]

Returns whether dynamic model (at given stage) is a DAE.

Parameters:
[in]stageIdxIndex of stage.
Returns:
BT_TRUE iff dynamic model is a DAE,
BT_FALSE otherwise
BooleanType Process::isDiscretized ( uint  stageIdx = 0) const [inline]

Returns whether dynamic model (at given stage) is discretized in time.

Parameters:
[in]stageIdxIndex of stage.
Returns:
BT_TRUE iff dynamic model is discretized in time,
BT_FALSE otherwise
BooleanType Process::isODE ( uint  stageIdx = 0) const [inline]

Returns whether dynamic model (at given stage) is an ODE.

Parameters:
[in]stageIdxIndex of stage.
Returns:
BT_TRUE iff dynamic model is an ODE,
BT_FALSE otherwise
Process & Process::operator= ( const Process rhs)

Assignment operator (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 150 of file process.cpp.

returnValue Process::projectToComponents ( const VariablesGrid _x,
const DVector _xComponents,
VariablesGrid _output 
) const [protected]

Projects differential states to global components actually used.

Parameters:
[in]_xDifferential states.
[in]_xComponentsGlobal components of differential states actually used.
[out]_outputProjected differential states.
Returns:
SUCCESSFUL_RETURN

Definition at line 1028 of file process.cpp.

Customized function for plotting process variables.

Parameters:
[in]_frequencyFrequency determining at which time instants the window is to be plotted.
Returns:
SUCCESSFUL_RETURN

Reimplemented from Plotting.

Definition at line 678 of file process.cpp.

returnValue Process::run ( const VariablesGrid _u,
const VariablesGrid _p = emptyVariablesGrid 
) [virtual]

Initializes simulation and performs one step based on given inputs.

Parameters:
[in]_uTime-varying controls.
[in]_pTime-varying parameters.
Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_PROCESS_STEP_FAILED,
RET_PROCESS_STEP_FAILED_DISTURBANCE,
RET_INVALID_ARGUMENTS

Definition at line 632 of file process.cpp.

returnValue Process::run ( const VariablesGrid _u,
const DVector _p 
) [virtual]

Initializes simulation and performs one step based on given inputs.

Parameters:
[in]_uTime-varying controls.
[in]_pTime-constant parameters.
Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_PROCESS_STEP_FAILED,
RET_PROCESS_STEP_FAILED_DISTURBANCE,
RET_INVALID_ARGUMENTS

Definition at line 647 of file process.cpp.

returnValue Process::run ( double  startTime,
double  endTime,
const DVector _u,
const DVector _p = emptyConstVector 
) [virtual]

Initializes simulation and performs one step based on given inputs.

Parameters:
[in]startTimeStart time of simulation step.
[in]endTimeEnd time of simulation step.
[in]_uTime-constant controls.
[in]_pTime-constant parameters.
Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_PROCESS_STEP_FAILED,
RET_PROCESS_STEP_FAILED_DISTURBANCE,
RET_INVALID_ARGUMENTS

Definition at line 659 of file process.cpp.

returnValue Process::setActuator ( const Actuator _actuator)

Assigns new actuator to be used for simulation.

Parameters:
[in]_actuatorNew actuator.
Returns:
SUCCESSFUL_RETURN

Definition at line 254 of file process.cpp.

returnValue Process::setDynamicSystem ( const DynamicSystem _dynamicSystem,
IntegratorType  _integratorType = INT_UNKNOWN 
)

Assigns new dynamic system to be used for simulation. All previously assigned dynamic systems will be deleted.

Parameters:
[in]_dynamicSystemDynamic system to be used for simulation.
[in]_integratorTypeType of integrator to be used for simulation.
Returns:
SUCCESSFUL_RETURN

Definition at line 204 of file process.cpp.

returnValue Process::setProcessDisturbance ( const Curve _processDisturbance)

Assigns new process disturbance to be used for simulation.

Parameters:
[in]_processDisturbanceNew sensor.
Returns:
SUCCESSFUL_RETURN

Definition at line 289 of file process.cpp.

returnValue Process::setProcessDisturbance ( const VariablesGrid _processDisturbance)

Assigns new process disturbance to be used for simulation.

Parameters:
[in]_processDisturbanceNew sensor.
Returns:
SUCCESSFUL_RETURN,
RET_INVALID_ARGUMENTS

Definition at line 303 of file process.cpp.

returnValue Process::setProcessDisturbance ( const char *  _processDisturbance)

Assigns new process disturbance to be used for simulation.

Parameters:
[in]_processDisturbanceNew sensor.
Returns:
SUCCESSFUL_RETURN,
RET_FILE_CAN_NOT_BE_OPENED

Definition at line 316 of file process.cpp.

returnValue Process::setSensor ( const Sensor _sensor)

Assigns new sensor to be used for simulation.

Parameters:
[in]_sensorNew sensor.
Returns:
SUCCESSFUL_RETURN

Definition at line 271 of file process.cpp.

returnValue Process::setupLogging ( ) [protected, virtual]

Sets-up default logging information.

Returns:
SUCCESSFUL_RETURN

Reimplemented from Logging.

Definition at line 745 of file process.cpp.

returnValue Process::setupOptions ( ) [protected, virtual]

Sets-up default options.

Returns:
SUCCESSFUL_RETURN

Reimplemented from Options.

Definition at line 711 of file process.cpp.

returnValue Process::simulate ( const VariablesGrid _u,
const VariablesGrid _p,
const VariablesGrid _w 
) [protected]

Actually calls the integrator for performing a simulation. All simulated results are logged internally.

Parameters:
[in]_uTime-varying controls.
[in]_pTime-varying parameters.
[in]_wTime-varying disturbances.
Returns:
SUCCESSFUL_RETURN

Definition at line 827 of file process.cpp.

returnValue Process::step ( const VariablesGrid _u,
const VariablesGrid _p = emptyVariablesGrid 
) [virtual]

Performs one step of the simulation based on given inputs.

Parameters:
[in]_uTime-varying controls.
[in]_pTime-varying parameters.
Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_PROCESS_STEP_FAILED,
RET_PROCESS_STEP_FAILED_DISTURBANCE,
RET_INVALID_ARGUMENTS

Definition at line 508 of file process.cpp.

returnValue Process::step ( const VariablesGrid _u,
const DVector _p 
) [virtual]

Performs one step of the simulation based on given inputs.

Parameters:
[in]_uTime-varying controls.
[in]_pTime-constant parameters.
Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_PROCESS_STEP_FAILED,
RET_PROCESS_STEP_FAILED_DISTURBANCE,
RET_INVALID_ARGUMENTS

Definition at line 601 of file process.cpp.

returnValue Process::step ( double  startTime,
double  endTime,
const DVector _u,
const DVector _p = emptyConstVector 
) [virtual]

Performs one step of the simulation based on given inputs.

Parameters:
[in]startTimeStart time of simulation step.
[in]endTimeEnd time of simulation step.
[in]_uTime-constant controls.
[in]_pTime-constant parameters.
Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_PROCESS_STEP_FAILED,
RET_PROCESS_STEP_FAILED_DISTURBANCE,
RET_INVALID_ARGUMENTS

Definition at line 613 of file process.cpp.


Member Data Documentation

Actuator.

Definition at line 610 of file process.hpp.

Dynamic system to be used for simulation.

Definition at line 606 of file process.hpp.

Integration method to be used for simulation.

Definition at line 608 of file process.hpp.

Definition at line 619 of file process.hpp.

double Process::lastTime [protected]

Definition at line 616 of file process.hpp.

uint Process::nDynSys [protected]

Number of dynamic systems.

Definition at line 605 of file process.hpp.

Process disturbance block.

Definition at line 612 of file process.hpp.

Sensor* Process::sensor [protected]

Sensor.

Definition at line 611 of file process.hpp.

DVector Process::x [protected]

Definition at line 602 of file process.hpp.

DVector Process::xa [protected]

Definition at line 603 of file process.hpp.

Definition at line 614 of file process.hpp.


The documentation for this class was generated from the following files:


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 12:01:40