Skip to content

Commit e16b9e5

Browse files
committed
doc: modify NonLinMPC pendulum example in manual with new p argument
1 parent 643754d commit e16b9e5

File tree

12 files changed

+101
-96
lines changed

12 files changed

+101
-96
lines changed

docs/src/manual/nonlinmpc.md

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -40,34 +40,34 @@ The plant model is nonlinear:
4040

4141
in which ``g`` is the gravitational acceleration in m/s², ``L``, the pendulum length in m,
4242
``K``, the friction coefficient at the pivot point in kg/s, and ``m``, the mass attached at
43-
the end of the pendulum in kg. The [`NonLinModel`](@ref) constructor assumes by default
44-
that the state function `f` is continuous in time, that is, an ordinary differential
45-
equation system (like here):
43+
the end of the pendulum in kg, all bundled in the parameter vector ``\mathbf{p} =
44+
[\begin{smallmatrix} g & L & K & m \end{smallmatrix}]'``. The [`NonLinModel`](@ref)
45+
constructor assumes by default that the state function `f` is continuous in time, that is,
46+
an ordinary differential equation system (like here):
4647

4748
```@example 1
4849
using ModelPredictiveControl
49-
function pendulum(par, x, u)
50-
g, L, K, m = par # [m/s²], [m], [kg/s], [kg]
50+
function f(x, u, _ , p)
51+
g, L, K, m = p # [m/s²], [m], [kg/s], [kg]
5152
θ, ω = x[1], x[2] # [rad], [rad/s]
5253
τ = u[1] # [Nm]
5354
dθ = ω
5455
dω = -g/L*sin(θ) - K/m*ω + τ/m/L^2
5556
return [dθ, dω]
5657
end
57-
# declared constants, to avoid type-instability in the f function, for speed:
58-
const par = (9.8, 0.4, 1.2, 0.3)
59-
f(x, u, _ ) = pendulum(par, x, u)
60-
h(x, _ ) = [180/π*x[1]] # [°]
58+
h(x, _ , _ ) = [180/π*x[1]] # [°]
59+
p_model = [9.8, 0.4, 1.2, 0.3]
6160
nu, nx, ny, Ts = 1, 2, 1, 0.1
6261
vu, vx, vy = ["\$τ\$ (Nm)"], ["\$θ\$ (rad)", "\$ω\$ (rad/s)"], ["\$θ\$ (°)"]
63-
model = setname!(NonLinModel(f, h, Ts, nu, nx, ny); u=vu, x=vx, y=vy)
62+
model = setname!(NonLinModel(f, h, Ts, nu, nx, ny; p=p_model); u=vu, x=vx, y=vy)
6463
```
6564

6665
The output function ``\mathbf{h}`` converts the ``θ`` angle to degrees. Note that special
6766
characters like ``θ`` can be typed in the Julia REPL or VS Code by typing `\theta` and
68-
pressing the `<TAB>` key. The tuple `par` is constant here to improve the [performance](https://docs.julialang.org/en/v1/manual/performance-tips/#Avoid-untyped-global-variables).
69-
A 4th order [`RungeKutta`](@ref) method solves the differential equations by default. It is
70-
good practice to first simulate `model` using [`sim!`](@ref) as a quick sanity check:
67+
pressing the `<TAB>` key. Note that the model parameter `p` can be any
68+
A 4th order [`RungeKutta`](@ref) method solves the differential
69+
equations by default. It is good practice to first simulate `model` using [`sim!`](@ref) as
70+
a quick sanity check:
7171

7272
```@example 1
7373
using Plots
@@ -101,9 +101,9 @@ motor torque ``τ``, with an associated standard deviation `σQint_u` of 0.1 N m
101101
estimator tuning is tested on a plant with a 25 % larger friction coefficient ``K``:
102102

103103
```@example 1
104-
const par_plant = (par[1], par[2], 1.25*par[3], par[4])
105-
f_plant(x, u, _ ) = pendulum(par_plant, x, u)
106-
plant = setname!(NonLinModel(f_plant, h, Ts, nu, nx, ny); u=vu, x=vx, y=vy)
104+
p_plant = copy(p_model)
105+
p_plant[3] = 1.25*p_model[3]
106+
plant = setname!(NonLinModel(f, h, Ts, nu, nx, ny; p=p_plant); u=vu, x=vx, y=vy)
107107
res = sim!(estim, N, [0.5], plant=plant, y_noise=[0.5])
108108
plot(res, plotu=false, plotxwithx̂=true)
109109
savefig("plot2_NonLinMPC.svg"); nothing # hide
@@ -182,10 +182,10 @@ angle ``θ`` is measured here). As the arguments of [`NonLinMPC`](@ref) economic
182182
Kalman Filter similar to the previous one (``\mathbf{y^m} = θ`` and ``\mathbf{y^u} = ω``):
183183

184184
```@example 1
185-
h2(x, _ ) = [180/π*x[1], x[2]]
185+
h2(x, _ , _ ) = [180/π*x[1], x[2]]
186186
nu, nx, ny = 1, 2, 2
187-
model2 = setname!(NonLinModel(f , h2, Ts, nu, nx, ny), u=vu, x=vx, y=[vy; vx[2]])
188-
plant2 = setname!(NonLinModel(f_plant, h2, Ts, nu, nx, ny), u=vu, x=vx, y=[vy; vx[2]])
187+
model2 = setname!(NonLinModel(f, h2, Ts, nu, nx, ny; p=p_model), u=vu, x=vx, y=[vy; vx[2]])
188+
plant2 = setname!(NonLinModel(f, h2, Ts, nu, nx, ny; p=p_plant), u=vu, x=vx, y=[vy; vx[2]])
189189
estim2 = UnscentedKalmanFilter(model2; σQ, σR, nint_u, σQint_u, i_ym=[1])
190190
```
191191

src/controller/nonlinmpc.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -159,7 +159,7 @@ This method uses the default state estimator :
159159
160160
# Examples
161161
```jldoctest
162-
julia> model = NonLinModel((x,u,_)->0.5x+u, (x,_)->2x, 10.0, 1, 1, 1, solver=nothing);
162+
julia> model = NonLinModel((x,u,_,_)->0.5x+u, (x,_,_)->2x, 10.0, 1, 1, 1, solver=nothing);
163163
164164
julia> mpc = NonLinMPC(model, Hp=20, Hc=1, Cwt=1e6)
165165
NonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, UnscentedKalmanFilter estimator and:
@@ -236,7 +236,7 @@ Use custom state estimator `estim` to construct `NonLinMPC`.
236236
237237
# Examples
238238
```jldoctest
239-
julia> model = NonLinModel((x,u,_)->0.5x+u, (x,_)->2x, 10.0, 1, 1, 1, solver=nothing);
239+
julia> model = NonLinModel((x,u,_,_)->0.5x+u, (x,_,_)->2x, 10.0, 1, 1, 1, solver=nothing);
240240
241241
julia> estim = UnscentedKalmanFilter(model, σQint_ym=[0.05]);
242242

src/estimator/kalman.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -623,7 +623,7 @@ initial state estimate ``\mathbf{x̂}_{-1}(0)`` can be manually specified with [
623623
624624
# Examples
625625
```jldoctest
626-
julia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1, solver=nothing);
626+
julia> model = NonLinModel((x,u,_,_)->0.1x+u, (x,_,_)->2x, 10.0, 1, 1, 1, solver=nothing);
627627
628628
julia> estim = UnscentedKalmanFilter(model, σR=[1], nint_ym=[2], σPint_ym_0=[1, 1])
629629
UnscentedKalmanFilter estimator with a sample time Ts = 10.0 s, NonLinModel and:
@@ -951,7 +951,7 @@ automatic differentiation.
951951
952952
# Examples
953953
```jldoctest
954-
julia> model = NonLinModel((x,u,_)->0.2x+u, (x,_)->-3x, 5.0, 1, 1, 1, solver=nothing);
954+
julia> model = NonLinModel((x,u,_,_)->0.2x+u, (x,_,_)->-3x, 5.0, 1, 1, 1, solver=nothing);
955955
956956
julia> estim = ExtendedKalmanFilter(model, σQ=[2], σQint_ym=[2], σP_0=[0.1], σPint_ym_0=[0.1])
957957
ExtendedKalmanFilter estimator with a sample time Ts = 5.0 s, NonLinModel and:

src/estimator/mhe/construct.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -256,7 +256,7 @@ See [`UnscentedKalmanFilter`](@ref) for details on the augmented process model a
256256
257257
# Examples
258258
```jldoctest
259-
julia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1, solver=nothing);
259+
julia> model = NonLinModel((x,u,_,_)->0.1x+u, (x,_,_)->2x, 10.0, 1, 1, 1, solver=nothing);
260260
261261
julia> estim = MovingHorizonEstimator(model, He=5, σR=[1], σP_0=[0.01])
262262
MovingHorizonEstimator estimator with a sample time Ts = 10.0 s, Ipopt optimizer, NonLinModel and:

src/model/linearization.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ necessarily an equilibrium, details in Extended Help). The Jacobians of ``\mathb
2121
2222
# Examples
2323
```jldoctest
24-
julia> model = NonLinModel((x,u,_)->x.^3 + u, (x,_)->x, 0.1, 1, 1, 1, solver=nothing);
24+
julia> model = NonLinModel((x,u,_,_)->x.^3 + u, (x,_,_)->x, 0.1, 1, 1, 1, solver=nothing);
2525
2626
julia> linmodel = linearize(model, x=[10.0], u=[0.0]);
2727
@@ -96,7 +96,7 @@ The keyword arguments are identical to [`linearize`](@ref).
9696
9797
# Examples
9898
```jldoctest
99-
julia> model = NonLinModel((x,u,_)->x.^3 + u, (x,_)->x, 0.1, 1, 1, 1, solver=nothing);
99+
julia> model = NonLinModel((x,u,_,_)->x.^3 + u, (x,_,_)->x, 0.1, 1, 1, 1, solver=nothing);
100100
101101
julia> linmodel = linearize(model, x=[10.0], u=[0.0]); linmodel.A
102102
1×1 Matrix{Float64}:

src/model/nonlinmodel.jl

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,8 @@ functions are defined as:
6969
```
7070
where ``\mathbf{x}``, ``\mathbf{y}, ``\mathbf{u}``, ``\mathbf{d}`` and ``\mathbf{p}`` are
7171
respectively the state, output, manipulated input, measured disturbance and parameter vectors,
72-
and ``t`` the time in second. The functions can be implemented in two possible ways:
72+
and ``t`` the time in second. If the dynamics is a function of time, simply add a measured
73+
disturbance defined as ``d(t)=t``. The functions can be implemented in two possible ways:
7374
7475
1. **Non-mutating functions** (out-of-place): define them as `f(x, u, d, p) -> ẋ` and
7576
`h(x, d, p) -> y`. This syntax is simple and intuitive but it allocates more memory.

src/plot_sim.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ internal states.
118118
119119
# Examples
120120
```jldoctest
121-
julia> plant = NonLinModel((x,u,d)->0.1x+u+d, (x,_)->2x, 10.0, 1, 1, 1, 1, solver=nothing);
121+
julia> plant = NonLinModel((x,u,d,_)->0.1x+u+d, (x,_,_)->2x, 5, 1, 1, 1, 1, solver=nothing);
122122
123123
julia> res = sim!(plant, 15, [0], [0], x_0=[1])
124124
Simulation results of NonLinModel with 15 time steps.

src/precompile.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -74,8 +74,8 @@ exmpc.estim()
7474
u = exmpc([55, 30])
7575
sim!(exmpc, 3, [55, 30])
7676

77-
f(x,u,_) = model.A*x + model.Bu*u
78-
h(x,_) = model.C*x
77+
f(x,u,_,_) = model.A*x + model.Bu*u
78+
h(x,_,_) = model.C*x
7979

8080
nlmodel = setop!(NonLinModel(f, h, Ts, 2, 2, 2, solver=nothing), uop=[10, 10], yop=[50, 30])
8181
y = nlmodel()

src/sim_model.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ Functor allowing callable `SimModel` object as an alias for [`evaloutput`](@ref)
1111
1212
# Examples
1313
```jldoctest
14-
julia> model = NonLinModel((x,u,_)->-x + u, (x,_)->x .+ 20, 10.0, 1, 1, 1, solver=nothing);
14+
julia> model = NonLinModel((x,u,_,_)->-x + u, (x,_,_)->x .+ 20, 4, 1, 1, 1, solver=nothing);
1515
1616
julia> y = model()
1717
1-element Vector{Float64}:

test/test_predictive_control.jl

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -474,8 +474,8 @@ end
474474
linmodel1 = LinModel(sys,Ts,i_d=[3])
475475
nmpc0 = NonLinMPC(linmodel1, Hp=15)
476476
@test isa(nmpc0.estim, SteadyKalmanFilter)
477-
f = (x,u,d) -> linmodel1.A*x + linmodel1.Bu*u + linmodel1.Bd*d
478-
h = (x,d) -> linmodel1.C*x + linmodel1.Dd*d
477+
f = (x,u,d,_) -> linmodel1.A*x + linmodel1.Bu*u + linmodel1.Bd*d
478+
h = (x,d,_) -> linmodel1.C*x + linmodel1.Dd*d
479479
nonlinmodel = NonLinModel(f, h, Ts, 2, 4, 2, 1, solver=nothing)
480480
nmpc1 = NonLinMPC(nonlinmodel, Hp=15)
481481
@test isa(nmpc1.estim, UnscentedKalmanFilter)
@@ -545,8 +545,8 @@ end
545545
# ensure that the current estimated output is updated for correct JE values:
546546
@test nmpc. evaloutput(nmpc.estim, Float64[])
547547
linmodel2 = LinModel([tf(5, [2000, 1]) tf(7, [8000,1])], 3000.0, i_d=[2])
548-
f = (x,u,d) -> linmodel2.A*x + linmodel2.Bu*u + linmodel2.Bd*d
549-
h = (x,d) -> linmodel2.C*x + linmodel2.Dd*d
548+
f = (x,u,d,_) -> linmodel2.A*x + linmodel2.Bu*u + linmodel2.Bd*d
549+
h = (x,d,_) -> linmodel2.C*x + linmodel2.Dd*d
550550
nonlinmodel = NonLinModel(f, h, 3000.0, 1, 2, 1, 1, solver=nothing)
551551
nmpc2 = NonLinMPC(nonlinmodel, Nwt=[0], Hp=1000, Hc=1)
552552
d = [0.1]
@@ -628,8 +628,8 @@ end
628628

629629
@testset "NonLinMPC other methods" begin
630630
linmodel = setop!(LinModel(sys,Ts,i_u=[1,2]), uop=[10,50], yop=[50,30])
631-
f = (x,u,_) -> linmodel.A*x + linmodel.Bu*u
632-
h = (x,_) -> linmodel.C*x
631+
f = (x,u,_,_) -> linmodel.A*x + linmodel.Bu*u
632+
h = (x,_,_) -> linmodel.C*x
633633
nonlinmodel = setop!(
634634
NonLinModel(f, h, Ts, 2, 2, 2, solver=nothing), uop=[10,50], yop=[50,30]
635635
)
@@ -652,8 +652,8 @@ end
652652
setconstraint!(nmpc_lin, c_ymin=[1.0,1.1], c_ymax=[1.2,1.3])
653653
@test all((-nmpc_lin.con.A_Ymin[:, end], -nmpc_lin.con.A_Ymax[:, end]) .≈ ([1.0,1.1], [1.2,1.3]))
654654

655-
f = (x,u,d) -> linmodel1.A*x + linmodel1.Bu*u + linmodel1.Bd*d
656-
h = (x,d) -> linmodel1.C*x + linmodel1.Dd*d
655+
f = (x,u,d,_) -> linmodel1.A*x + linmodel1.Bu*u + linmodel1.Bd*d
656+
h = (x,d,_) -> linmodel1.C*x + linmodel1.Dd*d
657657
nonlinmodel = NonLinModel(f, h, Ts, 2, 4, 2, 1, solver=nothing)
658658
nmpc = NonLinMPC(nonlinmodel, Hp=1, Hc=1)
659659

@@ -715,8 +715,8 @@ end
715715
info = getinfo(nmpc_lin)
716716
@test info[:x̂end][1] 0 atol=1e-1
717717

718-
f = (x,u,_) -> linmodel.A*x + linmodel.Bu*u
719-
h = (x,_) -> linmodel.C*x
718+
f = (x,u,_,_) -> linmodel.A*x + linmodel.Bu*u
719+
h = (x,_,_) -> linmodel.C*x
720720
nonlinmodel = NonLinModel(f, h, linmodel.Ts, 1, 1, 1, solver=nothing)
721721
nmpc = NonLinMPC(nonlinmodel, Hp=50, Hc=5)
722722

@@ -791,8 +791,8 @@ end
791791
@test mpc.M_Hp diagm(1:1000)
792792
@test mpc.Ñ_Hc diagm([0.1;1e6])
793793
@test mpc.L_Hp diagm(1.1:1000.1)
794-
f = (x,u,d) -> estim.model.A*x + estim.model.Bu*u + estim.model.Bd*d
795-
h = (x,d) -> estim.model.C*x + estim.model.Du*d
794+
f = (x,u,d,_) -> estim.model.A*x + estim.model.Bu*u + estim.model.Bd*d
795+
h = (x,d,_) -> estim.model.C*x + estim.model.Du*d
796796
nonlinmodel = NonLinModel(f, h, 10.0, 1, 1, 1)
797797
nmpc = NonLinMPC(nonlinmodel, Nwt=[0], Cwt=1e4, Hp=1000, Hc=10)
798798
setmodel!(nmpc, Mwt=[100], Nwt=[200], Lwt=[300])
@@ -808,8 +808,8 @@ end
808808

809809
@testset "LinMPC v.s. NonLinMPC" begin
810810
linmodel = setop!(LinModel(sys,Ts,i_d=[3]), uop=[10,50], yop=[50,30], dop=[20])
811-
f = (x,u,d) -> linmodel.A*x + linmodel.Bu*u + linmodel.Bd*d
812-
h = (x,d) -> linmodel.C*x + linmodel.Dd*d
811+
f = (x,u,d,_) -> linmodel.A*x + linmodel.Bu*u + linmodel.Bd*d
812+
h = (x,d,_) -> linmodel.C*x + linmodel.Dd*d
813813
nonlinmodel = NonLinModel(f, h, Ts, 2, 4, 2, 1, solver=nothing)
814814
nonlinmodel = setop!(nonlinmodel, uop=[10,50], yop=[50,30], dop=[20])
815815
optim = JuMP.Model(optimizer_with_attributes(Ipopt.Optimizer, "sb"=>"yes"))

0 commit comments

Comments
 (0)