Public Member Functions | Protected Member Functions | Protected Attributes

Allows to run closed-loop simulations of dynamic systems. More...

#include <simulation_environment.hpp>

Inheritance diagram for SimulationEnvironment:
Inheritance graph
[legend]

List of all members.

Public Member Functions

returnValue getFeedbackControl (Curve &_feedbackControl) const
returnValue getFeedbackControl (VariablesGrid &_sampledFeedbackControl)
returnValue getFeedbackParameter (Curve &_feedbackParameter) const
returnValue getFeedbackParameter (VariablesGrid &_sampledFeedbackParameter)
uint getNP () const
uint getNU () const
uint getNumSteps () const
uint getNY () const
returnValue getProcessAlgebraicStates (VariablesGrid &_algStates)
returnValue getProcessDifferentialStates (VariablesGrid &_diffStates)
returnValue getProcessIntermediateStates (VariablesGrid &_interStates)
returnValue getProcessOutput (Curve &_processOutput) const
returnValue getSampledProcessOutput (VariablesGrid &_sampledProcessOutput)
returnValue init (const DVector &x0_, const DVector &p_=emptyConstVector)
returnValue initializeAlgebraicStates (const VariablesGrid &_xa_init)
returnValue initializeAlgebraicStates (const char *fileName)
SimulationEnvironmentoperator= (const SimulationEnvironment &rhs)
returnValue run ()
returnValue setController (Controller &_controller)
returnValue setProcess (Process &_process)
 SimulationEnvironment ()
 SimulationEnvironment (double _startTime, double _endTime, Process &_process, Controller &_controller)
 SimulationEnvironment (const SimulationEnvironment &rhs)
returnValue step ()
returnValue step (double intermediateTime)
virtual ~SimulationEnvironment ()

Protected Member Functions

double determineComputationalDelay (double controllerRuntime) const
virtual returnValue setupLogging ()
virtual returnValue setupOptions ()

Protected Attributes

Controllercontroller
double endTime
Curve feedbackControl
Curve feedbackParameter
uint nSteps
Processprocess
Curve processOutput
SimulationClock simulationClock
double startTime

Detailed Description

Allows to run closed-loop simulations of dynamic systems.

The class Simulation Environment is designed to run closed-loop simulations of dynamic systems.

In a standard setup the Simulation Environment consists of a Process and a Controller that are connected by signals. These two main members can be specified within the constructor or set afterwards by using the methods "setController" and "setProcess" , respectively.

A simulation has to be initialized by providing the initial value of the differential states of the dynamic system to be simulated. Afterwards, the simulation can be run at once or stepped until a given intermediate time.

Author:
Hans Joachim Ferreau, Boris Houska

Definition at line 72 of file simulation_environment.hpp.


Constructor & Destructor Documentation

Default constructor.

Definition at line 49 of file simulation_environment.cpp.

SimulationEnvironment::SimulationEnvironment ( double  _startTime,
double  _endTime,
Process _process,
Controller _controller 
)

Constructor which takes the name of the block and the sampling time.

Parameters:
[in]_startTimeStart time of the simulation.
[in]_endTimeEnd time of the simulation.
[in]_processProcess used for simulating the dynamic system.
[in]_controllerController used for controlling the dynamic system.
Note:
Only pointers to Process and Controller are stored!

Definition at line 66 of file simulation_environment.cpp.

Copy constructor (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 95 of file simulation_environment.cpp.

Destructor.

Definition at line 120 of file simulation_environment.cpp.


Member Function Documentation

double SimulationEnvironment::determineComputationalDelay ( double  controllerRuntime) const [protected]

Returns computational delay used for simulation based on the actual real controller runtime and the options set by the user.

Parameters:
[in]controllerRuntimeReal controller runtime.
Returns:
Computational delay used for simulation

Definition at line 509 of file simulation_environment.cpp.

returnValue SimulationEnvironment::getFeedbackControl ( Curve _feedbackControl) const [inline]

Returns feedback control signals of the controller over the whole simulation.

Parameters:
[out]_feedbackControlFeedback control signals of the controller.
Returns:
SUCCESSFUL_RETURN
returnValue SimulationEnvironment::getFeedbackControl ( VariablesGrid _sampledFeedbackControl) [inline]

Returns feedback control signals of the controller over the whole simulation.

Parameters:
[out]_sampledFeedbackControlFeedback control signals of the controller.
Returns:
SUCCESSFUL_RETURN
returnValue SimulationEnvironment::getFeedbackParameter ( Curve _feedbackParameter) const [inline]

Returns feedback parameter signals of the controller over the whole simulation.

Parameters:
[out]_feedbackParameterFeedback parameter signals of the controller.
Returns:
SUCCESSFUL_RETURN
returnValue SimulationEnvironment::getFeedbackParameter ( VariablesGrid _sampledFeedbackParameter) [inline]

Returns feedback parameter signals of the controller over the whole simulation.

Parameters:
[out]_sampledFeedbackParameterFeedback parameter signals of the controller.
Returns:
SUCCESSFUL_RETURN
uint SimulationEnvironment::getNP ( ) const [inline]

Returns number of feedback parameters.

Returns:
Number of feedback parameters
uint SimulationEnvironment::getNU ( ) const [inline]

Returns number of feedback controls.

Returns:
Number of feedback controls

Returns current number of simulation steps.

Returns:
Current number of simulation steps
uint SimulationEnvironment::getNY ( ) const [inline]

Returns number of process outputs.

Returns:
Number of process outputs

Returns algebraic states of the process over the whole simulation.

Parameters:
[out]_algStatesAlgebraic states of the process.
Returns:
SUCCESSFUL_RETURN

Returns differential states of the process over the whole simulation.

Parameters:
[out]_diffStatesDifferential states of the process.
Returns:
SUCCESSFUL_RETURN

Returns intermediate states of the process over the whole simulation.

Parameters:
[out]_interStatesIntermediate states of the process.
Returns:
SUCCESSFUL_RETURN
returnValue SimulationEnvironment::getProcessOutput ( Curve _processOutput) const [inline]

Returns continuous output of the process.

Parameters:
[out]_processOutputContinuous output of the process.
Returns:
SUCCESSFUL_RETURN

Returns output of the process at sampling instants.

Parameters:
[out]_sampledProcessOutputSampled output of the process.
Returns:
SUCCESSFUL_RETURN

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

Parameters:
[in]x0_Initial value for differential states.
[in]p_Initial value for parameters.
Returns:
SUCCESSFUL_RETURN,
RET_ENVIRONMENT_INIT_FAILED,
RET_NO_CONTROLLER_SPECIFIED,
RET_NO_PROCESS_SPECIFIED,
RET_BLOCK_DIMENSION_MISMATCH

Definition at line 220 of file simulation_environment.cpp.

Initializes algebraic states of the process.

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

Definition at line 195 of file simulation_environment.cpp.

Initializes algebraic states of the process from data file.

Parameters:
[in]fileNameName of file containing initial value for algebraic states.
Returns:
SUCCESSFUL_RETURN,
RET_FILE_CAN_NOT_BE_OPENED

Definition at line 207 of file simulation_environment.cpp.

SimulationEnvironment & SimulationEnvironment::operator= ( const SimulationEnvironment rhs)

Assignment Operator (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 125 of file simulation_environment.cpp.

Runs the complete simulation.

Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_ENVIRONMENT_STEP_FAILED,
RET_COMPUTATIONAL_DELAY_TOO_BIG

Definition at line 477 of file simulation_environment.cpp.

Assigns new controller block to be used for simulation.

Parameters:
[in]_controllerNew controller block.
Note:
Only a pointer is stored!
Returns:
SUCCESSFUL_RETURN

Definition at line 176 of file simulation_environment.cpp.

Assigns new process block to be used for simulation.

Parameters:
[in]_processNew process block.
Note:
Only a pointer is stored!
Returns:
SUCCESSFUL_RETURN

Definition at line 158 of file simulation_environment.cpp.

Sets-up default logging information.

Returns:
SUCCESSFUL_RETURN

Reimplemented from Logging.

Definition at line 497 of file simulation_environment.cpp.

Sets-up default options.

Returns:
SUCCESSFUL_RETURN

Reimplemented from Options.

Definition at line 487 of file simulation_environment.cpp.

Performs next step of the simulation.

Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_ENVIRONMENT_STEP_FAILED,
RET_COMPUTATIONAL_DELAY_TOO_BIG

Definition at line 304 of file simulation_environment.cpp.

returnValue SimulationEnvironment::step ( double  intermediateTime)

Performs next steps of the simulation until given intermediate time.

Parameters:
[in]intermediateTimeIntermediate time.
Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_ENVIRONMENT_STEP_FAILED,
RET_COMPUTATIONAL_DELAY_TOO_BIG,
RET_INVALID_ARGUMENTS

Definition at line 455 of file simulation_environment.cpp.


Member Data Documentation

Pointer to Controller used for controlling the dynamic system.

Definition at line 359 of file simulation_environment.hpp.

double SimulationEnvironment::endTime [protected]

End time of the simulation.

Definition at line 356 of file simulation_environment.hpp.

Curve storing control signals from the Controller during the whole simulation.

Definition at line 364 of file simulation_environment.hpp.

Curve storing parameter signals from the Controller during the whole simulation.

Definition at line 365 of file simulation_environment.hpp.

Number of simulation steps (loops) that have been performed.

Definition at line 367 of file simulation_environment.hpp.

Pointer to Process used for simulating the dynamic system.

Definition at line 358 of file simulation_environment.hpp.

Curve storing output of the Process during the whole simulation.

Definition at line 363 of file simulation_environment.hpp.

Clock for managing the simulation time.

Definition at line 361 of file simulation_environment.hpp.

Start time of the simulation.

Definition at line 355 of file simulation_environment.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