Engee documentation
Notebook

Integrating Julia code into Engee models using the Engee Function block

This example shows how to integrate Julia code into Engee models using the Engee Function block.

Before we start, let's connect the necessary libraries:

In [ ]:
Pkg.add(["Statistics", "ControlSystems", "CSV"])
In [ ]:
using Plots
using MATLAB
using CSV
using Statistics
using ControlSystems
plotlyjs();

Use the macro @__DIR__ to find out the folder where the interactive script lies:

In [ ]:
demoroot = @__DIR__
Out[0]:
"/user/start/examples/base_simulation/juliacodeintegration"

Task Setup

Suppose that we are interested in filtering noisy measurements of the angular position of the $\theta$ pendulum using a Kalman filter.

1.PNG

We determine the gain of the Kalman filter using the ControlSystems.jl library and integrate the Julia code implementing the filter into the Engee model using the Engee Function block.

Simplified mathematical model of a pendulum in state space

To implement the Kalman filter we need a model of a pendulum in the state space.

A simple frictionless pendulum system can be represented by Eq:

$$I \cdot \frac{d^2\theta}{dt^2} + mgl \cdot \sin{\theta} = \tau \qquad (I = ml^2)$$

This equation can be rewritten as follows:

$$\frac{d^2\theta}{dt^2} + \frac{g}{l} \cdot \sin{\theta} = \frac{1}{ml^2} \cdot \tau $$

For small angles $\sin{\theta} \approx \theta$:

$$\frac{d^2\theta}{dt^2} + \frac{g}{l} \cdot \theta = \frac{1}{ml^2} \cdot \tau$$.

We replace the torque $\tau$ by the input vector $u$ and represent the linearised system by a state-space model:

$$\dot{x} = \begin{bmatrix} \dot{x}_1 \\ \dot{x}_2 \end{bmatrix} = Ax + Bu$$ $$y = Cx + Du$$

$$x_1 = \theta = y \qquad \dot{x}_1 = \dot{\theta} = x_2$$ $$x_2 = \dot{\theta} \qquad \dot{x}_2 = \ddot{\theta} = -\frac{g}{l} \cdot x_1 + \frac{1}{ml^2}\cdot u$$

Then the state space matrices will be defined as follows:

$$A = \begin{bmatrix} 0 & 1 \\ -g/l & 0 \end{bmatrix}$$ $$B = \begin{bmatrix} 0 \\ 1/(ml^2) \end{bmatrix}$$ $$C = \begin{bmatrix} 1 & 0 \end{bmatrix}$$ $$D = 0$$

Signal filtering in Engee using the Engee Function block

Model analysis

Let's analyse the model juliaCodeIntegration.engee.

Upper level of the model:

ef_1.PNG

The pendulum is represented by a transfer function:

$$W = \frac{4}{s^2 + 19.62}$$

Blocks Band-Limited White Noise ProcessNoise and MeasurementNoise represent external influence and measurement noise.

Subsystem Kalman Filter:

ef_2.PNG

Unit settings KF (Engee Function):

  • Tab Main:

ef_3_1.PNG

The number of input and output ports is defined by the Number of input ports and Number of output ports properties.

  • Tab Ports:

ef_3_2.PNG

The dimensionality of the input and output signals is defined by the Size property:

  • two scalar signals and a vector [2x1] are input to the block;
  • one vector [2x1] is generated at the output.
  • Tab Parameters:

parameters.PNG

Parameters KF_A, KF_B, KF_C, KF_D, KF_K are mapped to variables A, B, C, D and K from the Engee workspace. Their values will be defined in the Simulation Run section.

Contents of the ExeCode tab of the KF block :

include("/user/start/examples/base_simulation/juliacodeintegration/filter.jl")

struct KF <: AbstractCausalComponent; end

function (kalman_filter::KF)(t::Real, u, y, x)
    xhat = xhat_predict(u, x, KF_A, KF_B) + xhat_update(u, y, x, KF_C, KF_D, KF_K)

    return xhat
end

The structure KF inherits from AbstractCausalComponent.

The line include("/user/start/examples/base_simulation/juliacodeintegration/filter.jl") is required to connect the external source code file filter.jl.

The file filter.jl defines the functions xhat_predict and xhat_update, which are intended to generate the output signal xhat of the block KF:

function xhat_predict(u, x, A, B)
    return (B * u) + (A * x)
end

function xhat_update(u, y, x, C, D, K)
    return (K * (y .- ((C * x) .+ (D * u))))
end

In this example, there are no internal states, so there is no method update!, designed to update them.

Running the simulation

Load the model juliaCodeIntegration.engee:

In [ ]:
juliaCodeIntegration = engee.load("$demoroot/juliaCodeIntegration.engee", force = true)
Out[0]:
Model(
	name: juliaCodeIntegration
	id: 053374c2-1fab-48ee-8dbe-e698974ce662
)

And initialise the variables required for its simulation:

In [ ]:
g = 9.81;
m = 1;
L = 0.5;

Ts = 0.001;
Q = 1e-3;
R = 1e-4;

processNoisePower = Q * Ts;
measurementNoisePower = R * Ts;

Form the model of the pendulum in the state space using the function ss from the library ControlSystems.jl:

In [ ]:
A = [0 1; -g/L 0];
B = [0; 1/(m*L^2)];
C = [1.0 0.0];
D = 0.0;

sys = ss(A, B, C, D)
Out[0]:
StateSpace{Continuous, Float64}
A = 
   0.0   1.0
 -19.62  0.0
B = 
 0.0
 4.0
C = 
 1.0  0.0
D = 
 0.0

Continuous-time state-space model

Determine the Kalman filter gain using the function kalman from the library ControlSystems.jl:

In [ ]:
K = kalman(sys, Q, R)
Out[0]:
2×1 Matrix{Float64}:
 3.2413602377158526
 0.2532080953226874

Let's model the system:

In [ ]:
simulationResults = engee.run(juliaCodeIntegration)
Out[0]:
Dict{String, DataFrame} with 2 entries:
  "filtered" => 40001×2 DataFrame…
  "noisy"    => 40001×2 DataFrame

Let's close the model:

In [ ]:
engee.close(juliaCodeIntegration,force = true);

Modelling results

Import the results of the simulation:

In [ ]:
juliaCodeIntegration_noisy_t = simulationResults["noisy"].time;
juliaCodeIntegration_noisy_y = simulationResults["noisy"].value;
In [ ]:
juliaCodeIntegration_filtered_t = simulationResults["filtered"].time;
juliaCodeIntegration_filtered_y = simulationResults["filtered"].value;

Plot the graph:

In [ ]:
plot(juliaCodeIntegration_noisy_t, juliaCodeIntegration_noisy_y, label = "Исходный сигнал")
plot!(juliaCodeIntegration_filtered_t, juliaCodeIntegration_filtered_y, label = "Отфильтрованный сигнал")

title!("Фильтрация сигнала в Engee (Engee Function)")
xlabel!("Время, [с]")
ylabel!("Угловое положение маятника")
Out[0]:

Model analysis

Let's analyse the model simulinkKalmanFilter.slx:

skf_1.PNG

Kalman Filter unit settings:

skf_2.PNG

The input port data of the model simulinkKalmanFilter.slx is fed with the values of the noisy signal noisy from the model juliaCodeIntegration.engee, so that the filtered signals obtained in the two simulation environments can be compared.

Running the simulation

Extract the variables time and data needed to run the simulation in Simulink from the file juliaCodeIntegration_noisy.csv, obtained after the simulation in Engee:

In [ ]:
mat"""
skf_T = readtable('/user/CSVs/juliaCodeIntegration_noisy.csv', 'NumHeaderLines', 1);
time = skf_T.Var1;
data = skf_T.Var2;
"""

Simulate the system:

In [ ]:
mdlSim = joinpath(demoroot,"simulinkKalmanFilter")
mat"""myMod = $mdlSim;
    out = sim(myMod);""";

Modelling results

Import the results of the simulation:

In [ ]:
skf_data = mat"out.yout{1}.Values.Data";
skf_time = mat"out.tout";

Plot the graph:

In [ ]:
plot(juliaCodeIntegration_noisy_t, juliaCodeIntegration_noisy_y, label = "Исходный сигнал")
plot!(skf_time, skf_data, label = "Отфильтрованный сигнал")

title!("Фильтрация сигнала в Simulink (Kalman Filter)")
xlabel!("Время, [с]")
ylabel!("Угловое положение маятника")
Out[0]:

Comparison with the result obtained in Engee

Let's determine the average absolute error of calculations:

In [ ]:
tol_abs = skf_data - juliaCodeIntegration_filtered_y;
tol_abs_mean = abs(mean(tol_abs))
Out[0]:
8.708215107605803e-17

Determine the average relative error of calculations:

In [ ]:
tol_rel = (skf_data - juliaCodeIntegration_filtered_y)./skf_data;
tol_rel_mean = abs(mean(filter(!isnan, tol_rel))) * 100
Out[0]:
2.312573232451167e-12

Let's plot the absolute error of calculations:

In [ ]:
plot(skf_time, broadcast(abs, tol_abs), legend = false)

title!("Сравнение результатов, полученных в Engee и Simulink")
xlabel!("Время, [с]")
ylabel!("Абсолютная погрешность вычислений")
Out[0]:

Based on the obtained results, we can conclude that the implementation of the Kalman filter using the Engee Function block is not inferior in accuracy to the Kalman Filter block built into Simulink.

Conclusions

This example demonstrates how to integrate Julia code into Engee models and the peculiarities of using Engee Function block - working with multidimensional signals, passing parameters, connecting external source code files.