Public Member Functions | Protected Member Functions | Protected Attributes | List of all members

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

#include <simulation_environment.hpp>

Inheritance diagram for SimulationEnvironment:
Inheritance graph
[legend]

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 ()
 
- Public Member Functions inherited from SimulationBlock
BlockName getName () const
 
double getSamplingTime () const
 
BooleanType isDefined () const
 
SimulationBlockoperator= (const SimulationBlock &rhs)
 
returnValue setName (BlockName _name)
 
returnValue setSamplingTime (double _samplingTime)
 
 SimulationBlock ()
 
 SimulationBlock (BlockName _name, double _samplingTime=DEFAULT_SAMPLING_TIME)
 
 SimulationBlock (const SimulationBlock &rhs)
 
virtual ~SimulationBlock ()
 
- Public Member Functions inherited from UserInteraction
virtual int addPlotWindow (PlotWindow &_window)
 
virtual int operator<< (PlotWindow &_window)
 
virtual int operator<< (LogRecord &_record)
 
UserInteractionoperator= (const UserInteraction &rhs)
 
 UserInteraction ()
 
 UserInteraction (const UserInteraction &rhs)
 
virtual ~UserInteraction ()
 
- Public Member Functions inherited from Options
returnValue addOptionsList ()
 
returnValue ensureConsistency ()
 
returnValue ensureConsistency ()
 
returnValue get (OptionsName name, int &value) const
 
returnValue get (OptionsName name, double &value) const
 
returnValue get (OptionsName name, std::string &value) const
 
returnValue get (uint idx, OptionsName name, int &value) const
 
returnValue get (uint idx, OptionsName name, double &value) const
 
returnValue get (uint idx, OptionsName name, std::string &value) const
 
uint getNumOptionsLists () const
 
Options getOptions (uint idx) const
 
Optionsoperator= (const Options &rhs)
 
Optionsoperator= (const Options &rhs)
 
 Options ()
 
 Options ()
 
 Options (const Options &rhs)
 
 Options (const Options &rhs)
 
 Options ()
 
 Options (const OptionsList &_optionsList)
 
returnValue print () const
 
returnValue print () const
 
returnValue printOptionsList () const
 
returnValue printOptionsList (uint idx) const
 
returnValue set (OptionsName name, int value)
 
returnValue set (OptionsName name, double value)
 
returnValue set (OptionsName name, const std::string &value)
 
returnValue set (uint idx, OptionsName name, int value)
 
returnValue set (uint idx, OptionsName name, double value)
 
returnValue set (uint idx, OptionsName name, const std::string &value)
 
returnValue setOptions (const Options &arg)
 
returnValue setOptions (uint idx, const Options &arg)
 
returnValue setToDefault ()
 
returnValue setToDefault ()
 
returnValue setToFast ()
 
returnValue setToFast ()
 
returnValue setToMPC ()
 
returnValue setToReliable ()
 
returnValue setToReliable ()
 
 ~Options ()
 
 ~Options ()
 
virtual ~Options ()
 
- Public Member Functions inherited from Logging
int addLogRecord (LogRecord &record)
 
returnValue getAll (LogName _name, MatrixVariablesGrid &values) const
 
returnValue getFirst (LogName _name, DMatrix &firstValue) const
 
returnValue getFirst (LogName _name, VariablesGrid &firstValue) const
 
returnValue getLast (LogName _name, DMatrix &lastValue) const
 
returnValue getLast (LogName _name, VariablesGrid &lastValue) const
 
returnValue getLogRecord (LogRecord &_record) const
 
uint getNumLogRecords () const
 
 Logging ()
 
int operator<< (LogRecord &record)
 
returnValue printLoggingInfo () const
 
returnValue printNumDoubles () const
 
returnValue setAll (LogName _name, const MatrixVariablesGrid &values)
 
returnValue setLast (LogName _name, const DMatrix &value, double time=-INFTY)
 
returnValue setLast (LogName _name, VariablesGrid &value, double time=-INFTY)
 
returnValue updateLogRecord (LogRecord &_record) const
 
virtual ~Logging ()
 
- Public Member Functions inherited from Plotting
int addPlotWindow (PlotWindow &_window)
 
uint getNumPlotWindows () const
 
returnValue getPlotWindow (uint idx, PlotWindow &_window) const
 
returnValue getPlotWindow (PlotWindow &_window) const
 
int operator<< (PlotWindow &_window)
 
Plottingoperator= (const Plotting &rhs)
 
virtual returnValue plot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
 Plotting ()
 
 Plotting (const Plotting &rhs)
 
virtual returnValue replot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
virtual ~Plotting ()
 

Protected Member Functions

double determineComputationalDelay (double controllerRuntime) const
 
virtual returnValue setupLogging ()
 
virtual returnValue setupOptions ()
 
- Protected Member Functions inherited from UserInteraction
virtual returnValue getPlotDataFromMemberLoggings (PlotWindow &_window) const
 
BlockStatus getStatus () const
 
returnValue setStatus (BlockStatus _status)
 
- Protected Member Functions inherited from Options
returnValue addOption (OptionsName name, int value)
 
returnValue addOption (OptionsName name, double value)
 
returnValue addOption (OptionsName name, const std::string &value)
 
returnValue addOption (uint idx, OptionsName name, int value)
 
returnValue addOption (uint idx, OptionsName name, double value)
 
returnValue addOption (uint idx, OptionsName name, const std::string &value)
 
returnValue clearOptionsList ()
 
returnValue copy (const Options &rhs)
 
returnValue copy (const Options &rhs)
 
returnValue declareOptionsUnchanged ()
 
returnValue declareOptionsUnchanged (uint idx)
 
BooleanType haveOptionsChanged () const
 
BooleanType haveOptionsChanged (uint idx) const
 

Protected Attributes

Controllercontroller
 
double endTime
 
Curve feedbackControl
 
Curve feedbackParameter
 
uint nSteps
 
Processprocess
 
Curve processOutput
 
SimulationClock simulationClock
 
double startTime
 
- Protected Attributes inherited from SimulationBlock
BlockName name
 
RealClock realClock
 
double samplingTime
 
- Protected Attributes inherited from UserInteraction
BlockStatus status
 
- Protected Attributes inherited from Options
std::vector< OptionsListlists
 
- Protected Attributes inherited from Logging
std::vector< LogRecordlogCollection
 
int logIdx
 
- Protected Attributes inherited from Plotting
PlotCollection plotCollection
 

Additional Inherited Members

- Public Attributes inherited from Options
real_t boundRelaxation
 
real_t boundTolerance
 
int dropBoundPriority
 
int_t dropBoundPriority
 
int dropEqConPriority
 
int_t dropEqConPriority
 
int dropIneqConPriority
 
int_t dropIneqConPriority
 
int enableCholeskyRefactorisation
 
int_t enableCholeskyRefactorisation
 
int enableDriftCorrection
 
int_t enableDriftCorrection
 
BooleanType enableDropInfeasibles
 
BooleanType enableEqualities
 
BooleanType enableFarBounds
 
BooleanType enableFlippingBounds
 
BooleanType enableFullLITests
 
BooleanType enableInertiaCorrection
 
BooleanType enableNZCTests
 
BooleanType enableRamping
 
BooleanType enableRegularisation
 
real_t epsDen
 
real_t epsFlipping
 
real_t epsIterRef
 
real_t epsLITests
 
real_t epsNum
 
real_t epsNZCTests
 
real_t epsRegularisation
 
real_t finalRamping
 
real_t growFarBounds
 
real_t initialFarBounds
 
real_t initialRamping
 
SubjectToStatus initialStatusBounds
 
real_t maxDualJump
 
real_t maxPrimalJump
 
int numRefinementSteps
 
int_t numRefinementSteps
 
int numRegularisationSteps
 
int_t numRegularisationSteps
 
PrintLevel printLevel
 
real_t rcondSMin
 
real_t terminationTolerance
 

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

BEGIN_NAMESPACE_ACADO SimulationEnvironment::SimulationEnvironment ( )

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.

@param[in] _startTime               Start time of the simulation.
@param[in] _endTime                 End time of the simulation.
@param[in] _process                 Process used for simulating the dynamic system.
@param[in] _controller              Controller used for controlling the dynamic system.

\note Only pointers to Process and Controller are stored!

Definition at line 66 of file simulation_environment.cpp.

SimulationEnvironment::SimulationEnvironment ( const SimulationEnvironment rhs)

Copy constructor (deep copy).

@param[in] rhs      Right-hand side object.

Definition at line 95 of file simulation_environment.cpp.

SimulationEnvironment::~SimulationEnvironment ( )
virtual

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.

@param[out]  _feedbackControl                       Feedback 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.

@param[out]  _sampledFeedbackControl        Feedback 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.

@param[out]  _feedbackParameter                     Feedback 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.

@param[out]  _sampledFeedbackParameter      Feedback parameter signals of the controller.
Returns
SUCCESSFUL_RETURN
uint SimulationEnvironment::getNP ( ) const
inline

Returns number of feedback parameters.

\return Number of feedback parameters
uint SimulationEnvironment::getNU ( ) const
inline

Returns number of feedback controls.

\return Number of feedback controls
uint SimulationEnvironment::getNumSteps ( ) const
inline

Returns current number of simulation steps.

\return Current number of simulation steps
uint SimulationEnvironment::getNY ( ) const
inline

Returns number of process outputs.

\return Number of process outputs
returnValue SimulationEnvironment::getProcessAlgebraicStates ( VariablesGrid _algStates)
inline

Returns algebraic states of the process over the whole simulation.

@param[out]  _algStates                             Algebraic states of the process.
Returns
SUCCESSFUL_RETURN
returnValue SimulationEnvironment::getProcessDifferentialStates ( VariablesGrid _diffStates)
inline

Returns differential states of the process over the whole simulation.

@param[out]  _diffStates                    Differential states of the process.
Returns
SUCCESSFUL_RETURN
returnValue SimulationEnvironment::getProcessIntermediateStates ( VariablesGrid _interStates)
inline

Returns intermediate states of the process over the whole simulation.

@param[out]  _interStates                   Intermediate states of the process.
Returns
SUCCESSFUL_RETURN
returnValue SimulationEnvironment::getProcessOutput ( Curve _processOutput) const
inline

Returns continuous output of the process.

@param[out]  _processOutput                 Continuous output of the process.
Returns
SUCCESSFUL_RETURN
returnValue SimulationEnvironment::getSampledProcessOutput ( VariablesGrid _sampledProcessOutput)
inline

Returns output of the process at sampling instants.

@param[out]  _sampledProcessOutput  Sampled output of the process.
Returns
SUCCESSFUL_RETURN
returnValue SimulationEnvironment::init ( const DVector x0_,
const DVector p_ = emptyConstVector 
)

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.

returnValue SimulationEnvironment::initializeAlgebraicStates ( const VariablesGrid _xa_init)

Initializes algebraic states of the process.

@param[in]  _xa_init        Initial value for algebraic states.
Returns
SUCCESSFUL_RETURN

Definition at line 195 of file simulation_environment.cpp.

returnValue SimulationEnvironment::initializeAlgebraicStates ( const char *  fileName)

Initializes algebraic states of the process from data file.

@param[in]  fileName        Name 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).

@param[in] rhs      Right-hand side object.

Definition at line 125 of file simulation_environment.cpp.

returnValue SimulationEnvironment::run ( )

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.

returnValue SimulationEnvironment::setController ( Controller _controller)

Assigns new controller block to be used for simulation.

@param[in]  _controller             New controller block.

\note Only a pointer is stored!
Returns
SUCCESSFUL_RETURN

Definition at line 176 of file simulation_environment.cpp.

returnValue SimulationEnvironment::setProcess ( Process _process)

Assigns new process block to be used for simulation.

@param[in]  _process                New process block.

\note Only a pointer is stored!
Returns
SUCCESSFUL_RETURN

Definition at line 158 of file simulation_environment.cpp.

returnValue SimulationEnvironment::setupLogging ( )
protectedvirtual

Sets-up default logging information.

Returns
SUCCESSFUL_RETURN

Reimplemented from Logging.

Definition at line 497 of file simulation_environment.cpp.

returnValue SimulationEnvironment::setupOptions ( )
protectedvirtual

Sets-up default options.

Returns
SUCCESSFUL_RETURN

Reimplemented from Options.

Definition at line 487 of file simulation_environment.cpp.

returnValue SimulationEnvironment::step ( )

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.

@param[in]  intermediateTime                Intermediate 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

Controller* SimulationEnvironment::controller
protected

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 SimulationEnvironment::feedbackControl
protected

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

Definition at line 364 of file simulation_environment.hpp.

Curve SimulationEnvironment::feedbackParameter
protected

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

Definition at line 365 of file simulation_environment.hpp.

uint SimulationEnvironment::nSteps
protected

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

Definition at line 367 of file simulation_environment.hpp.

Process* SimulationEnvironment::process
protected

Pointer to Process used for simulating the dynamic system.

Definition at line 358 of file simulation_environment.hpp.

Curve SimulationEnvironment::processOutput
protected

Curve storing output of the Process during the whole simulation.

Definition at line 363 of file simulation_environment.hpp.

SimulationClock SimulationEnvironment::simulationClock
protected

Clock for managing the simulation time.

Definition at line 361 of file simulation_environment.hpp.

double SimulationEnvironment::startTime
protected

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 Mon Jun 10 2019 12:35:26