Skip to content

Commit 84c6034

Browse files
committed
added : additionnal MPC kargs are passed to estimator
1 parent 7f62624 commit 84c6034

File tree

8 files changed

+120
-37
lines changed

8 files changed

+120
-37
lines changed

src/controller/explicitmpc.jl

Lines changed: 19 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,7 @@ state estimator, a [`SteadyKalmanFilter`](@ref) with default arguments.
9595
- `Nwt=fill(0.1,model.nu)` : main diagonal of ``\mathbf{N}`` weight matrix (vector).
9696
- `Lwt=fill(0.0,model.nu)` : main diagonal of ``\mathbf{L}`` weight matrix (vector).
9797
- `ru=model.uop` : manipulated input setpoints ``\mathbf{r_u}`` (vector).
98+
- additionnal keyword arguments are passed to [`SteadyKalmanFilter`](@ref) constructor.
9899
99100
# Examples
100101
```jldoctest
@@ -112,7 +113,19 @@ ExplicitMPC controller with a sample time Ts = 4.0 s, SteadyKalmanFilter estimat
112113
```
113114
114115
"""
115-
ExplicitMPC(model::LinModel; kwargs...) = ExplicitMPC(SteadyKalmanFilter(model); kwargs...)
116+
function ExplicitMPC(
117+
model::LinModel;
118+
Hp::Union{Int, Nothing} = nothing,
119+
Hc::Int = DEFAULT_HC,
120+
Mwt = fill(DEFAULT_MWT, model.ny),
121+
Nwt = fill(DEFAULT_NWT, model.nu),
122+
Lwt = fill(DEFAULT_LWT, model.nu),
123+
ru = model.uop,
124+
kwargs...
125+
)
126+
estim = SteadyKalmanFilter(model; kwargs...)
127+
return ExplicitMPC(estim; Hp, Hc, Mwt, Nwt, Lwt, ru)
128+
end
116129

117130
"""
118131
ExplicitMPC(estim::StateEstimator; <keyword arguments>)
@@ -139,17 +152,17 @@ ExplicitMPC controller with a sample time Ts = 4.0 s, KalmanFilter estimator and
139152
function ExplicitMPC(
140153
estim::S;
141154
Hp::Union{Int, Nothing} = nothing,
142-
Hc::Int = 2,
143-
Mwt = fill(1.0, estim.model.ny),
144-
Nwt = fill(0.1, estim.model.nu),
145-
Lwt = fill(0.0, estim.model.nu),
155+
Hc::Int = DEFAULT_HC,
156+
Mwt = fill(DEFAULT_MWT, estim.model.ny),
157+
Nwt = fill(DEFAULT_NWT, estim.model.nu),
158+
Lwt = fill(DEFAULT_LWT, estim.model.nu),
146159
ru = estim.model.uop,
147160
) where {S<:StateEstimator}
148161
isa(estim.model, LinModel) || error("estim.model type must be LinModel")
149162
poles = eigvals(estim.model.A)
150163
nk = sum(poles .≈ 0)
151164
if isnothing(Hp)
152-
Hp = 10 + nk
165+
Hp = DEFAULT_HP + nk
153166
end
154167
if Hp nk
155168
@warn("prediction horizon Hp ($Hp) ≤ number of delays in model "*

src/controller/linmpc.jl

Lines changed: 23 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -111,6 +111,7 @@ arguments.
111111
- `optim=JuMP.Model(OSQP.MathOptInterfaceOSQP.Optimizer)` : quadratic optimizer used in
112112
the predictive controller, provided as a [`JuMP.Model`](https://jump.dev/JuMP.jl/stable/reference/models/#JuMP.Model)
113113
(default to [`OSQP.jl`](https://osqp.org/docs/parsers/jump.html) optimizer).
114+
- additionnal keyword arguments are passed to [`SteadyKalmanFilter`](@ref) constructor.
114115
115116
# Examples
116117
```jldoctest
@@ -149,7 +150,21 @@ The objective function follows this nomenclature:
149150
| ``C`` | slack variable weight | `()` |
150151
| ``ϵ`` | slack variable for constraint softening | `()` |
151152
"""
152-
LinMPC(model::LinModel; kwargs...) = LinMPC(SteadyKalmanFilter(model); kwargs...)
153+
function LinMPC(
154+
model::LinModel;
155+
Hp::Union{Int, Nothing} = nothing,
156+
Hc::Int = DEFAULT_HC,
157+
Mwt = fill(DEFAULT_MWT, model.ny),
158+
Nwt = fill(DEFAULT_NWT, model.nu),
159+
Lwt = fill(DEFAULT_LWT, model.nu),
160+
Cwt = DEFAULT_CWT,
161+
ru = model.uop,
162+
optim::JuMP.Model = JuMP.Model(OSQP.MathOptInterfaceOSQP.Optimizer),
163+
kwargs...
164+
)
165+
estim = SteadyKalmanFilter(model; kwargs...)
166+
return LinMPC(estim; Hp, Hc, Mwt, Nwt, Lwt, Cwt, ru, optim)
167+
end
153168

154169

155170
"""
@@ -176,20 +191,20 @@ LinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, KalmanFilter es
176191
"""
177192
function LinMPC(
178193
estim::S;
179-
Hp::Union{Int, Nothing} = nothing,
180-
Hc::Int = 2,
181-
Mwt = fill(1.0, estim.model.ny),
182-
Nwt = fill(0.1, estim.model.nu),
183-
Lwt = fill(0.0, estim.model.nu),
184-
Cwt = 1e5,
194+
Hp::Union{Int, Nothing} = DEFAULT_HP,
195+
Hc::Int = DEFAULT_HC,
196+
Mwt = fill(DEFAULT_MWT, estim.model.ny),
197+
Nwt = fill(DEFAULT_NWT, estim.model.nu),
198+
Lwt = fill(DEFAULT_LWT, estim.model.nu),
199+
Cwt = DEFAULT_CWT,
185200
ru = estim.model.uop,
186201
optim::JuMP.Model = JuMP.Model(OSQP.MathOptInterfaceOSQP.Optimizer)
187202
) where {S<:StateEstimator}
188203
isa(estim.model, LinModel) || error("estim.model type must be LinModel")
189204
poles = eigvals(estim.model.A)
190205
nk = sum(poles .≈ 0)
191206
if isnothing(Hp)
192-
Hp = 10 + nk
207+
Hp = DEFAULT_HP + nk
193208
end
194209
if Hp nk
195210
@warn("prediction horizon Hp ($Hp) ≤ number of delays in model "*

src/controller/nonlinmpc.jl

Lines changed: 43 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -125,6 +125,8 @@ This method uses the default state estimator :
125125
- `optim=JuMP.Model(Ipopt.Optimizer)` : nonlinear optimizer used in the predictive
126126
controller, provided as a [`JuMP.Model`](https://jump.dev/JuMP.jl/stable/reference/models/#JuMP.Model)
127127
(default to [`Ipopt.jl`](https://github.com/jump-dev/Ipopt.jl) optimizer).
128+
- additionnal keyword arguments are passed to [`UnscentedKalmanFilter`](@ref) constructor
129+
(or [`SteadyKalmanFilter`](@ref), for [`LinModel`](@ref)).
128130
129131
# Examples
130132
```jldoctest
@@ -152,8 +154,40 @@ generally benefit from exact derivatives like AD. However, the [`NonLinModel`](@
152154
and `h` functions must be compatible with this feature. See [Automatic differentiation](https://jump.dev/JuMP.jl/stable/manual/nlp/#Automatic-differentiation)
153155
for common mistakes when writing these functions.
154156
"""
155-
NonLinMPC(model::SimModel; kwargs...) = NonLinMPC(UnscentedKalmanFilter(model); kwargs...)
156-
NonLinMPC(model::LinModel; kwargs...) = NonLinMPC(SteadyKalmanFilter(model); kwargs...)
157+
function NonLinMPC(
158+
model::SimModel;
159+
Hp::Int = DEFAULT_HP,
160+
Hc::Int = DEFAULT_HC,
161+
Mwt = fill(DEFAULT_MWT, model.ny),
162+
Nwt = fill(DEFAULT_NWT, model.nu),
163+
Lwt = fill(DEFAULT_LWT, model.nu),
164+
Cwt = DEFAULT_CWT,
165+
Ewt = DEFAULT_EWT,
166+
JE::Function = (_,_,_) -> 0.0,
167+
ru = model.uop,
168+
optim::JuMP.Model = JuMP.Model(optimizer_with_attributes(Ipopt.Optimizer,"sb"=>"yes")),
169+
kwargs...
170+
)
171+
estim = UnscentedKalmanFilter(model; kwargs...)
172+
NonLinMPC(estim; Hp, Hc, Mwt, Nwt, Lwt, Cwt, Ewt, JE, ru, optim)
173+
end
174+
function NonLinMPC(
175+
model::LinModel;
176+
Hp::Int = DEFAULT_HP,
177+
Hc::Int = DEFAULT_HC,
178+
Mwt = fill(DEFAULT_MWT, model.ny),
179+
Nwt = fill(DEFAULT_NWT, model.nu),
180+
Lwt = fill(DEFAULT_LWT, model.nu),
181+
Cwt = DEFAULT_CWT,
182+
Ewt = DEFAULT_EWT,
183+
JE::Function = (_,_,_) -> 0.0,
184+
ru = model.uop,
185+
optim::JuMP.Model = JuMP.Model(optimizer_with_attributes(Ipopt.Optimizer,"sb"=>"yes")),
186+
kwargs...
187+
)
188+
estim = SteadyKalmanFilter(model; kwargs...)
189+
NonLinMPC(estim; Hp, Hc, Mwt, Nwt, Lwt, Cwt, Ewt, JE, ru, optim)
190+
end
157191

158192

159193
"""
@@ -180,13 +214,13 @@ NonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, UnscentedK
180214
"""
181215
function NonLinMPC(
182216
estim::S;
183-
Hp::Int = 10,
184-
Hc::Int = 2,
185-
Mwt = fill(1.0, estim.model.ny),
186-
Nwt = fill(0.1, estim.model.nu),
187-
Lwt = fill(0.0, estim.model.nu),
188-
Cwt = 1e5,
189-
Ewt = 0.0,
217+
Hp::Int = DEFAULT_HP,
218+
Hc::Int = DEFAULT_HC,
219+
Mwt = fill(DEFAULT_MWT, estim.model.ny),
220+
Nwt = fill(DEFAULT_NWT, estim.model.nu),
221+
Lwt = fill(DEFAULT_LWT, estim.model.nu),
222+
Cwt = DEFAULT_CWT,
223+
Ewt = DEFAULT_EWT,
190224
JE::JEFunc = (_,_,_) -> 0.0,
191225
ru = estim.model.uop,
192226
optim::JuMP.Model = JuMP.Model(optimizer_with_attributes(Ipopt.Optimizer,"sb"=>"yes"))

src/estimator/kalman.jl

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -96,11 +96,11 @@ unmeasured ones, for ``\mathbf{Ĉ^u, D̂_d^u}``).
9696
- `nint_u=0`: integrator quantity for the stochastic model of the unmeasured disturbances at
9797
the manipulated inputs (vector), use `nint_u=0` for no integrator (see Extended Help).
9898
- `σQint_u=fill(1,sum(nint_u))`: same than `σQ` but for the unmeasured disturbances at
99-
manipulated inputs ``\mathbf{Q_{int_u}}`` (composed of integrating states).
99+
manipulated inputs ``\mathbf{Q_{int_u}}`` (composed of integrators).
100100
- `nint_ym=default_nint(model,i_ym,nint_u)` : same than `nint_u` but for the unmeasured
101101
disturbances at the measured outputs, use `nint_ym=0` for no integrator (see Extended Help).
102102
- `σQint_ym=fill(1,sum(nint_ym))` : same than `σQ` for the unmeasured disturbances at
103-
measured outputs ``\mathbf{Q_{int_{ym}}}`` (composed of integrating states).
103+
measured outputs ``\mathbf{Q_{int_{ym}}}`` (composed of integrators).
104104
105105
# Examples
106106
```jldoctest
@@ -240,18 +240,18 @@ Construct a time-varying Kalman Filter with the [`LinModel`](@ref) `model`.
240240
241241
The process model is identical to [`SteadyKalmanFilter`](@ref). The matrix
242242
``\mathbf{P̂}_k(k+1)`` is the estimation error covariance of `model` states augmented with
243-
the stochastic ones (specified by `nint_ym`). Three keyword arguments modify its initial
244-
value with ``\mathbf{P̂}_{-1}(0) =
243+
the stochastic ones (specified by `nint_u` and `nint_ym`). Three keyword arguments modify
244+
its initial value with ``\mathbf{P̂}_{-1}(0) =
245245
\mathrm{diag}\{ \mathbf{P}(0), \mathbf{P_{int_{u}}}(0), \mathbf{P_{int_{ym}}}(0) \}``.
246246
247247
# Arguments
248248
- `model::LinModel` : (deterministic) model for the estimations.
249249
- `σP0=fill(1/model.nx,model.nx)` : main diagonal of the initial estimate covariance
250250
``\mathbf{P}(0)``, specified as a standard deviation vector.
251251
- `σP0int_u=fill(1,sum(nint_u))` : same than `σP0` but for the unmeasured disturbances at
252-
manipulated inputs ``\mathbf{P_{int_u}}(0)`` (composed of integrating states).
252+
manipulated inputs ``\mathbf{P_{int_u}}(0)`` (composed of integrators).
253253
- `σP0int_ym=fill(1,sum(nint_ym))` : same than `σP0` but for the unmeasured disturbances at
254-
measured outputs ``\mathbf{P_{int_{ym}}}(0)`` (composed of integrating states).
254+
measured outputs ``\mathbf{P_{int_{ym}}}(0)`` (composed of integrators).
255255
- `<keyword arguments>` of [`SteadyKalmanFilter`](@ref) constructor.
256256
257257
# Examples

src/estimator/luenberger.jl

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -57,12 +57,12 @@ end
5757
5858
Construct a Luenberger observer with the [`LinModel`](@ref) `model`.
5959
60-
`i_ym` provides the `model` output indices that are measured ``\mathbf{y^m}``, the rest are
60+
`i_ym` provides the `model` output indices that are measured ``\mathbf{y^m}``, the rest are
6161
unmeasured ``\mathbf{y^u}``. `model` matrices are augmented with the stochastic model, which
6262
is specified by the numbers of integrator `nint_u` and `nint_ym` (see [`SteadyKalmanFilter`](@ref)
63-
Extended Help). The argument `p̂` is a vector of `model.nx + sum(nint_ym)` elements
64-
specifying the observer poles/eigenvalues (near ``z=0.5`` by default). The method computes
65-
the observer gain `K̂` with [`place`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/synthesis/#ControlSystemsBase.place).
63+
Extended Help). The argument `p̂` is a vector of `model.nx + sum(nint_u) + sum(nint_ym)`
64+
elements specifying the observer poles/eigenvalues (near ``z=0.5`` by default). The method
65+
computes the observer gain `K̂` with [`place`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/synthesis/#ControlSystemsBase.place).
6666
6767
# Examples
6868
```jldoctest

src/predictive_control.jl

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,14 @@ julia> u = mpc([5]); round.(u, digits=3)
1919
"""
2020
abstract type PredictiveController end
2121

22+
const DEFAULT_HP = 10
23+
const DEFAULT_HC = 2
24+
const DEFAULT_MWT = 1.0
25+
const DEFAULT_NWT = 0.1
26+
const DEFAULT_LWT = 0.0
27+
const DEFAULT_CWT = 1e5
28+
const DEFAULT_EWT = 0.0
29+
2230
"Type alias for vector of linear inequality constraints."
2331
const LinConVector = Vector{ConstraintRef{
2432
Model,

src/state_estim.jl

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -217,10 +217,11 @@ end
217217
218218
Get default integrator quantity per measured outputs `nint_ym` for [`LinModel`](@ref).
219219
220-
The measured output ``\mathbf{y^m}`` indices are specified by `i_ym` argument. By default,
221-
one integrator is added on each measured outputs. If ``\mathbf{Â, Ĉ}`` matrices of the
222-
augmented model become unobservable, the integrator is removed. This approach works well
223-
for stable, integrating and unstable `model` (see Examples).
220+
The arguments `i_ym` and `nint_u` are the measured output indices and the integrator
221+
quantity on each manipulated input, respectively. By default, one integrator is added on
222+
each measured outputs. If ``\mathbf{Â, Ĉ}`` matrices of the augmented model become
223+
unobservable, the integrator is removed. This approach works well for stable, integrating
224+
and unstable `model` (see Examples).
224225
225226
# Examples
226227
```jldoctest

test/test_predictive_control.jl

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,9 @@ sys = [ tf(1.90,[18.0,1]) tf(1.90,[18.0,1]) tf(1.90,[18.0,1]);
2424
kf = KalmanFilter(model)
2525
mpc8 = LinMPC(kf)
2626
@test isa(mpc8.estim, KalmanFilter)
27+
mpc9 = LinMPC(model, nint_u=[1, 1], nint_ym=[0, 0])
28+
@test mpc9.estim.nint_u == [1, 1]
29+
@test mpc9.estim.nint_ym == [0, 0]
2730

2831
@test_throws ErrorException LinMPC(model, Hp=0)
2932
@test_throws ErrorException LinMPC(model, Hc=0)
@@ -131,6 +134,9 @@ end
131134
kf = KalmanFilter(model)
132135
mpc8 = ExplicitMPC(kf)
133136
@test isa(mpc8.estim, KalmanFilter)
137+
mpc9 = ExplicitMPC(model, nint_u=[1, 1], nint_ym=[0, 0])
138+
@test mpc9.estim.nint_u == [1, 1]
139+
@test mpc9.estim.nint_ym == [0, 0]
134140

135141
@test_throws ErrorException ExplicitMPC(model, Hp=0)
136142
@test_throws ErrorException ExplicitMPC(model, Hc=0)
@@ -240,6 +246,12 @@ end
240246
im = InternalModel(nonlinmodel)
241247
nmpc9 = NonLinMPC(im)
242248
@test isa(nmpc9.estim, InternalModel)
249+
nmpc10 = NonLinMPC(linmodel1, nint_u=[1, 1], nint_ym=[0, 0])
250+
@test nmpc10.estim.nint_u == [1, 1]
251+
@test nmpc10.estim.nint_ym == [0, 0]
252+
nmpc11 = NonLinMPC(nonlinmodel, nint_u=[1, 1], nint_ym=[0, 0])
253+
@test nmpc11.estim.nint_u == [1, 1]
254+
@test nmpc11.estim.nint_ym == [0, 0]
243255
end
244256

245257
@testset "NonLinMPC constraints" begin

0 commit comments

Comments
 (0)