Welcome to PyMoskito’s documentation!¶
Contents:
Introduction¶
What is PyMoskito ?¶
PyMoskito aims to be a useful tool for students and researchers in the field of control theory that performs repetitive task occurring in modelling as well as controller and observer design.
The toolbox consists of two parts: Part one -the core- is a modular simulation circuit whose parts (Model, Controller and many more) can be easily fitted to one’s personal needs by using one of the “ready to go” variants or deriving from the more powerful base classes.
To configure this simulation loop and to analyse its results, part two -the frontend- comes into play. The graphical user interfaces not only allows one to accurately tune the parameters of each part of the simulation but also allows to automate simulation runs e.g. to simulate different combinations of modules or parameters. This batch-like interface is feed by human readable yaml files which make it easy to store and reproduce simulated setups. Furthermore PyMoskito offers possibilities to run postprocessing on the generated results and easily lets you create plots for step responses.
What is PyMoskito not ?¶
Although the simulation loop is quite flexible it is not a complete block oriented simulation environment for model based-design but ideas for the development in this direction are always appreciated.
Installation¶
General Options¶
At the command line:
$ pip install pymoskito
Or, if you have virtualenvwrapper installed:
$ mkvirtualenv pymoskito
$ pip install pymoskito
From the repository:
$ git clone https://github.com/cklb/pymoskito
$ python setup.py install
For Windows¶
PyMoskito depends on Qt5 and VTK .
Qt5 is already included in the most python distributions, to have an easy start we recommend to use Winpython .
The wheel for the VTK package (Version >= 7) can be obtained from http://www.lfd.uci.edu/~gohlke/pythonlibs/#vtk . It can be installed using the Winpython Control Panel or directly via:
$ pip install VTK-VERSION_NAME_HERE.whl
from your winpython shell.
Troubleshooting¶
Missing dependencies (windows)
If the provided packages on your system are to old, pip may feel obligated to update them. Since the majority of packages now provide ready to use wheels for windows on pypi this should work automatically. If for some reason this process fails, you will most certainly find an appropriate wheel here . After downloading just navigate your shell into the directory and call:
$ pip install PACKAGE_NAME.whl
to install it.
Missing vtk libraries (linux)
If importing vtk
fails with something similar to:
>>> Import Error: vtkIOAMRPython module not found
then look at the output of:
$ ldd PATH/TO/SITE-PKGS/vtk/vtkIOAMRPython.so
to see which libs are missing.
Tutorials¶
Below you will find some lessons on different aspects of the toolbox, sorted from basic to expert level.
Beginner:
Beginners Tutorial¶
Welcome to the PyMoskito Tutorial! It is intended to introduce new users to the toolbox. For more detailed descriptions, please see the Users Guide or the Modules Reference.
Within this tutorial, an inverse pendulum on cart will be simulated and stabilized. With the help of PyMoskito, the model as well as the controller will be tested by simulating the open and closed control loop.
All code is written in Python. If you want to refresh or expand your knowledge about this language, see e.g. the Python Tutorial.
PyMoskito’s Signal Diagram¶
PyMoskito simulates the control loop as shown in Fig. 1. This tutorial will focus on the part highlighted in blue, since these modules are essential to run the toolbox.

The control loop implemented by PyMoskito
Every block in this diagram represents a configurable part of the control loop that is implemented as a generic base class. By deriving from these base classes, it is easy to make sure that implemented classes work well within the context of the toolbox.
From the highlighted classes, the trajectory generator and the model mixer are considered reusable, therefore PyMoskito provides these classes ready to go. On the other hand, the model and the controller are determined by the specific system and have to be implemented to suit your problem. If you would like to implement one of the nonhighlighted classes, see the Users Guide or other Tutorials for help.
Next up the system, used for implementation is introduced.
A Pendulum on Cart¶
A pendulum is fixed on a cart, which can move in the horizontal direction.
The cart has a mass .
The friction between the cart and the surface causes a frictional force
, in opposite direction to the movement of the cart.
The pendulum has a mass
, a moment of intertia
, a length
and an angle of deflection
.
The friction in the joint where the pendulum is mounted on the cart causes a frictional torque
,
in opposite direction to the rotational speed of the pendululm.
The system is illustrated in Fig. 2.
The task is to control the position of the cart
and to stabilize the pendulum in its downside position.
The possibility of stabilizing the pendulum in its upside position is not implemented in this tutorial.
Actuating variable is the force
.
With the state vector
the model equations are given by
The cart’s position
is chosen as output of the system. With this model given, the next step is to implement a class containing these equations.
Implementing a Model¶
At first, a new class derived from the abstract class Model
is necessary.
Its basic functions will be calculating the state derivatives and the output from the model parameters, the current state and the input values.
Create a folder within a path of your choice. All files created during this tutorial need to be stored here. Create a file called:
model.py
With the first lines of code, import the library NumPy, the OrderedDictionary class and PyMoskito itself:
1 2 3 4 5 6 7 | # -*- coding: utf-8 -*-
from collections import OrderedDict
import numpy as np
import pymoskito as pm
|
Derive your class from Model
.
Next, create an OrderedDict
called public_settings
.
All entries in this dictionary will be accessible in the graphical interface of PyMoskito during runtime.
While you have the freedom to name these entries as you like,
the entry initial state
is obligatory and must contain the initial state vector.
All values entered will be the initial values for the model parameters:
9 10 11 12 13 14 15 16 17 18 | class PendulumModel(pm.Model):
public_settings = OrderedDict([("initial state", [0, 180.0, 0, 0]),
("cart mass", 4.3), # [kg]
("cart friction", 10), # [Ns/m]
("pendulum mass", 0.32), # [kg]
("pendulum inertia", 0.07), # [kg*m^2]
("pendulum friction", 0.03), # [Nms]
("pendulum length", 0.35), # [m]
("gravity", 9.81)]) # [m/s^2]
|
Within the constructor, you must define the number of inputs and states.
Do so by storing these values in settings as seen in lines 24
and 25
.
Adding output information as seen in line 26
is optional,
this will make it easier to distinguish between several outputs of bigger systems.
It is obligatory to call the constructor of the base class at the end.
The constructor’s argument settings
is a copy of public_settings
with all changes the user made in the interface:
20 21 22 23 24 25 26 27 28 29 30 31 | def __init__(self, settings):
# conversion from degree to radiant
settings["initial state"][1] = np.deg2rad(settings["initial state"][1])
settings["initial state"][3] = np.deg2rad(settings["initial state"][3])
# add specific "private" settings
settings.update(state_count=4)
settings.update(input_count=1)
settings.update({"output_info": {0: {"Name": "cart position",
"Unit": "m"}}})
pm.Model.__init__(self, settings)
|
The calculation of the state derivatives takes place in a method
that returns the results as an array.
The method’s parameters are the current time t
, the current state vector x
,
and the parameter args
. The later is free to be defined as you need it,
in this case it will be the force F
as the model input.
To keep the model equations compact and readable,
it is recommended to store the model values in variables with short names:
33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 | def state_function(self, t, x, args):
# definitional
s = x[0]
phi = x[1]
ds = x[2]
dphi = x[3]
F = args[0]
# shortcuts for readability
M = self._settings["cart mass"]
D = self._settings["cart friction"]
m = self._settings["pendulum mass"]
J = self._settings["pendulum inertia"]
d = self._settings["pendulum friction"]
l = self._settings["pendulum length"]
g = self._settings["gravity"]
dx1 = ds
dx2 = dphi
dx3 = ((J * F
- J * D * ds
- m * l * J * dphi ** 2 * np.sin(phi)
+ (m * l) ** 2 * g * np.sin(phi) * np.cos(phi)
- m * l * d * dphi * np.cos(phi))
/ ((M + m) * J - (m * l * np.cos(phi)) ** 2))
dx4 = ((m * l * np.cos(phi) * F
- m * l * D * ds * np.cos(phi)
- (m * l * dphi) ** 2 * np.cos(phi) * np.sin(phi)
+ (M + m) * m * l * g * np.sin(phi) - (M + m) * d * dphi)
/ ((M + m) * J - (m * l * np.cos(phi)) ** 2))
dx = np.array([dx1, dx2, dx3, dx4])
return dx
|
The output of the system is calculated in a method with the current state vector as parameter.
Returning the results as an array as previously would be possible.
But in this case, the output is simply the position s
of the cart,
so extracting it from the state vector and returning it as a scalar is sufficient
:
68 69 | def calc_output(self, input_vector):
return input_vector[0]
|
This now fully implemented model class has a yet unknown behavior. To test it, the next step is to start PyMoskito for simulation purposes.
Starting the Program¶
For PyMoskito to start, an application needs to launch the toolbox and execute it. To do so, create a file in the same directory as the model and name it:
main.py
Copy the following code into your main file:
1 2 3 4 5 6 7 8 9 10 11 12 13 | # -*- coding: utf-8 -*-
import pymoskito as pm
# import custom modules
import model
if __name__ == '__main__':
# register model
pm.register_simulation_module(pm.Model, model.PendulumModel)
# start the program
pm.run()
|
Note the import
command in line 5
,
which includes the earlier implemented model file in the application.
The command in line 10
registers the model to the toolbox.
This lets PyMoskito know that this module is available
and adds it to the eligible options in the interface.
Line 13
finally starts our application.
Use the command line to navigate to the directory of the main file and the model file and start the toolbox with the command:
$ python main.py
The upstarting interface of PyMoskito gives you the possibility to test the implemented model in the next step.
Testing the Model¶
Choose initial states that make the prediction of the system’s reaction easy and compare them with the simulation results. After successfully starting the program, you will see the interface of the toolbox as shown in Fig. 3.
Within the Properties Window (1), double clicking on a value (all None
by default)
activates a drop down menu.
Clicking again presents all eligible options.
One of these options now is PendulumModel
,
since it was registered to PyMoskito earlier.
Choose it now and press enter to confirm your choice.
By clicking on the arrow that appeared on the left of Model
,
all model parameters and the initial state are displayed.
These are taken from the public_settings
which have been defined earlier in the model.
Double click on a value to change it manually.
Press enter to confirm the input.
Choose the PendulumModel
, the ODEInt
as Solver
and the AdditiveMixer
as ModelMixer
.
Change the initial state of Model
to [0, 100, 0, 0] and the end time of Solver
to 20 as shown in Fig. 4.
Click the gearwheel button (2), use the drop-down menu (3) or press F5 to start the simulation. After a succesful simulation, all created diagrams will be listed in the Data Window (4). Double click on one to display it as shown in Fig. 5.
Feel free to experiment with the properties and see, if the model reacts the way you would have predicted. After testing the model class, a controller shall be implemented.
Implementing a Controller¶
To close the loop a controller has to be added.
This can easily be done by deriving from the Controller
class.
Its task is to stabilize the pendulum by calculating a suitable input for the model.
To keep things simple, the linear state-feedback controller in this scenario
and it is based on the linearized system which is given by
with
The linear control law is given by
with the control gain
and the prefilter
.
One possibility to calculate the control gain is by using the Ackermann formula.
With all necessary equations, the implementation of the controller class can begin. Start by creating a file called:
controller.py
Import the same classes as in the model class:
1 2 3 4 5 6 7 | # -*- coding: utf-8 -*-
import numpy as np
from collections import OrderedDict
import pymoskito as pm
|
Derive your controller from
Controller
Next, create public_settings
as before in the model.
Its entries will be accessable in the graphical interface of PyMoskito during runtime.
This time, the only parameters will be the desired poles of the closed loop,
which the controller shall establish:
9 10 11 12 | class BasicController(pm.Controller):
public_settings = OrderedDict([("poles", [-2, -2, -2, -2])
])
|
Within the constructor, it is obligatory to set the input order
and
an input type
.
The input order
determines how many derivatives of the trajectory
will be required, sinc eour controller is very simple a 0
will do here.
Valid entries for input type
are system_state, system_output,
Observer and Sensor. In our case we will go for system_state
.
After all necessary updates, call the constructor of the base class as seen in
line 20
.
Store the linearized system matrices and the equilibrium state.
To make matrix operations possible, use the array type provided by NumPy.
PyMoskito’s Controltools provide functions
to calculate the values of a linear state feedback and a prefilter,
which can be used as seen in lines 49-50
.
The method place_siso()
is an implementation of the Ackermann formula:
14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 | def __init__(self, settings):
settings.update(input_order=0)
settings.update(input_type="system_state")
pm.Controller.__init__(self, settings)
# model parameters
g = 9.81 # gravity [m/s^2]
M = 4.2774 # cart mass [kg]
D = 10 # cart friction constant [Ns/m]
m = 0.3211 # pendulum mass [kg]
d = 0.023 # pendulum friction constant [Nms]
l = 0.3533 # pendulum length [m]
J = 0.072 # pendulum moment of intertia [kg*m^2]
# the system matrices after linearization in phi=PI
z = (M + m) * J - (m * l) ** 2
A = np.array([[0, 0, 1, 0],
[0, 0, 0, 1],
[0, (m * l) ** 2 * g / z, -J * D / z, m * l * d / z],
[0, -(M + m) * m * l * g / z, m * l * D / z,
-(M + m) * d / z]
])
B = np.array([[0],
[0],
[J / z],
[-l * m / z]
])
C = np.array([[1, 0, 0, 0]])
# the equilibrium state as a vector
self._eq_state = np.array([0, np.pi, 0, 0])
# pole placement of linearized state feedback
self._K = pm.controltools.place_siso(A, B, self._settings["poles"])
self._V = pm.controltools.calc_prefilter(A, B, C, self._K)
|
That would be all for the constructor.
The only other method left to implement contains the actual control law and will
be called by the solver during runtime.
Its parameters are the current time, the current values of trajectory,
feedforward and controller input.
The parameter **kwargs
holds further information, which is explained
in pymoskito.simulation_modules.Controller
. For our example, we will just ignore it.
Since this controller will be stabilizing the system in the steady state [0,0,0,0],
it has to be subtracted to work on the small signal scale.
52 53 54 55 56 57 58 | def _control(self, time, trajectory_values=None, feedforward_values=None,
input_values=None, **kwargs):
x = input_values - self._eq_state
yd = trajectory_values - self._eq_state[0]
output = - np.dot(self._K, x) + np.dot(self._V, yd[0])
return output
|
Finally, import the controller file and register the controller class to PyMoskito by adding two lines to the main.py file as done before with the model class. Your main.py should now look like this, with the changed lines highlighted:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 | # -*- coding: utf-8 -*-
import pymoskito as pm
# import custom modules
import model
import controller
if __name__ == '__main__':
# register model
pm.register_simulation_module(pm.Model, model.PendulumModel)
# register controller
pm.register_simulation_module(pm.Controller, controller.BasicController)
# start the program
pm.run()
|
Having put all pieces together, we are now ready to run our scenario.
Closing the Control Loop¶
Firstly, start PyMoskito from the commandline and reapply the previous steps:
- select
PendulumModel
asModel
- change the initial state of
PendulumModel
to[0, 100, 0, 0]
- select
ODEInt
asSolver
- change the end time of
Solver
to 10 - select
AdditiveMixer
asModelMixer
Now, it gets interesting, select:
- the new
BasicController
asController
- change
Input A
ofModelMixer
toController
and - select
Setpoint
asTrajectory
to generate desired values for out new setup. The setpoint 0
demands that
the cart position (the output defined by our model) should be kept at zero.
To enter string values, type 'Controller'
or "Controller"
and remember to press enter to confirm the input.
The Properties window should now look like Fig. 6
Now, hit F5
to run the simulation.
After simulating, you find a few more diagrams in the data section.
Fig. 7 shows the example of the control error.
Feel free to experiment with the settings and see, if the control loop reacts the way you would have predicted. Keep in mind that the implemented controller is static. The control law does not adapt to changes of the model parameters, since the controller gain is calculated from values stored in the controller class. You can use this effect to simulate the situation, where the controller design was based on model parameters that differ from the real parameters of the process.
These were all the fundamental functions of PyMoskito considered necessary to work with it. One more important, but also more advanced feature is the system’s visualization in 2D or 3D. This animation appears in the window at the top right, which remained grey during this tutorial (see Fig. 3, Fig. 5, Fig. 7). For more information on this topic, see the lesson on visualization.
Further Reading¶
After completing the Beginners Tutorial, there are several ways to go on if you did not find an answer to your problem or simply would like to know more.
PyMoskito contains a few examples of fully implemented systems. Take a peak into what is possible by running their simulations or reading their source code.
The Users Guide offers instructions to access the full potential of PyMoskito. Read about animated visualization, storing simulation settings for future reuse, comparing simulation results and more.
The Modules Reference contains documentations of all classes, that are part of PyMoskito. Read about all abstract classes being part of the control loop, the modules realizing the simulation or the interface and more.
Visualization¶
This tutorial covers the subject of how to visualize your system using pymoskito.
To do this, you can provide a pm.Visualizer
to the toolbox which
will then be used to show the system. To accomplish this, pymoskito uses the
VisualizationToolkit (vtk) for natty 3d plots. However, if vtk is not available
a fallback method using the matplotlib is also supported.
Before we start visualizing, we need to choose a system. For sake of simplicity, the simple_example system from the introduction will be used. Visualizers for both toolkits will be explained in the following sections.
Visualization using the Matplotlib¶
Building the visualizer¶
The overall plan here is to derive a class that we will call MplPendulumVisualizer
from MplVisualizer
. In its constructor,
we will lay down all the elements we want to use to visualize the system.
In our case these will be the beam on which the cart is moving, the cart and
of course the pendulum. Later on, the method
pymoskito.MplVisualizer.update_scene()
will be called repeatedly from the GUI to update the visualization.
We will start off with the following code:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 | # -*- coding: utf-8 -*-
import numpy as np
import pymoskito as pm
import matplotlib as mpl
import matplotlib.patches
import matplotlib.transforms
class MplPendulumVisualizer(pm.MplVisualizer):
# parameters
x_min_plot = -.85
x_max_plot = .85
y_min_plot = -.6
y_max_plot = .6
cart_height = .1
cart_length = .2
beam_height = .01
beam_length = 1
pendulum_shaft_height = 0.027
pendulum_shaft_radius = 0.020
pendulum_height = 0.5
pendulum_radius = 0.005
|
On top, we import some modules we’ll need later on. Once this is done we derive
our MplPendulumVisualizer from MplVisualizer
.
What follows below are some parameters for the matplotlib canvas and the objects
we want to draw, fell free to adapt them as you like!
In the first part of the constructor, we set up the canvas:
30 31 32 33 34 35 36 37 |
def __init__(self, q_widget, q_layout):
# setup canvas
pm.MplVisualizer.__init__(self, q_widget, q_layout)
self.axes.set_xlim(self.x_min_plot, self.x_max_plot)
self.axes.set_ylim(self.y_min_plot, self.y_max_plot)
self.axes.set_aspect("equal")
|
Afterwards, our “actors” are created:
39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 | self.beam = mpl.patches.Rectangle(xy=[-self.beam_length/2,
-(self.beam_height
+ self.cart_height/2)],
width=self.beam_length,
height=self.beam_height,
color="lightgrey")
self.cart = mpl.patches.Rectangle(xy=[-self.cart_length/2,
-self.cart_height/2],
width=self.cart_length,
height=self.cart_height,
color="dimgrey")
self.pendulum_shaft = mpl.patches.Circle(
xy=[0, 0],
radius=self.pendulum_shaft_radius,
color="lightgrey",
zorder=3)
t = mpl.transforms.Affine2D().rotate_deg(180) + self.axes.transData
self.pendulum = mpl.patches.Rectangle(
xy=[-self.pendulum_radius, 0],
width=2*self.pendulum_radius,
height=self.pendulum_height,
color=pm.colors.HKS07K100,
zorder=2,
transform=t)
|
Note that a transformation object is used to get the patch in the correct place and orientation. We’ll make more use of transformations later. For now, all that is left to do for the constructor is to add our actors t the canvas:
68 69 70 71 72 | self.axes.add_patch(self.beam)
self.axes.add_patch(self.cart)
self.axes.add_patch(self.pendulum_shaft)
self.axes.add_patch(self.pendulum)
|
After this step, the GUI knows how our system looks like. Now comes the interesting part: We use the systems state vector (the first Equation in introduction) which we obtained from the simulation to update our drawing:
74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 | def update_scene(self, x):
cart_pos = x[0]
phi = np.rad2deg(x[1])
# cart and shaft
self.cart.set_x(cart_pos - self.cart_length/2)
self.pendulum_shaft.center = (cart_pos, 0)
# pendulum
ped_trafo = (mpl.transforms.Affine2D().rotate_deg(phi)
+ mpl.transforms.Affine2D().translate(cart_pos, 0)
+ self.axes.transData)
self.pendulum.set_transform(ped_trafo)
# update canvas
self.canvas.draw()
|
As defined by our model, the first element of the state vector x yields the
cart position, while the pendulum deflection (in rad) is given by x[1]
.
Firstly, cart and the pendulum shaft are moved. This can either be done via
set_x()
or by directly overwriting the value of the center
attribute.
For the pendulum however, a transformation chain is build. It consists of a rotation
by the pendulum angle phi
followed by a translation to the current cart position.
The last component is used to compensate offsets from the rendered window.
Lastly but important: The canvas is updated vie a call to self.canvas.draw()
The complete class can be found under:
pymoskito/examples/simple_pednulum/visualizer_mpl.py
Registering the visualizer¶
To get our visualizer actually working, we need to register it. For the simple main.py of our example this would mean adding the following lines:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 | # -*- coding: utf-8 -*-
import pymoskito as pm
# import custom modules
import model
import controller
import visualizer_mpl
if __name__ == '__main__':
# register model
pm.register_simulation_module(pm.Model, model.PendulumModel)
# register controller
pm.register_simulation_module(pm.Controller, controller.BasicController)
# register visualizer
pm.register_visualizer(visualizer_mpl.MplPendulumVisualizer)
# start the program
pm.run()
|
After starting the program, this is what you should see in the top right corner:
If you are looking for a fancier animation, check out the VTK Tutorial.
Intermediate:
Expert:
Metaprocessing¶
TODO
Examples¶
PyMoskito comes with quite a set of interesting examples from the field of control theory. To run an example just enter:
$ python -m pymoskito.examples.NAME
where NAME
is the name, given in parenthesis behind the example titles.
List of Examples:
Ball and Beam (ballbeam)¶
A beam is pivoted on a bearing in its middle. The position of a ball on the beam is controlable by applying a torque into the bearing.
The ball has a mass , a radius
and a moment of inertia
.
Its distance
to the beam center is counted positively to the right.
For the purpose of simplification, the ball can only move in the horizontal direction.
The beam has a length , a moment of inertia
and its deflection from the horizontal line is the angle
.
The task is to control the position of the ball with the actuation
variable being the torque
. The interesting part in this particular
system is that while being nonlinear and intrinsically unstable, it’s relative
degree is not well-defined. This makes it an exciting but yet still clear lab
example. The description used here is taken from the publication [Hauser92] .

The ball and beam system
With the state vector
the nonlinear model equations are given by
Violations of the model’s boundary conditions are the ball leaving the beam
or the beam’s deflection reaching the vertical line
The ball’s position
is chosen as output.
The example comes with five controllers.
The FController
and GController
both implemenent a input-output-linearization of the system
and manipulate the second output derivative by ignoring certain parts of the term.
The JController
ignores the nonlinear parts of the linearized model equations,
also called standard jacobian approximation.
The LSSController
linearizes the nonlinear model in a chosen steady state
and applies static state feedback.
The PIXController
also linearizes the model and additionally integrates the control error.
LinearFeedforward
implements a compensation of the linear system equation parts,
with the aim of reducing the controllers task to the nonlinear terms of the equations and disturbances.
The example comes with four observers.
LuenbergerObserver
, LuenbergerObserverReduced
and LuenbergerObserverInt
are different implementations of the Luenberger observer.
The second of these improves its performance by using a different method of integration and the third uses the solver for integration.
The HighGainObserver
tries to implement an observer for nonlinear systems,
However, the examination for observability leads to the presumption that this attempt should fail.
A 3D visualizer is implemented. In case of missing VTK, a 2D visualization can be used instead.
An external settings
file contains all parameters.
All implemented classes import their initial values from here.
At program start, the main loads two regimes from the file default.sreg
.
test-nonlinear
is a setting of the nonlinear controller moving the ball from the left to the right side
of the beam.
test-linear
shows the step response of a linear controller, resulting in the ball moving from the middle to the right side of the beam.
The example also provides ten different modules for postprocessing.
They plot different combinations of results in two formats, one of them being pdf
.
The second format of files can be given to a metaprocessor.
The structure of __main__.py
allows starting the example without navigating to the directory
and using an __init__.py
file to outsource the import commands for additional files.
[Hauser92] | Hauser, J.; Sastry, S.; Kokotovic, P. Nonlinear Control Via Approximate Input-Output-Linearization: The Ball and Beam Example. IEEE Trans. on Automatic Control, 1992, vol 37, no. 3, pp. 392-398 |
Ball in Tube (balltube)¶
A fan at the bottom of a tube produces an air stream moving upwards. A ball levitates in the air stream.
The task is to control the ball’s position .
Actuating variable is the motor’s control signal
.

The ball in tube system
The example comes with two models, which differ in the reaction to the ball falling down.
The BallInTubeModel
makes the ball stick to the ground once it falls down.
The BallInTubeSpringModel
lets the ball to jump back up again:
Ball in Tube Model¶
A fan at the bottom of a tube produces an air stream moving upwards. A ball levitates in the air stream.
The fan rotates with the rotational speed .
It produces an air stream with the velocity
.
The factor
describes the proportionality between the air’s volume flow rate and the fan’s rotational speed.
The motor driving the fan is modeled as a PT2-element with the amplification
,
the damping
and the time constant
.
An Arduino Uno controls the motor,
its discrete control signal
has a range of
and amplifies the supply voltage
.
The ball covers an area and has a mass
.
Its distance to the tube’s bottom is the position
.
The gap between the ball and the tube covers an area
.
The factor
describes the proportionality between
the force of flow resistance and the velocity of the air streaming through the gap.
The tube has a height .
The task is to control the ball’s position .
Actuating variable is the motor’s control signal
.

The ball in tube system in detail
TWith the state vector
the model equations are given by
In case of the ball falling down and reaching a position below the fan,
the root function of the model overrides the ball’s position
and velocity
.
The model’s boundary condition is violated if the ball leaves the tube on the upper end:
The ball’s position
is chosen as output.
Ball in Tube Spring Model¶
This model contains all equations of the Ball in Tube Model except for one single change: The dynamics of the ball bouncing back up once it falls to the ground.
Instead of overriding the ball’s position and speed once the ball falls below the fan, the fourth system equation is overwritten by an extended version
This inserts a spring with the stiffness and the damping
on the ground of the tube.
The OpenLoop
controller ignores the current state and output of the model,
as well as trajectory values.
Instead it gives the opportunity to set the actuating variable manually.
The ball’s position is used as a flat output in this flatness based feedforward module:
Ball in Tube Feedforward¶
Analyzing the system for flatness leads to finding the ball’s position as the flat output of the system, meaning that all other system variables can be calculated from it. This can be retraced easily with the following chain of equations:
The last equation is implented in this feedforward module.
The highest order of derivatives is
, so the trajectory generator
needs to provide a trajectory that is differentiable at least four times.
A 3D visualizer is implemented. In case of missing VTK, a 2D visualization can be used instead.
An external settings
file contains all parameters.
All implemented classes import their initial values from here.
Regimes are stored in two files.
At program start, the main function loads six regimes from the file default.sreg
.
In addition, nine regimes can be loaded manually from the file experiments.sreg
.
The structure of __main__.py
allows starting the example without navigating to the directory
and using an __init__.py
file to outsource the import commands for additional files.
The example also provides a package for symbolic calculation.
Tandem Pendulum (pendulum)¶
Two pendulums are fixed on a cart, which can move in the horizontal direction.
The cart has a mass . The friction between the cart and the surface causes a frictional force
,
in opposite direction as the velocity
of the cart.
Each pendulum has a mass , a moment of intertia
, a length
and an angle of deflection
.
The friction in the joint where the pendulums are mounted on the cart causes a frictional torque
,
in opposite direction as the speed of rotation
.
The system is shown in Fig. 12 .
The task is to control the position of the cart and to stabilize the pendulums in either the upward or downward position.
Actuating variable is the force F.

The pendulum system
The example comes with three models. A point mass model, a rigid body model and a partially linearized model.
The state vector is chosen in all three models as:
The class TwoPendulumModel
is the implementation of a point mass model.
The mass of each pendulum is considered concentrated at the end of its rod.
The model resulting model equations are relatively simple and moments of inertia do not appear:
The class TwoPendulumRigidBodyModel
is the implementation of a rigid body model.
The rods are considered to have a mass and can not be ignored,
each pendulum has a moment of inertia :
The class TwoPendulumModelParLin
is the implementation of a the partially linearized point mass model.
The input is chosen as
with ,
and
as before in
TwoPendulumModel
.
This transforms the model equations into the input afine form
All three models define the cart’s position
as the output of the system.
The example comes with five controllers.
Two of them, LinearStateFeedback
and LinearStateFeedbackParLin
, implement linear state feedback,
both using the package symbolic_calculation
to calculate their gain and prefilter.
The LinearQuadraticRegulator
calculates its gain and prefilter by solving the continuous algebraic Riccati equation.
The LjapunovController
is designed with the method of Ljapunov to stabilize the pendulums in the upward position.
And finally the SwingUpController
, especially designed to swing up the pendulums using linear state feedback
and to stabilize the system by switching to a Ljapunov controller once the pendulums point upwards.
A 3D visualizer is implemented. In case of missing VTK, a 2D visualization can be used instead.
An external settings
file contains all parameters.
All implemented classes import their initial values from here.
At program start, the main loads eleven regimes from the file default.sreg
.
The provided regimes not only show the stabilization of the system in different
steady-states (e.g. both pendulums pointing downwards or both pointing upwards)
but also ways to transition them between those states (e.g. swinging them up).
The example also provides two modules for postprocessing.
They plot different combinations of results in two formats, one of them being pdf
.
The second format of files can be passed to a metaprocessor.
The structure of __main__.py
allows starting the example without navigating to the directory
and using an __init__.py
file to outsource the import commands for additional files.
Car with Trailers (car)¶
A car pulls multiple trailers. All parts of the vehicle have one axis for simplification.
The car moves forward with a velocity and turns with a ratotional speed
.
The coordinates
and
describe the car’s distance to the origin of a stationary coordinate system.
The car’s and the trailer’s deflections regarding the horizontal line are ,
and
.
The distances between the axles and the couplings from front to back are ,
,
and

The car system
With the state vector
the model equations are given by
with
The driving speed and the turning speed
are set to constant values in the state function of the model.
They are potential actuating variables to control the system.
There is no output defined.
The example comes with no controller,
with a 2D visualization,
an external settings
file containing all initial values for the parameters
and one regime loaded from the file default.sreg
by the main at program start.
The structure of __main__.py
allows starting the example without navigating to the directory
and using an __init__.py
file to outsource the import commands for additional files.
Users Guide¶
tbd
PyMoskito Modules Reference¶
Because every feature of PyMoskito must have a test case, when you are not sure how
to use something, just look into the tests/
directories, find that feature
and read the tests for it, that will tell you everything you need to know.
Most of the things are already documented though in this document, that is automatically generated using PyMoskito’s docstrings.
Click the “modules” (Module Index) link in the top right corner to easily access any PyInduct module, or use this contents:
Simulation GUI¶
-
class
pymoskito.simulation_gui.
SimulationGui
[source]¶ class for the graphical user interface
-
apply_regime_by_name
(regime_name)[source]¶ Apply the regime given by regime_name und update the regime index.
Returns: True if successful, False if errors occurred. Return type: bool
-
export_simulation_data
(ok)[source]¶ Query the user for a custom name and export the current simulation results.
Parameters: ok – unused parameter from QAction.triggered() Signal
-
new_simulation_data
(status, data)[source]¶ Slot to be called when the simulation interface has completed the current job and new data is available.
Parameters: - status (str) – Status of the simulation, either - finished : Simulation has been finished successfully or - failed : Simulation has failed.
- data (dict) – Dictionary, holding the simulation data.
-
plot_data_vector
(item)[source]¶ Creates a plot widget based on the given item.
If a plot for this item is already open no new plot is created but the existing one is raised up again.
Parameters: item (Qt.ListItem) – Item to plot.
-
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 theSimulationInterface
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 thesettings
property.The most important method is
calc_output()
which is called by theSimulator
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.
-
class
pymoskito.simulation_modules.
Trajectory
(settings)[source]¶ Base class for all trajectory generators
-
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.
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
-
-
exception
pymoskito.simulation_modules.
ModelException
[source]¶ Exception to be raised if the current system state violates modelling assumptions.
-
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
-
Generic Simulation Modules¶
-
class
pymoskito.generic_simulation_modules.
LinearStateSpaceModel
(settings)[source]¶ The state space model of a linear system.
The parameters of this model can be provided in form of a file whose path is given by the setting
config file
. This path should point to a pickled dict holding the following keys:- system:
- An Instance of
scipy.signal.StateSpace
(from scipy) representing the system, - op_inputs:
- An array-like object holding the operational point’s inputs,
- op_outputs:
- An array-like object holding the operational point’s outputs.
-
class
pymoskito.generic_simulation_modules.
ODEInt
(settings)[source]¶ Wrapper for ode_int from Scipy project
-
class
pymoskito.generic_simulation_modules.
ModelInputLimiter
(settings)[source]¶ ModelInputLimiter that limits the model input values.
- Settings:
- Limits: (List of) list(s) that hold (min, max) pairs for the corresponding input.
-
class
pymoskito.generic_simulation_modules.
Setpoint
(settings)[source]¶ Provides setpoints for every output component.
If the output is not scalar, just add more entries to the list. By querying the differential order from the controller (if available) the required derivatives are given.
Note
Keep in mind that while this class provides zeros for all derivatives of the desired value, they actually strive to infinity for
.
-
class
pymoskito.generic_simulation_modules.
HarmonicTrajectory
(settings)[source]¶ This generator provides a scalar harmonic sinus signal with derivatives up to order n
-
class
pymoskito.generic_simulation_modules.
SmoothTransition
(settings)[source]¶ provides (differential) smooth transition between two scalar states
-
class
pymoskito.generic_simulation_modules.
LinearStateSpaceController
(settings)[source]¶ A controller that is based on a state space model of a linear system.
This controller needs a linear statespace model, just as the
LinearStateSpaceModel
. The file provided inconfig file
should therefore contain a dict holding the entries:model
,op_inputs
andop_outputs
.If poles is given (differing from None ) the state-feedback will be computed using
pymoskito.place_siso()
. Furthermore an appropriate prefilter is calculated, which establishes stationary attainment of the desired output values.
-
class
pymoskito.generic_simulation_modules.
DeadTimeSensor
(settings)[source]¶ Sensor that adds a measurement delay on chosen states
Simulation Core¶
-
class
pymoskito.simulation_core.
SimulationStateChange
(**kwargs)[source]¶ Object that is emitted when Simulator changes its state.
Keyword Arguments: - type –
Keyword describing the state change, can be one of the following
- init Initialisation
- start : Start of Simulation
- time : Accomplishment of new progress step
- finish : Finish of Simulation
- abort : Abortion of Simulation
- data – Data that is emitted on state change.
- info – Further information.
- type –
Processing GUI¶
Processing Core¶
-
class
pymoskito.processing_core.
PostProcessingModule
[source]¶ Base Class for Postprocessing Modules
-
static
calc_l1_norm_abs
(meas_values, desired_values, step_width)[source]¶ Calculate the L1-Norm of the absolute error.
Parameters: - step_width (float) – Time difference between measurements.
- desired_values (array-like) – Desired values.
- meas_values (array-like) – Measured values.
-
static
calc_l1_norm_itae
(meas_values, desired_values, step_width)[source]¶ Calculate the L1-Norm of the ITAE (Integral of Time-multiplied Absolute value of Error).
Parameters: - step_width (float) – Time difference between measurements.
- desired_values (array-like) – Desired values.
- meas_values (array-like) – Measured values.
-
process
(files)[source]¶ worker-wrapper function that processes an array of result files This is an convenience wrapper for simple processor implementation. Overload for more sophisticated implementations :param files:
-
run
(data)[source]¶ Run this postprocessor.
This function will be called from
process()
with the simulation results from one simulation result file.Overwrite this function to implement your own PostProcessor.
Args; param data: simulation results from a pymoskito simulation result file.
Returns: With a figure Canvas an a name. Return type: Dict
-
static
-
class
pymoskito.processing_core.
MetaProcessingModule
[source]¶ Base Class for Meta-Processing Modules
Controltools¶
This file contains some functions that are quite helpful when designing feedback laws. This collection is not complete and does not aim to be so. For a more sophisticated collection have a look at the symbtools (https://github.com/TUD-RST/symbtools) or control package which are not used in this package to keep a small footprint.
-
pymoskito.controltools.
char_coefficients
(poles)[source]¶ Calculate the coefficients of a characteristic polynomial.
Parameters: poles (list or numpy.ndarray
) – pol configurationReturns: coefficients Return type: numpy.ndarray
-
pymoskito.controltools.
place_siso
(a_mat, b_mat, poles)[source]¶ Place poles for single input single output (SISO) systems:
- pol placement for state feedback:
and
- pol placement for observer:
and
Parameters: - a_mat (
numpy.ndarray
) – System matrix.:math:A - b_mat (
numpy.ndarray
) – Input vectoror Output matrix
.
- poles (list or
numpy.ndarray
) – Desired poles.
Returns: Feedback vector or
or observer gain
.
Return type: numpy.ndarray
- pol placement for state feedback:
-
pymoskito.controltools.
calc_prefilter
(a_mat, b_mat, c_mat, k_mat=None)[source]¶ Calculate the prefilter matrix
Parameters: - a_mat (
numpy.ndarray
) – system matrix - b_mat (
numpy.ndarray
) – input matrix - c_mat (
numpy.ndarray
) – output matrix - k_mat (
numpy.ndarray
) – control matrix
Returns: Prefilter matrix
Return type: numpy.ndarray
- a_mat (
-
pymoskito.controltools.
controllability_matrix
(a_mat, b_mat)[source]¶ Calculate controllability matrix and check controllability of the system.
Parameters: - a_mat (
numpy.ndarray
) – system matrix - b_mat (
numpy.ndarray
) – manipulating matrix
Returns: controllability matrix
Return type: numpy.ndarray
- a_mat (
-
pymoskito.controltools.
observability_matrix
(a_mat, c_mat)[source]¶ Calculate observability matrix and check observability of the system.
Parameters: - a_mat (
numpy.ndarray
) – system matrix - c_mat (
numpy.ndarray
) – output matrix
Returns: observability matrix
Return type: numpy.ndarray
- a_mat (
-
pymoskito.controltools.
lie_derivatives
(h, f, x, order=1)[source]¶ Calculates the Lie-Derivative from a scalar field
along a vector field
.
Parameters: - h (sympy.matrix) – scalar field
- f (sympy.matrix) – vector field
- x (sympy.matrix) – symbolic representation of the states
- order (int) – order
Returns: lie derivatives in ascending order
Return type: list of sympy.matrix
Tools¶
Tools, functions and other funny things
-
pymoskito.tools.
rotation_matrix_xyz
(axis, angle, angle_dim)[source]¶ Calculate the rotation matrix for a rotation around a given axis with the angle
.
Parameters: - axis (str) – choose rotation axis “x”, “y” or “z”
- angle (int or float) – rotation angle
- angle_dim (str) – choose “deg” for degree or “rad” for radiant
Returns: rotation matrix
Return type: numpy.ndarray
Contributions to docs¶
All contributions are welcome. If you’d like to improve something, look into
the sources if they contain the information you need (if not, please fix them),
otherwise the documentation generation needs to be improved (look in the
doc/
directory).
Contributing¶
Contributions are welcome, and they are greatly appreciated! Every little bit helps, and credit will always be given.
You can contribute in many ways:
Types of Contributions¶
Report Bugs¶
Report bugs at https://github.com/cklb/pymoskito/issues.
If you are reporting a bug, please include:
- Your operating system name and version.
- Any details about your local setup that might be helpful in troubleshooting.
- Detailed steps to reproduce the bug.
Fix Bugs¶
Look through the GitHub issues for bugs. Anything tagged with “bug” is open to whoever wants to implement it.
Implement Features¶
Look through the GitHub issues for features. Anything tagged with “feature” is open to whoever wants to implement it.
Write Documentation¶
PyMoskito could always use more documentation, whether as part of the official PyMoskito docs, in docstrings, or even on the web in blog posts, articles, and such.
Submit Feedback¶
The best way to send feedback is to file an issue at https://github.com/cklb/pymoskito/issues.
If you are proposing a feature:
- Explain in detail how it would work.
- Keep the scope as narrow as possible, to make it easier to implement.
- Remember that this is a volunteer-driven project, and that contributions are welcome :)
Get Started!¶
Ready to contribute? Here’s how to set up pymoskito for local development.
Fork the pymoskito repo on GitHub.
Clone your fork locally:
$ git clone git@github.com:your_name_here/pymoskito.git
Install your local copy into a virtualenv. Assuming you have virtualenvwrapper installed, this is how you set up your fork for local development:
$ mkvirtualenv pymoskito $ cd pymoskito/ $ python setup.py develop
Create a branch for local development:
$ git checkout -b name-of-your-bugfix-or-feature
Now you can make your changes locally.
When you’re done making changes, check that your changes pass flake8 and the tests, including testing other Python versions with tox:
$ python setup.py test
Commit your changes and push your branch to GitHub:
$ git add . $ git commit -m "Your detailed description of your changes." $ git push origin name-of-your-bugfix-or-feature
Submit a pull request through the GitHub website.
Pull Request Guidelines¶
Before you submit a pull request, check that it meets these guidelines:
- The pull request should include tests.
- If the pull request adds functionality, the docs should be updated. Put your new functionality into a function with a docstring, and add the feature to the list in README.rst.
- The pull request should work for Python 3.4+ and for PyPy. Check https://travis-ci.org/cklb/pymoskito/pull_requests and make sure that the tests pass for all supported Python versions.
Credits¶
Development Lead¶
- Stefan Ecklebe <stefan.ecklebe@tu-dresden.de>
Contributors¶
- Christoph Burggraf
- Marcus Riesmeier
- Jonas Hoffmann
- Jens Wurm
History¶
0.3.0 (2018-10-01)¶
- Added a new plot system
- Added a last simulation list
- Added more log messages
- Removed latex as an requirement for the main GUI, only required for the Postprocessor
0.2.3 (2018-05-14)¶
- Added sensible examples for Post- and Meta processors in the Ball and Beam example
- Fixed Issue regarding the Disturbance Block
- Removed error-prone pseudo post processing
- Fixed problems due to changes in trajectory generators
0.2.2 (2018-03-28)¶
- Added extensive beginners guide (thanks to Jonas) and tutorial section
- Added extended documentation for examples (again, thanks to Jonas)
0.2.1 (2017-09-07)¶
- Fixed issue when installing via pip
- Fixed issue with metaprocessors and added example metaprocessor for ballbeam
- Downgraded requirements
0.2.0 (2017-08-18)¶
- Second minor release with lots of new features.
- Completely overhauled graphical user interface with menus and shortcuts.
- PyMoskito now comes with three full-fledged examples from the world of control theory, featuring the Ball and Beam- and a Tandem-Pendulum system.
- The main application now has a logger window which makes it easier to see what is going on in the simulation circuit.
- Several bugs concerning encoding issues have been fixed
- Unittest have been added and the development now uses travis-ci
- Version change from PyQt4 to Pyt5
- Version change form Python 2.7 to 3.5+
- Changed version to GPLv3 and added appropriate references for the used images.
- Improved the export of simulation results
- Introduced persistent settings that make opening files less painful.
- Made vtk an optional dependency and added matplotlib based visualizers.
- Large improvements concerning the sphinx-build documentation
- Fixed issue concerning possible data types for simulation module properties
- Introduced new generic modules that directly work on scipy StateSpace objects.
0.1.0 (2015-01-11)¶
- First release on PyPI.