Skip to content

Commit

Permalink
add stable noise sources and tutorial (#11)
Browse files Browse the repository at this point in the history
  • Loading branch information
baggepinnen authored Sep 3, 2024
1 parent 68122c4 commit 070a375
Show file tree
Hide file tree
Showing 8 changed files with 269 additions and 23 deletions.
10 changes: 10 additions & 0 deletions Project.toml
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,24 @@ authors = ["Fredrik Bagge Carlson"]
version = "0.1.0"

[deps]
DiffEqCallbacks = "459566f4-90b8-5000-8ac3-15dfb0a30def"
JuliaSimCompiler = "8391cb6b-4921-5777-4e45-fd9aab8cb88d"
ModelingToolkit = "961ee093-0014-501f-94e3-6117800e7a78"
ModelingToolkitStandardLibrary = "16a59e39-deab-5bd0-87e4-056b12336739"
OrdinaryDiffEq = "1dea7af3-3e70-54e6-95c3-0bf5283fa5ed"
Random = "9a3f8284-a2c9-5f02-9a11-845980a1fd5c"
StableRNGs = "860ef19b-820b-49d6-a774-d7a799459cd3"

[compat]
DiffEqCallbacks = "~3.8"
julia = "1.10"
StableRNGs = "1"
JuliaSimCompiler = "0.1.19"
ModelingToolkit = "9"
ModelingToolkitStandardLibrary = "2"
OrdinaryDiffEq = "6.89"
Random = "1"


[extras]
ControlSystemsBase = "aaaaaaaa-a6ca-5380-bf3e-84a91bcd477e"
Expand Down
1 change: 1 addition & 0 deletions docs/Project.toml
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
[deps]
ControlSystemIdentification = "3abffc1c-5106-53b7-b354-a47bfc086282"
Documenter = "e30172f5-a6a5-5a46-863b-614d45cd2de4"
JuliaSimCompiler = "8391cb6b-4921-5777-4e45-fd9aab8cb88d"
ModelingToolkit = "961ee093-0014-501f-94e3-6117800e7a78"
Expand Down
3 changes: 2 additions & 1 deletion docs/make.jl
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,8 @@ makedocs(;
pages = [
"Home" => "index.md",
"Tutorials" => [
"Getting started with Sampled-Data Systems" => "SampledData.md",
"Getting started with Sampled-Data Systems" => "tutorials/SampledData.md",
"Noise" => "tutorials/noise.md",
],
"Examples" => [
"Controlled DC motor" => "examples/dc_motor_pi.md",
Expand Down
22 changes: 13 additions & 9 deletions docs/src/SampledData.md → docs/src/tutorials/SampledData.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,22 @@ A sampled-data system contains both continuous-time and discrete-time components
## Clocks, operators and difference equations
A clock can be seen as an *event source*, i.e., when the clock ticks, an event is generated. In response to the event the discrete-time logic is executed, for example, a control signal is computed. For basic modeling of sampled-data systems, the user does not have to interact with clocks explicitly, instead, the modeling is performed using the operators

- [`Sample`](@ref)
- [`Hold`](@ref)
- [`ShiftIndex`](@ref)
- [`ModelingToolkit.Sample`](@ref)
- [`ModelingToolkit.Hold`](@ref)
- [`ModelingToolkit.ShiftIndex`](@ref)

or their corresponding components

- [`ModelingToolkitSampledData.Sampler`](@ref)
- [`ModelingToolkitSampledData.ZeroOrderHold`](@ref)

When a continuous-time variable `x` is sampled using `xd = Sample(x, dt)`, the result is a discrete-time variable `xd` that is defined and updated whenever the clock ticks. `xd` is *only defined when the clock ticks*, which it does with an interval of `dt`. If `dt` is unspecified, the tick rate of the clock associated with `xd` is inferred from the context in which `xd` appears. Any variable taking part in the same equation as `xd` is inferred to belong to the same *discrete partition* as `xd`, i.e., belonging to the same clock. A system may contain multiple different discrete-time partitions, each with a unique clock. This allows for modeling of multi-rate systems and discrete-time processes located on different computers etc.

To make a discrete-time variable available to the continuous partition, the [`Hold`](@ref) operator is used. `xc = Hold(xd)` creates a continuous-time variable `xc` that is updated whenever the clock associated with `xd` ticks, and holds its value constant between ticks.
To make a discrete-time variable available to the continuous partition, the `Hold` operator is used. `xc = Hold(xd)` creates a continuous-time variable `xc` that is updated whenever the clock associated with `xd` ticks, and holds its value constant between ticks.

The operators [`Sample`](@ref) and [`Hold`](@ref) are thus providing the interface between continuous and discrete partitions.
The operators `Sample` and `Hold` are thus providing the interface between continuous and discrete partitions.

The [`ShiftIndex`](@ref) operator is used to refer to past and future values of discrete-time variables. The example below illustrates its use, implementing the discrete-time system
The `ShiftIndex` operator is used to refer to past and future values of discrete-time variables. The example below illustrates its use, implementing the discrete-time system

```math
x(k+1) = 0.5x(k) + u(k)
Expand All @@ -48,7 +53,7 @@ eqs = [
A few things to note in this basic example:

- The equation `x(k+1) = 0.5x(k) + u(k)` has been rewritten in terms of negative shifts since positive shifts are not yet supported.
- `x` and `u` are automatically inferred to be discrete-time variables, since they appear in an equation with a discrete-time [`ShiftIndex`](@ref) `k`.
- `x` and `u` are automatically inferred to be discrete-time variables, since they appear in an equation with a discrete-time `ShiftIndex` `k`.
- `y` is also automatically inferred to be a discrete-time-time variable, since it appears in an equation with another discrete-time variable `x`. `x,u,y` all belong to the same discrete-time partition, i.e., they are all updated at the same *instantaneous point in time* at which the clock ticks.
- The equation `y ~ x` does not use any shift index, this is equivalent to `y(k) ~ x(k)`, i.e., discrete-time variables without shift index are assumed to refer to the variable at the current time step.
- The equation `x(k) ~ 0.5x(k-1) + u(k-1)` indicates how `x` is updated, i.e., what the value of `x` will be at the *current* time step in terms of the *past* value. The output `y`, is given by the value of `x` at the *current* time step, i.e., `y(k) ~ x(k)`. If this logic was implemented in an imperative programming style, the logic would thus be
Expand Down Expand Up @@ -106,11 +111,10 @@ eqs = [
]
```

(see also [ModelingToolkitStandardLibrary](https://docs.sciml.ai/ModelingToolkitStandardLibrary/stable/) for a discrete-time transfer-function component.)

## Initial conditions

The initial condition of discrete-time variables is defined using the [`ShiftIndex`](@ref) operator, for example
The initial condition of discrete-time variables is defined using the `ShiftIndex` operator, for example

```julia
ODEProblem(model, [x(k-1) => 1.0], (0.0, 10.0))
Expand Down
122 changes: 122 additions & 0 deletions docs/src/tutorials/noise.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,122 @@
# Measurement noise and corruption
Measurement noise is practically always present in signals originating from real-world sensors. In a sampled-data system, analyzing the influence of measurement noise using simulation is relatively straight forward. Below, we add Gaussian white noise to the speed sensor signal in the DC motor example. The noise is added using the [`NormalNoise`](@ref) block.

This block has two modes of operation
1. If `additive = false` (default), the block has the connector `output` only, and this output is the noise signal.
2. If `additive = true`, the block has the connectors `input` and `output`, and the output is the sum of the input and the noise signal, i.e., the noise is _added_ to the input signal. This mode makes it convenient to add noise to a signal in a sampled-data system.

## Example: Noise
```@example NOISE
using ModelingToolkit
using ModelingToolkit: t_nounits as t
using ModelingToolkitStandardLibrary.Electrical
using ModelingToolkitStandardLibrary.Mechanical.Rotational
using ModelingToolkitStandardLibrary.Blocks
using ModelingToolkitSampledData
using JuliaSimCompiler
using OrdinaryDiffEq
using Plots
R = 0.5 # [Ohm] armature resistance
L = 4.5e-3 # [H] armature inductance
k = 0.5 # [N.m/A] motor constant
J = 0.02 # [kg.m²] inertia
f = 0.01 # [N.m.s/rad] friction factor
tau_L_step = -0.3 # [N.m] amplitude of the load torque step
nothing # hide
z = ShiftIndex()
@mtkmodel NoisyClosedLoop begin
@components begin
ground = Ground()
source = Voltage()
ref = Blocks.Step(height = 1, start_time = 0, smooth = false)
sampler = Sampler(dt = 0.002)
noise = NormalNoise(sigma = 0.1, additive = true)
pi_controller = DiscretePIDStandard(
K = 1, Ti = 0.035, u_max = 10, with_D = false)
zoh = ZeroOrderHold()
R1 = Resistor(R = R)
L1 = Inductor(L = L)
emf = EMF(k = k)
fixed = Fixed()
load = Torque()
load_step = Blocks.Step(height = tau_L_step, start_time = 1.3)
inertia = Inertia(J = J)
friction = Damper(d = f)
speed_sensor = SpeedSensor()
angle_sensor = AngleSensor()
end
@equations begin
connect(fixed.flange, emf.support, friction.flange_b)
connect(emf.flange, friction.flange_a, inertia.flange_a)
connect(inertia.flange_b, load.flange)
connect(inertia.flange_b, speed_sensor.flange, angle_sensor.flange)
connect(load_step.output, load.tau)
connect(ref.output, pi_controller.reference)
connect(speed_sensor.w, sampler.input)
connect(sampler.output, noise.input)
connect(noise.output, pi_controller.measurement)
connect(pi_controller.ctr_output, zoh.input)
connect(zoh.output, source.V)
connect(source.p, R1.p)
connect(R1.n, L1.p)
connect(L1.n, emf.p)
connect(emf.n, source.n, ground.g)
end
end
@named noisy_model = NoisyClosedLoop()
noisy_model = complete(noisy_model)
ssys = structural_simplify(IRSystem(noisy_model)) # Conversion to an IRSystem from JuliaSimCompiler is required for sampled-data systems
noise_prob = ODEProblem(ssys, [unknowns(noisy_model) .=> 0.0; noisy_model.pi_controller.I(z-1) => 0; noisy_model.pi_controller.eI(z-1) => 0; noisy_model.noise.y(z-1) => 0], (0, 2.0))
noise_sol = solve(noise_prob, Tsit5())
figy = plot(noise_sol, idxs=noisy_model.noise.y, label = "Measured speed", )
plot!(noise_sol, idxs=noisy_model.inertia.w, ylabel = "Angular Vel. [rad/s]",
label = "Actual speed", legend=:bottomleft, dpi=600, l=(2, :blue))
figu = plot(noise_sol, idxs=noisy_model.source.V.u, label = "Control signal [V]", )
plot(figy, figu, plot_title = "DC Motor with Discrete-time Speed Controller")
```

## Linear analysis of noise
Propagation of Gaussian noise through linear time-invariant systems is well understood, the stationary covariance of the output can be computed by solving a Lyapunov equation. Unfortunately, ModelingToolkit models that contain both continuous time and discrete time components cannot yet be linearized and linear analysis is thus made slightly harder. Below, we instead use a data-driven linearization approach where we use recorded signals from the simulation and fit a linear model using subspace-based identification. The function `subspaceid` below is provided by the package [ControlSystemIdentification.jl](https://baggepinnen.github.io/ControlSystemIdentification.jl/stable/).

We let the angular velocity of the inertia be the output, and the output of the noise block as well as the output of the load disturbance be the inputs.

```@example NOISE
using ControlSystemIdentification, ControlSystemsBase
Tf = 20
prob2 = remake(noise_prob, p=Dict(noisy_model.load_step.height=>0.0), tspan=(0.0, Tf))
noise_sol = solve(prob2, Tsit5())
tv = 0:0.002:Tf
y = noise_sol(tv, idxs=noisy_model.inertia.w) |> vec
un = noise_sol(tv, idxs=noisy_model.noise.y)-y |> vec
ud = noise_sol(tv, idxs=noisy_model.load_step.output.u) |> vec
d = iddata(y', [un ud]', 0.002)
lsys,_ = newpem(d, 4, focus=:simulation, zeroD=false)
```
With an LTI model available, we can ask for the theoretical output covariance we should obtain if we feed a white noise signal with covariance matrix ``0.1^2 I`` through the noise input of the system. We compare this to the actual output covariance obtained from the simulation (discarding the initial transient as well as the transient caused by the load disturbance).
```@example NOISE
sqrt(covar(lsys[1,1],0.1^2*I)), std(y[[50:648; 750:end]])
```

## Noise filtering
No discrete-time filter components are available yet. You may, e.g.
- Add exponential filtering using `xf(k) ~ (1-α)xf(k-1) + α*x(k)`, where `α` is the filter coefficient and `x` is the signal to be filtered.
- Add moving average filtering using `xf(k) ~ 1/N sum(i->x(k-i), i=0:N-1)`, where `N` is the number of samples to average over.

## Colored noise
Colored noise can be achieved by filtering white noise through a filter with the desired spectrum. No components are available for this yet.

## Internal details
Internally, a random number generator from [StableRNGs.jl](https://github.com/JuliaRandom/StableRNGs.jl) is used to produce reproducible streams of random numbers. Each draw of a random number is seeded by `hash(t, hash(seed))`, where `seed` is a parameter in the noise source component, and `t` is the current simulation time. This ensures that
1. The user can alter the stream of random numbers with `seed`.
2. Multiple calls to the random number generator at the same time step all return the same number.

## Quantization
Not yet available.
1 change: 1 addition & 0 deletions src/ModelingToolkitSampledData.jl
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
module ModelingToolkitSampledData
using ModelingToolkit
using JuliaSimCompiler
using StableRNGs

export get_clock
export DiscreteIntegrator, DiscreteDerivative, Delay, Difference, ZeroOrderHold, Sampler,
Expand Down
100 changes: 89 additions & 11 deletions src/discrete_blocks.jl
Original file line number Diff line number Diff line change
Expand Up @@ -144,35 +144,68 @@ A discrete-time noise source that returns a normally-distributed value at each c
# Parameters
- `mu = 0`: Mean
- `sigma = 1`: Standard deviation
- `seed = 1`: Seed for the random number generator
# Structural parameters
- `rng`: A random number generator, defaults to `Random.Xoshiro()`.
- `z`: The `ShiftIndex` used to indicate clock partition.
# Connectors:
- `output`
"""
@mtkmodel NormalNoise begin
@structural_parameters begin
z = ShiftIndex()
additive = false
end
@components begin
output = RealOutput()
if additive
input = RealInput()
end
end
@variables begin
y(t), [description = "Output variable"]
if additive
u(t), [description = "Input variable"]
end
n(t), [description = "Internal noise variable"]
end
@parameters begin
mu = 0
sigma = 1
end
@structural_parameters begin
z = ShiftIndex()
rng = Random.Xoshiro()
seed = 1
end
@equations begin
y(z) ~ mu + sigma*Symbolics.term(randn, rng; type=Real)
output.u ~ y
n(z) ~ mu + sigma*Symbolics.term(seeded_randn, seed, t; type=Real)
# n(z) ~ mu + sigma*Symbolics.term(randn, rng; type=Real)
if additive
y(z) ~ u(z) + n(z) + 1e-100*y(z-1) # The 0*y(z-1) is a workaround for a bug in the compiler, to force the y variable to be a discrete-time state variable
u ~ input.u
else
y(z) ~ n(z) + 1e-100*y(z-1)
end
end
end

"""
seeded_randn(seed, t)
Internal function. This function seeds the seed parameter as well as the current simulation time.
"""
function seeded_randn(seed, t)
rng = StableRNGs.StableRNG(hash(t, hash(seed)))
randn(rng)
end
"""
seeded_rand(seed, t)
Internal function. This function seeds the seed parameter as well as the current simulation time.
"""
function seeded_rand(seed, t)
rng = StableRNGs.StableRNG(hash(t, hash(seed)))
rand(rng)
end

"""
UniformNoise()
Expand All @@ -182,6 +215,7 @@ A discrete-time noise source that returns a uniformly distributed value at each
# Parameters
- `l = 0`: Lower bound
- `u = 1`: Upper bound
- `seed = 1`: Seed for the random number generator
# Structural parameters
- `rng`: A random number generator, defaults to `Random.Xoshiro()`.
Expand All @@ -191,26 +225,70 @@ A discrete-time noise source that returns a uniformly distributed value at each
- `output`
"""
@mtkmodel UniformNoise begin
@structural_parameters begin
z = ShiftIndex()
rng = Random.Xoshiro()
additive = false
end
@components begin
output = RealOutput()
if additive
input = RealInput()
end
end
@variables begin
y(t), [description = "Output variable"]
n(t), [description = "Internal noise variable"]
end
@parameters begin
l = 0
u = 1
end
@structural_parameters begin
z = ShiftIndex()
rng = Random.Xoshiro()
seed = 1
end
@equations begin
y(z) ~ l + (u-l)*Symbolics.term(rand, rng; type=Real)
output.u ~ y
n(z) ~ l + (u-l)*Symbolics.term(seeded_rand, seed, t; type=Real)
# y(z) ~ l + (u-l)*Symbolics.term(rand, rng; type=Real)

if additive
y(z) ~ input.u(z) + n(z) + 1e-100*y(z-1) # The 0*y(z-1) is a workaround for a bug in the compiler, to force the y variable to be a discrete-time state variable
else
y(z) ~ n(z) + 1e-100*y(z-1)
end
end
end

"""
GenericNoise()
A discrete-time noise source that at each clock tick returns a random value distributed according to the provided distribution.
# Structural parameters
- `rng`: A random number generator, defaults to `Random.Xoshiro()`.
- `z`: The `ShiftIndex` used to indicate clock partition.
- `d`: The distribution to sample from.`
# Connectors:
- `output`
"""
# @mtkmodel GenericNoise begin
# @components begin
# output = RealOutput()
# end
# @variables begin
# y(t), [description = "Output variable"]
# end
# @structural_parameters begin
# z = ShiftIndex()
# rng = Random.Xoshiro()
# d
# end
# @equations begin
# y(z) ~ Symbolics.term(rand, rng, d; type=Real)
# output.u ~ y
# end
# end

"""
ZeroOrderHold()
Expand Down
Loading

0 comments on commit 070a375

Please sign in to comment.