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_settingsare read by theSimulationInterfaceand 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 thesettingsproperty.The most important method is
calc_output()which is called by theSimulatorto 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:
See the property.
- 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.
- 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.
- abstract 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.
- abstract 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_width¶
The discrete step width that this module is called with.
This parameter will be set when the simulation is initialised and is based on the solver step size and the selected tick divider of the module.
- property tick_divider¶
Simulation 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.
Note
This setting is ignored for the Solver module, whose tick_divider is fixed at 1.
- 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 .
- abstract _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.Disturbance(settings)[source]¶
Base class for all disturbance variants
- abstract _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_signalproperty.- Returns:
Noise that will be mixed with a signal later on.
- Return type:
array-like float
- class pymoskito.simulation_modules.Feedforward(settings)[source]¶
Base class for all feedforward implementations.
After subclassing, the method _feedforward has to be implemented.
- abstract _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
ModelMixerand 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
- 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.
- property initial_state¶
Return the initial state of the model.
- 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
- exception pymoskito.simulation_modules.ModelException[source]¶
Exception to be raised if the current system state violates modelling assumptions.
- class pymoskito.simulation_modules.Observer(settings)[source]¶
Base class for observers.
After subclassing, the method _observe has to be implemented.
- abstract _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
- 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_signalproperty.- Returns:
‘Measured’ values.
- Return type:
array-like float
- 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.
- 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 integrate(t)[source]¶
Perform numerical integration.
- Parameters:
t (float) – New time up to which the model is to be integrated.
- abstract property t¶
The current simulation time.
- class pymoskito.simulation_modules.Trajectory(settings)[source]¶
Base class for all trajectory generators.