Simulation Modules

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

Smallest unit pof 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 changeable 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:

output info:
Dict holding an information dictionaries with keys Name and Unit for each element in the output data. If available, these information are used to display reasonable names in the result view and to display the corresponding units for the result plots.
Warn:
Do NOT use ‘.’ in the output_info name field.
exception pymoskito.simulation_modules.SimulationException[source]
class pymoskito.simulation_modules.Trajectory(settings)[source]

Base class for all trajectory generators

_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
class pymoskito.simulation_modules.Feedforward(settings)[source]

Base class for all feedforward implementations

_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

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

Base class for controllers.

Parameters:settings (dict) –

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: system_state , system_output , Observer or Sensor .
_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

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
class pymoskito.simulation_modules.ModelMixer(settings)[source]
class pymoskito.simulation_modules.Model(settings)[source]

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

Parameters:settings (dict) –

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.
initial_state

Return the initial state of the system.

root_function(x)[source]

Check whether a reinitialisation of the integrator should be performed.

This can be the case if there are discontinuities in the system dynamics such as switching.

Parameters:x (array-like) – Current system state.
Returns:
  • bool: True if reset is advised.
  • array-like: State to continue with.
Return type:tuple
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.
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.Solver(settings)[source]

Base Class for solver implementations

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

Base class for all disturbance variants

_disturb(value)[source]

Placeholder for disturbance calculations.

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

Parameters:value (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
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
class pymoskito.simulation_modules.ObserverMixer(settings)[source]
class pymoskito.simulation_modules.Observer(settings)[source]

Base class for observers

_observe(time, system_input, system_output)[source]

Placeholder for observer law.

Parameters:
  • time – Current time.
  • system_input – Current system input.
  • system_output – Current system output.
Returns:

Estimated system state