Simulation Modules

Base classes for all modules of the simulation loop.

Every block of the pymoskito simulation loop is implemented by subclassing SimulationModule.

class pymoskito.simulation_modules.SimulationModule(settings)[source]

Base unit of the simulation framework.

This class provides necessary functions like output calculation and holds all settings that can be accessed by the user. The public_settings are read by the SimulationInterface and the rendered by the GUI. All entries stated in this dictionary will be available as editable settings for the module. On initialization, a possibly modified (in terms of its values) version of this dict will be passed back to this class and is thenceforward available via the settings property.

The most important method is calc_output() which is called by the Simulator to retrieve this modules output.

Parameters:

settings (OrderedDict) –

Settings for this simulation module. These entries will be shown in the properties view and can be changed by the user. The important entries for this base class are:

tick_divider:

This property controls the frequency at which this Module is evaluated in the main simulation loop. If e.g. a value of 2 is provided, the module will be evaluated at every 2nd step that the solver makes. This feature comes in handy if discrete setups with different sample rates are simulated.

output info:

Dict holding information about the model output that are used in the GUI. For every item in the output array, a key for its index can be provided, under whose value another dict with the keys keys Name and Unit is expected. If available, these information are used to display reasonable names in the result view and to display the corresponding units for the result plots.

Note

The ‘tick_divider’ setting is ignored for the Solver and Model modules, whose tick_divider is fixed at 1.

Warns:

Do NOT use ‘.’ in the `output_info` name field.

abstract property public_settings

Dict of public settings.

This contains all settings that will be shown and can be edited in the GUI.

abstractmethod calc_output(self)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.

abstractmethod calc_output(input_vector)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.

abstract property public_settings

Dict of public settings.

This contains all settings that will be shown and can be edited in the GUI.

property step_size

The step size that this module is called with.

This parameter will be computed when the simulation is initialised and is based on the solver step size and the selected tick divider of the module.

property tick_divider

The module tick divider.

class pymoskito.simulation_modules.Controller(settings)[source]

Base class for controllers.

After subclassing, the method _control has to be implemented.

Parameters:

settings (OrderedDict) –

Dictionary holding the config options for this module. It must contain the following keys:

input_order:

The order of required derivatives from the trajectory generator.

input_type:

Source for the feedback calculation and one of the following: Model_State , Model_Output , Observer or Sensor .

abstractmethod _control(time, trajectory_values=None, feedforward_values=None, input_values=None, **kwargs)[source]

Placeholder for control law calculations.

For more sophisticated implementations overload calc_output() .

Parameters:
  • time (float) – Current time.

  • trajectory_values (array-like) – Desired values from the trajectory generator.

  • feedforward_values (array-like) – Output of feedforward block.

  • input_values (array-like) – The input values selected by input_type .

  • **kwargs – Placeholder for custom parameters.

Returns:

Control output.

Return type:

Array

calc_output(input_vector)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.

class pymoskito.simulation_modules.Disturbance(settings)[source]

Base class for all disturbance variants

abstractmethod _disturb(t, signal)[source]

Placeholder for disturbance calculations.

If the noise is to be dependent on the measured signal use its value to create the noise.

Parameters:
  • t (float) – Current simulation time.

  • signal (array-like float) – Values from the source selected by the input_signal property.

Returns:

Noise that will be mixed with a signal later on.

Return type:

array-like float

calc_output(input_dict)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.

class pymoskito.simulation_modules.Feedforward(settings)[source]

Base class for all feedforward implementations.

After subclassing, the method _feedforward has to be implemented.

abstractmethod _feedforward(time, trajectory_values)[source]

Placeholder for feedforward calculations.

Parameters:
  • time (float) – Current time.

  • trajectory_values (array-like) – Desired values from the trajectory generator.

Returns:

Feedforward output. This signal can be added to the controllers output via the ModelMixer and is also directly passed to the controller.

Return type:

Array

calc_output(input_dict)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.

property input_order

This field can be used to specify the derivative order of the reference trajectories that have to be provided by the trajectory generator.

class pymoskito.simulation_modules.Limiter(settings)[source]

Base class for all limiter variants

_limit(values)[source]

Placeholder for actual limit calculations.

Parameters:

values (array-like) – Values to limit.

Returns:

Limited output.

Return type:

Array

calc_output(input_dict)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.

class pymoskito.simulation_modules.Model(settings)[source]

Base class for all user defined system models in state-space form.

Parameters:

settings (OrderedDict) –

Dictionary holding the config options for this module. It must contain the following keys:

input_count:

The length of the input vector for this model.

state_count:

The length of the state vector for this model.

initial state:

The initial state vector for this model.

check_consistency(x)[source]

Check whether the assumptions, made in the modelling process are violated.

Parameters:

x – Current system state

Raises:

ModelException – If a violation is detected. This will stop the simulation process.

event_example(t, x)[source]

This must be a continuous function of time and state.

Sign changes of this function are considered to be an event where a reinitialisation of the integrator must be performed because of discontinuities in the system dynamics.

Parameters:
  • t – Current time.

  • x (array-like) – Current system state.

Returns:

Float

property initial_state

Return the initial state of the model.

register_event(event)[source]

Register switching events with the model

These events do help the solver if the system equations are discontinuous. For an example event function, see event_example.

abstractmethod state_function(t, x, args)[source]

Calculate the state derivatives of a system with state x at time t.

Parameters:
  • x (Array-like) – System state.

  • t (float) – System time.

  • args – Extra arguments.

Returns:

Temporal derivative of the system state at time t.

exception pymoskito.simulation_modules.ModelException[source]

Exception to be raised if the current system state violates modelling assumptions.

class pymoskito.simulation_modules.ModelMixer(settings)[source]
class pymoskito.simulation_modules.Observer(settings)[source]

Base class for observers.

After subclassing, the method _observe has to be implemented.

abstractmethod _observe(time, system_input, system_output)[source]

Placeholder for observer law.

Note

For integration of the observer dynamics, the attribute step_width should be used the use the correct step size.

Parameters:
  • time – Current time.

  • system_input – Current system input.

  • system_output – Current system output.

Returns:

Estimated system state

calc_output(input_vector)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.

class pymoskito.simulation_modules.ObserverMixer(settings)[source]
class pymoskito.simulation_modules.Sensor(settings)[source]

Base class for all sensor variants

_measure(value)[source]

Placeholder for measurement calculations.

One may reorder or remove state elements or introduce measurement delays here.

Parameters:

value (array-like float) – Values from the source selected by the input_signal property.

Returns:

‘Measured’ values.

Return type:

array-like float

calc_output(input_dict)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.

exception pymoskito.simulation_modules.SimulationException[source]
class pymoskito.simulation_modules.Solver(settings)[source]

Base Class for solver implementations.

After initialization, for every step in the simulation set_input will be called, followed by integrate.

Parameters:

settings (OrderedDict) –

Dictionary holding the config options for this module. It must contain the following keys:

start time:

Time stamp to start the simulation.

end time:

Time stamp to end the simulation.

measure rate:

How many results to store per second, e.g. a ‘measure rate’ of 500 will

result of 500 values per second, thus one value every 2 milliseconds.

calc_output(input_vector)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.

abstractmethod integrate(t)[source]

Perform numerical integration.

Parameters:

t (float) – New time up to which the model is to be integrated.

abstractmethod set_input(*args)[source]

Updates the inputs for the next integration step.

abstract property t

The current simulation time.

class pymoskito.simulation_modules.Trajectory(settings)[source]

Base class for all trajectory generators.

abstractmethod _desired_values(t)[source]

Placeholder for calculations of desired values.

Parameters:

t (float) – Time.

Returns:

Trajectory output. This should always be a two-dimensional array holding the components in to 0th and their derivatives in the 1th axis.

Return type:

Array

calc_output(input_vector)[source]

Main evaluation routine.

Every time the solver has made the amount of steps specified in tick_divider, this method will be called to compute the next output of the module. This is typically where the main logic of a module is implemented.