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.