Skip to content

Commit feaf0ef

Browse files
committed
changed: moved lastu0 inside PredictiveController objects
1 parent b86dbd7 commit feaf0ef

File tree

10 files changed

+40
-42
lines changed

10 files changed

+40
-42
lines changed

src/controller/execute.jl

Lines changed: 21 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -2,9 +2,13 @@
22
initstate!(mpc::PredictiveController, u, ym, d=[]) -> x̂
33
44
Init the states of `mpc.estim` [`StateEstimator`](@ref) and warm start `mpc.Z̃` at zero.
5+
6+
It also stores `u - mpc.estim.model.uop` at `mpc.lastu0` for converting the input increments
7+
``\mathbf{ΔU}`` to inputs ``\mathbf{U}``.
58
"""
69
function initstate!(mpc::PredictiveController, u, ym, d=mpc.estim.buffer.empty)
710
mpc.Z̃ .= 0
11+
mpc.lastu0 .= u .- mpc.estim.model.uop
812
return initstate!(mpc.estim, u, ym, d)
913
end
1014

@@ -16,10 +20,11 @@ Compute the optimal manipulated input value `u` for the current control period.
1620
Solve the optimization problem of `mpc` [`PredictiveController`](@ref) and return the
1721
results ``\mathbf{u}(k)``. Following the receding horizon principle, the algorithm discards
1822
the optimal future manipulated inputs ``\mathbf{u}(k+1), \mathbf{u}(k+2), ...`` Note that
19-
the method mutates `mpc` internal data but it does not modifies `mpc.estim` states. Call
20-
[`preparestate!(mpc, ym, d)`](@ref) before `moveinput!`, and [`updatestate!(mpc, u, ym, d)`](@ref)
21-
after, to update `mpc` state estimates. Setpoint and measured disturbance previews can
22-
be implemented with the `R̂y`, `R̂u` and `D̂` keyword arguments.
23+
the method mutates `mpc` internal data (it stores `u - mpc.estim.model.uop` at `mpc.lastu0`
24+
for instance) but it does not modifies `mpc.estim` states. Call [`preparestate!(mpc, ym, d)`](@ref)
25+
before `moveinput!`, and [`updatestate!(mpc, u, ym, d)`](@ref) after, to update `mpc` state
26+
estimates. Setpoint and measured disturbance previews can be implemented with the `R̂y`, `R̂u`
27+
and `D̂` keyword arguments.
2328
2429
Calling a [`PredictiveController`](@ref) object calls this method.
2530
@@ -69,7 +74,7 @@ function moveinput!(
6974
linconstraint!(mpc, mpc.estim.model, mpc.transcription)
7075
linconstrainteq!(mpc, mpc.estim.model, mpc.transcription)
7176
= optim_objective!(mpc)
72-
return getinput(mpc, Z̃)
77+
return getinput!(mpc, Z̃)
7378
end
7479

7580
@doc raw"""
@@ -207,7 +212,7 @@ function initpred!(mpc::PredictiveController, model::LinModel, d, D̂, R̂y, R̂
207212
F = initpred_common!(mpc, model, d, D̂, R̂y, R̂u)
208213
F .+= mpc.B # F = F + B
209214
mul!(F, mpc.K, mpc.estim.x̂0, 1, 1) # F = F + K*x̂0
210-
mul!(F, mpc.V, mpc.estim.lastu0, 1, 1) # F = F + V*lastu0
215+
mul!(F, mpc.V, mpc.lastu0, 1, 1) # F = F + V*lastu0
211216
if model.nd > 0
212217
mul!(F, mpc.G, mpc.d0, 1, 1) # F = F + G*d0
213218
mul!(F, mpc.J, mpc.D̂0, 1, 1) # F = F + J*D̂0
@@ -254,7 +259,7 @@ Will also init `mpc.F` with 0 values, or with the stochastic predictions `Ŷs`
254259
is an [`InternalModel`](@ref). The function returns `mpc.F`.
255260
"""
256261
function initpred_common!(mpc::PredictiveController, model::SimModel, d, D̂, R̂y, R̂u)
257-
mul!(mpc.Tu_lastu0, mpc.Tu, mpc.estim.lastu0)
262+
mul!(mpc.Tu_lastu0, mpc.Tu, mpc.lastu0)
258263
mpc.ŷ .= evaloutput(mpc.estim, d)
259264
if model.nd > 0
260265
mpc.d0 .= d .- model.dop
@@ -446,20 +451,23 @@ function preparestate!(mpc::PredictiveController, ym, d=mpc.estim.buffer.empty)
446451
end
447452

448453
@doc raw"""
449-
getinput(mpc::PredictiveController, Z̃) -> u
454+
getinput!(mpc::PredictiveController, Z̃) -> u
450455
451-
Get current manipulated input `u` from a [`PredictiveController`](@ref) solution `Z̃`.
456+
Get current manipulated input `u` from the solution `Z̃`, store it and return it.
452457
453458
The first manipulated input ``\mathbf{u}(k)`` is extracted from the decision vector
454-
``\mathbf{Z̃}`` and applied on the plant (from the receding horizon principle).
459+
``\mathbf{Z̃}`` and applied on the plant (from the receding horizon principle). It also
460+
stores `u - mpc.estim.model.uop` at `mpc.lastu0`.
455461
"""
456-
function getinput(mpc, Z̃)
462+
function getinput!(mpc, Z̃)
463+
model = mpc.estim.model
457464
Δu = mpc.buffer.u
458-
for i in 1:mpc.estim.model.nu
465+
for i in 1:model.nu
459466
Δu[i] = Z̃[i]
460467
end
461468
u = Δu
462-
u .+= mpc.estim.lastu0 .+ mpc.estim.model.uop
469+
u .+= mpc.lastu0 .+ model.uop
470+
mpc.lastu0 .= u .- model.uop
463471
return u
464472
end
465473

src/controller/explicitmpc.jl

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ struct ExplicitMPC{
1313
weights::CW
1414
R̂u::Vector{NT}
1515
R̂y::Vector{NT}
16+
lastu0::Vector{NT}
1617
P̃Δu::Matrix{NT}
1718
P̃u ::Matrix{NT}
1819
Tu ::Matrix{NT}
@@ -46,6 +47,7 @@ struct ExplicitMPC{
4647
= 0 # no slack variable ϵ for ExplicitMPC
4748
# dummy vals (updated just before optimization):
4849
R̂y, R̂u, Tu_lastu0 = zeros(NT, ny*Hp), zeros(NT, nu*Hp), zeros(NT, nu*Hp)
50+
lastu0 = zeros(NT, nu)
4951
transcription = SingleShooting() # explicit MPC only supports SingleShooting
5052
PΔu = init_ZtoΔU(estim, transcription, Hp, Hc)
5153
Pu, Tu = init_ZtoU(estim, transcription, Hp, Hc)
@@ -71,6 +73,7 @@ struct ExplicitMPC{
7173
Hp, Hc, nϵ,
7274
weights,
7375
R̂u, R̂y,
76+
lastu0,
7477
P̃Δu, P̃u, Tu, Tu_lastu0,
7578
Ẽ, F, G, J, K, V, B,
7679
H̃, q̃, r,

src/controller/linmpc.jl

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ struct LinMPC{
2222
weights::CW
2323
R̂u::Vector{NT}
2424
R̂y::Vector{NT}
25+
lastu0::Vector{NT}
2526
P̃Δu::Matrix{NT}
2627
P̃u ::Matrix{NT}
2728
Tu ::Matrix{NT}
@@ -60,6 +61,7 @@ struct LinMPC{
6061
= copy(model.yop) # dummy vals (updated just before optimization)
6162
# dummy vals (updated just before optimization):
6263
R̂y, R̂u, Tu_lastu0 = zeros(NT, ny*Hp), zeros(NT, nu*Hp), zeros(NT, nu*Hp)
64+
lastu0 = zeros(NT, ny)
6365
PΔu = init_ZtoΔU(estim, transcription, Hp, Hc)
6466
Pu, Tu = init_ZtoU(estim, transcription, Hp, Hc)
6567
E, G, J, K, V, B, ex̂, gx̂, jx̂, kx̂, vx̂, bx̂ = init_predmat(
@@ -91,6 +93,7 @@ struct LinMPC{
9193
Hp, Hc, nϵ,
9294
weights,
9395
R̂u, R̂y,
96+
lastu0,
9497
P̃Δu, P̃u, Tu, Tu_lastu0,
9598
Ẽ, F, G, J, K, V, B,
9699
H̃, q̃, r,

src/controller/nonlinmpc.jl

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@ struct NonLinMPC{
3838
p::PT
3939
R̂u::Vector{NT}
4040
R̂y::Vector{NT}
41+
lastu0::Vector{NT}
4142
P̃Δu::Matrix{NT}
4243
P̃u ::Matrix{NT}
4344
Tu ::Matrix{NT}
@@ -83,6 +84,7 @@ struct NonLinMPC{
8384
= copy(model.yop) # dummy vals (updated just before optimization)
8485
# dummy vals (updated just before optimization):
8586
R̂y, R̂u, Tu_lastu0 = zeros(NT, ny*Hp), zeros(NT, nu*Hp), zeros(NT, nu*Hp)
87+
lastu0 = zeros(NT, nu)
8688
PΔu = init_ZtoΔU(estim, transcription, Hp, Hc)
8789
Pu, Tu = init_ZtoU(estim, transcription, Hp, Hc)
8890
E, G, J, K, V, B, ex̂, gx̂, jx̂, kx̂, vx̂, bx̂ = init_predmat(
@@ -118,6 +120,7 @@ struct NonLinMPC{
118120
weights,
119121
JE, p,
120122
R̂u, R̂y,
123+
lastu0,
121124
P̃Δu, P̃u, Tu, Tu_lastu0,
122125
Ẽ, F, G, J, K, V, B,
123126
H̃, q̃, r,

src/controller/transcription.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -852,7 +852,7 @@ function linconstraint!(mpc::PredictiveController, model::LinModel, ::Transcript
852852
nx̂, fx̂ = mpc.estim.nx̂, mpc.con.fx̂
853853
fx̂ .= mpc.con.bx̂
854854
mul!(fx̂, mpc.con.kx̂, mpc.estim.x̂0, 1, 1)
855-
mul!(fx̂, mpc.con.vx̂, mpc.estim.lastu0, 1, 1)
855+
mul!(fx̂, mpc.con.vx̂, mpc.lastu0, 1, 1)
856856
if model.nd > 0
857857
mul!(fx̂, mpc.con.gx̂, mpc.d0, 1, 1)
858858
mul!(fx̂, mpc.con.jx̂, mpc.D̂0, 1, 1)
@@ -938,7 +938,7 @@ function linconstrainteq!(mpc::PredictiveController, model::LinModel, ::Multiple
938938
Fŝ = mpc.con.Fŝ
939939
Fŝ .= mpc.con.Bŝ
940940
mul!(Fŝ, mpc.con.Kŝ, mpc.estim.x̂0, 1, 1)
941-
mul!(Fŝ, mpc.con.Vŝ, mpc.estim.lastu0, 1, 1)
941+
mul!(Fŝ, mpc.con.Vŝ, mpc.lastu0, 1, 1)
942942
if model.nd > 0
943943
mul!(Fŝ, mpc.con.Gŝ, mpc.d0, 1, 1)
944944
mul!(Fŝ, mpc.con.Jŝ, mpc.D̂0, 1, 1)

src/estimator/execute.jl

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2,17 +2,13 @@
22
remove_op!(estim::StateEstimator, ym, d, u=nothing) -> y0m, d0, u0
33
44
Remove operating pts on measured outputs `ym`, disturbances `d` and inputs `u` (if provided).
5-
6-
If `u` is provided, also store current inputs without operating points `u0` in
7-
`estim.lastu0`. This field is used for [`PredictiveController`](@ref) computations.
85
"""
96
function remove_op!(estim::StateEstimator, ym, d, u=nothing)
107
y0m, u0, d0 = estim.buffer.ym, estim.buffer.u, estim.buffer.d
118
y0m .= @views ym .- estim.model.yop[estim.i_ym]
129
d0 .= d .- estim.model.dop
1310
if !isnothing(u)
1411
u0 .= u .- estim.model.uop
15-
estim.lastu0 .= u0
1612
end
1713
return y0m, d0, u0
1814
end
@@ -108,8 +104,7 @@ end
108104
Init `estim.x̂0` states from current inputs `u`, measured outputs `ym` and disturbances `d`.
109105
110106
The method tries to find a good steady-state for the initial estimate ``\mathbf{x̂}``. It
111-
stores `u - estim.model.uop` at `estim.lastu0` and removes the operating points with
112-
[`remove_op!`](@ref), and call [`init_estimate!`](@ref):
107+
removes the operating points with [`remove_op!`](@ref) and call [`init_estimate!`](@ref):
113108
114109
- If `estim.model` is a [`LinModel`](@ref), it finds the steady-state of the augmented model
115110
using `u` and `d` arguments, and uses the `ym` argument to enforce that

src/estimator/internal_model.jl

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
struct InternalModel{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
22
model::SM
3-
lastu0::Vector{NT}
43
x̂op::Vector{NT}
54
f̂op::Vector{NT}
65
x̂0 ::Vector{NT}
@@ -41,7 +40,6 @@ struct InternalModel{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
4140
Â, B̂u, Ĉ, B̂d, D̂d, x̂op, f̂op = matrices_internalmodel(model)
4241
Ĉm, D̂dm = Ĉ[i_ym,:], D̂d[i_ym,:]
4342
Âs, B̂s = init_internalmodel(As, Bs, Cs, Ds)
44-
lastu0 = zeros(NT, nu)
4543
# x̂0 and x̂d are same object (updating x̂d will update x̂0):
4644
x̂d = x̂0 = zeros(NT, model.nx)
4745
x̂s, x̂snext = zeros(NT, nxs), zeros(NT, nxs)
@@ -51,7 +49,7 @@ struct InternalModel{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
5149
buffer = StateEstimatorBuffer{NT}(nu, nx̂, nym, ny, nd, nk)
5250
return new{NT, SM}(
5351
model,
54-
lastu0, x̂op, f̂op, x̂0, x̂d, x̂s, ŷs, x̂snext,
52+
x̂op, f̂op, x̂0, x̂d, x̂s, ŷs, x̂snext,
5553
i_ym, nx̂, nym, nyu, nxs,
5654
As, Bs, Cs, Ds,
5755
Â, B̂u, Ĉ, B̂d, D̂d, Ĉm, D̂dm,

src/estimator/kalman.jl

Lines changed: 4 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
struct SteadyKalmanFilter{NT<:Real, SM<:LinModel} <: StateEstimator{NT}
22
model::SM
3-
lastu0::Vector{NT}
43
x̂op ::Vector{NT}
54
f̂op ::Vector{NT}
65
x̂0 ::Vector{NT}
@@ -56,14 +55,13 @@ struct SteadyKalmanFilter{NT<:Real, SM<:LinModel} <: StateEstimator{NT}
5655
rethrow()
5756
end
5857
end
59-
lastu0 = zeros(NT, nu)
6058
x̂0 = [zeros(NT, model.nx); zeros(NT, nxs)]
6159
Q̂, R̂ = Hermitian(Q̂, :L), Hermitian(R̂, :L)
6260
corrected = [false]
6361
buffer = StateEstimatorBuffer{NT}(nu, nx̂, nym, ny, nd, nk)
6462
return new{NT, SM}(
6563
model,
66-
lastu0, x̂op, f̂op, x̂0,
64+
x̂op, f̂op, x̂0,
6765
i_ym, nx̂, nym, nyu, nxs,
6866
As, Cs_u, Cs_y, nint_u, nint_ym,
6967
Â, B̂u, Ĉ, B̂d, D̂d, Ĉm, D̂dm,
@@ -279,7 +277,6 @@ end
279277

280278
struct KalmanFilter{NT<:Real, SM<:LinModel} <: StateEstimator{NT}
281279
model::SM
282-
lastu0::Vector{NT}
283280
x̂op::Vector{NT}
284281
f̂op::Vector{NT}
285282
x̂0 ::Vector{NT}
@@ -319,7 +316,6 @@ struct KalmanFilter{NT<:Real, SM<:LinModel} <: StateEstimator{NT}
319316
Â, B̂u, Ĉ, B̂d, D̂d, x̂op, f̂op = augment_model(model, As, Cs_u, Cs_y)
320317
Ĉm, D̂dm = Ĉ[i_ym, :], D̂d[i_ym, :]
321318
validate_kfcov(nym, nx̂, Q̂, R̂, P̂_0)
322-
lastu0 = zeros(NT, nu)
323319
x̂0 = [zeros(NT, model.nx); zeros(NT, nxs)]
324320
Q̂, R̂ = Hermitian(Q̂, :L), Hermitian(R̂, :L)
325321
P̂_0 = Hermitian(P̂_0, :L)
@@ -329,7 +325,7 @@ struct KalmanFilter{NT<:Real, SM<:LinModel} <: StateEstimator{NT}
329325
buffer = StateEstimatorBuffer{NT}(nu, nx̂, nym, ny, nd, nk)
330326
return new{NT, SM}(
331327
model,
332-
lastu0, x̂op, f̂op, x̂0, P̂,
328+
x̂op, f̂op, x̂0, P̂,
333329
i_ym, nx̂, nym, nyu, nxs,
334330
As, Cs_u, Cs_y, nint_u, nint_ym,
335331
Â, B̂u, Ĉ, B̂d, D̂d, Ĉm, D̂dm,
@@ -493,7 +489,6 @@ end
493489

494490
struct UnscentedKalmanFilter{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
495491
model::SM
496-
lastu0::Vector{NT}
497492
x̂op ::Vector{NT}
498493
f̂op ::Vector{NT}
499494
x̂0 ::Vector{NT}
@@ -543,7 +538,6 @@ struct UnscentedKalmanFilter{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
543538
Ĉm, D̂dm = Ĉ[i_ym, :], D̂d[i_ym, :]
544539
validate_kfcov(nym, nx̂, Q̂, R̂, P̂_0)
545540
nσ, γ, m̂, Ŝ = init_ukf(model, nx̂, α, β, κ)
546-
lastu0 = zeros(NT, nu)
547541
x̂0 = [zeros(NT, model.nx); zeros(NT, nxs)]
548542
Q̂, R̂ = Hermitian(Q̂, :L), Hermitian(R̂, :L)
549543
P̂_0 = Hermitian(P̂_0, :L)
@@ -556,7 +550,7 @@ struct UnscentedKalmanFilter{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
556550
buffer = StateEstimatorBuffer{NT}(nu, nx̂, nym, ny, nd, nk)
557551
return new{NT, SM}(
558552
model,
559-
lastu0, x̂op, f̂op, x̂0, P̂,
553+
x̂op, f̂op, x̂0, P̂,
560554
i_ym, nx̂, nym, nyu, nxs,
561555
As, Cs_u, Cs_y, nint_u, nint_ym,
562556
Â, B̂u, Ĉ, B̂d, D̂d, Ĉm, D̂dm,
@@ -879,7 +873,6 @@ struct ExtendedKalmanFilter{
879873
LF<:Function
880874
} <: StateEstimator{NT}
881875
model::SM
882-
lastu0::Vector{NT}
883876
x̂op ::Vector{NT}
884877
f̂op ::Vector{NT}
885878
x̂0 ::Vector{NT}
@@ -925,7 +918,6 @@ struct ExtendedKalmanFilter{
925918
Â, B̂u, Ĉ, B̂d, D̂d, x̂op, f̂op = augment_model(model, As, Cs_u, Cs_y)
926919
Ĉm, D̂dm = Ĉ[i_ym, :], D̂d[i_ym, :]
927920
validate_kfcov(nym, nx̂, Q̂, R̂, P̂_0)
928-
lastu0 = zeros(NT, nu)
929921
x̂0 = [zeros(NT, model.nx); zeros(NT, nxs)]
930922
Q̂, R̂ = Hermitian(Q̂, :L), Hermitian(R̂, :L)
931923
P̂_0 = Hermitian(P̂_0, :L)
@@ -937,7 +929,7 @@ struct ExtendedKalmanFilter{
937929
buffer = StateEstimatorBuffer{NT}(nu, nx̂, nym, ny, nd, nk)
938930
return new{NT, SM, JB, LF}(
939931
model,
940-
lastu0, x̂op, f̂op, x̂0, P̂,
932+
x̂op, f̂op, x̂0, P̂,
941933
i_ym, nx̂, nym, nyu, nxs,
942934
As, Cs_u, Cs_y, nint_u, nint_ym,
943935
Â, B̂u, Ĉ, B̂d, D̂d, Ĉm, D̂dm,

src/estimator/luenberger.jl

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
struct Luenberger{NT<:Real, SM<:LinModel} <: StateEstimator{NT}
22
model::SM
3-
lastu0::Vector{NT}
43
x̂op::Vector{NT}
54
f̂op::Vector{NT}
65
x̂0 ::Vector{NT}
@@ -41,13 +40,12 @@ struct Luenberger{NT<:Real, SM<:LinModel} <: StateEstimator{NT}
4140
catch
4241
error("Cannot compute the Luenberger gain K̂ with specified poles.")
4342
end
44-
lastu0 = zeros(NT, nu)
4543
x̂0 = [zeros(NT, model.nx); zeros(NT, nxs)]
4644
corrected = [false]
4745
buffer = StateEstimatorBuffer{NT}(nu, nx̂, nym, ny, nd, nk)
4846
return new{NT, SM}(
4947
model,
50-
lastu0, x̂op, f̂op, x̂0,
48+
x̂op, f̂op, x̂0,
5149
i_ym, nx̂, nym, nyu, nxs,
5250
As, Cs_u, Cs_y, nint_u, nint_ym,
5351
Â, B̂u, Ĉ, B̂d, D̂d, Ĉm, D̂dm,

src/estimator/manual.jl

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
struct ManualEstimator{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
22
model::SM
3-
lastu0::Vector{NT}
43
x̂op ::Vector{NT}
54
f̂op ::Vector{NT}
65
x̂0 ::Vector{NT}
@@ -34,14 +33,13 @@ struct ManualEstimator{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
3433
nx̂ = model.nx + nxs
3534
Â, B̂u, Ĉ, B̂d, D̂d, x̂op, f̂op = augment_model(model, As, Cs_u, Cs_y)
3635
Ĉm, D̂dm = Ĉ[i_ym, :], D̂d[i_ym, :]
37-
lastu0 = zeros(NT, nu)
3836
x̂0 = [zeros(NT, model.nx); zeros(NT, nxs)]
3937
direct = false
4038
corrected = [true]
4139
buffer = StateEstimatorBuffer{NT}(nu, nx̂, nym, ny, nd, nk)
4240
return new{NT, SM}(
4341
model,
44-
lastu0, x̂op, f̂op, x̂0,
42+
x̂op, f̂op, x̂0,
4543
i_ym, nx̂, nym, nyu, nxs,
4644
As, Cs_u, Cs_y, nint_u, nint_ym,
4745
Â, B̂u, Ĉ, B̂d, D̂d, Ĉm, D̂dm,

0 commit comments

Comments
 (0)