Skip to content

Commit 3bfd43c

Browse files
committed
changed: default P0 not function of Q value
1 parent 6277637 commit 3bfd43c

File tree

3 files changed

+19
-19
lines changed

3 files changed

+19
-19
lines changed

Project.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
name = "ModelPredictiveControl"
22
uuid = "61f9bdb8-6ae4-484a-811f-bbf86720c31c"
33
authors = ["Francis Gagnon"]
4-
version = "0.14.0"
4+
version = "0.14.1"
55

66
[deps]
77
ControlSystemsBase = "aaaaaaaa-a6ca-5380-bf3e-84a91bcd477e"

src/estimator/kalman.jl

Lines changed: 15 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -253,13 +253,13 @@ its initial value with ``\mathbf{P̂}_{-1}(0) =
253253
254254
# Arguments
255255
- `model::LinModel` : (deterministic) model for the estimations.
256+
- `σP0=fill(1/model.nx,model.nx)` : main diagonal of the initial estimate covariance
257+
``\mathbf{P}(0)``, specified as a standard deviation vector.
258+
- `σP0int_u=fill(1,sum(nint_u))` : same than `σP0` but for the unmeasured disturbances at
259+
manipulated inputs ``\mathbf{P_{int_u}}(0)`` (composed of integrators).
260+
- `σP0int_ym=fill(1,sum(nint_ym))` : same than `σP0` but for the unmeasured disturbances at
261+
measured outputs ``\mathbf{P_{int_{ym}}}(0)`` (composed of integrators).
256262
- `<keyword arguments>` of [`SteadyKalmanFilter`](@ref) constructor.
257-
- `σP0=σQ` : main diagonal of the initial estimate covariance ``\mathbf{P}(0)``, specified
258-
as a standard deviation vector.
259-
- `σP0int_u=σQint_u` : same than `σP0` but for the unmeasured disturbances at manipulated
260-
inputs ``\mathbf{P_{int_u}}(0)`` (composed of integrators).
261-
- `σP0int_ym=σQint_ym` : same than `σP0` but for the unmeasured disturbances at measured
262-
outputs ``\mathbf{P_{int_{ym}}}(0)`` (composed of integrators).
263263
264264
# Examples
265265
```jldoctest
@@ -277,15 +277,15 @@ KalmanFilter estimator with a sample time Ts = 0.5 s, LinModel and:
277277
function KalmanFilter(
278278
model::SM;
279279
i_ym::IntRangeOrVector = 1:model.ny,
280+
σP0::Vector = fill(1/model.nx, model.nx),
280281
σQ ::Vector = fill(1/model.nx, model.nx),
281282
σR ::Vector = fill(1, length(i_ym)),
282-
σP0::Vector = σQ,
283283
nint_u ::IntVectorOrInt = 0,
284284
σQint_u ::Vector = fill(1, max(sum(nint_u), 0)),
285-
σP0int_u ::Vector = σQint_u,
285+
σP0int_u ::Vector = fill(1, max(sum(nint_u), 0)),
286286
nint_ym ::IntVectorOrInt = default_nint(model, i_ym, nint_u),
287287
σQint_ym ::Vector = fill(1, max(sum(nint_ym), 0)),
288-
σP0int_ym::Vector = σQint_ym,
288+
σP0int_ym::Vector = fill(1, max(sum(nint_ym), 0)),
289289
) where {NT<:Real, SM<:LinModel{NT}}
290290
# estimated covariances matrices (variance = σ²) :
291291
P̂0 = Hermitian(diagm(NT[σP0; σP0int_u; σP0int_ym].^2), :L)
@@ -443,15 +443,15 @@ responsibility to ensure that the augmented model is still observable.
443443
function UnscentedKalmanFilter(
444444
model::SM;
445445
i_ym::IntRangeOrVector = 1:model.ny,
446+
σP0::Vector = fill(1/model.nx, model.nx),
446447
σQ ::Vector = fill(1/model.nx, model.nx),
447448
σR ::Vector = fill(1, length(i_ym)),
448-
σP0::Vector = σQ,
449449
nint_u ::IntVectorOrInt = 0,
450450
σQint_u ::Vector = fill(1, max(sum(nint_u), 0)),
451-
σP0int_u ::Vector = σQint_u,
451+
σP0int_u ::Vector = fill(1, max(sum(nint_u), 0)),
452452
nint_ym ::IntVectorOrInt = default_nint(model, i_ym, nint_u),
453453
σQint_ym ::Vector = fill(1, max(sum(nint_ym), 0)),
454-
σP0int_ym::Vector = σQint_ym,
454+
σP0int_ym::Vector = fill(1, max(sum(nint_ym), 0)),
455455
α::Real = 1e-3,
456456
β::Real = 2,
457457
κ::Real = 0
@@ -669,15 +669,15 @@ ExtendedKalmanFilter estimator with a sample time Ts = 5.0 s, NonLinModel and:
669669
function ExtendedKalmanFilter(
670670
model::SM;
671671
i_ym::IntRangeOrVector = 1:model.ny,
672+
σP0::Vector = fill(1/model.nx, model.nx),
672673
σQ ::Vector = fill(1/model.nx, model.nx),
673674
σR ::Vector = fill(1, length(i_ym)),
674-
σP0::Vector = σQ,
675675
nint_u ::IntVectorOrInt = 0,
676676
σQint_u ::Vector = fill(1, max(sum(nint_u), 0)),
677-
σP0int_u ::Vector = σQint_u,
677+
σP0int_u ::Vector = fill(1, max(sum(nint_u), 0)),
678678
nint_ym ::IntVectorOrInt = default_nint(model, i_ym, nint_u),
679679
σQint_ym ::Vector = fill(1, max(sum(nint_ym), 0)),
680-
σP0int_ym::Vector = σQint_ym,
680+
σP0int_ym::Vector = fill(1, max(sum(nint_ym), 0)),
681681
) where {NT<:Real, SM<:SimModel{NT}}
682682
# estimated covariances matrices (variance = σ²) :
683683
P̂0 = Hermitian(diagm(NT[σP0; σP0int_u; σP0int_ym].^2), :L)

src/estimator/mhe.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -162,15 +162,15 @@ function MovingHorizonEstimator(
162162
model::SM;
163163
He::Union{Int, Nothing}=nothing,
164164
i_ym::IntRangeOrVector = 1:model.ny,
165+
σP0::Vector = fill(1/model.nx, model.nx),
165166
σQ ::Vector = fill(1/model.nx, model.nx),
166167
σR ::Vector = fill(1, length(i_ym)),
167-
σP0::Vector = σQ,
168168
nint_u ::IntVectorOrInt = 0,
169169
σQint_u ::Vector = fill(1, max(sum(nint_u), 0)),
170-
σP0int_u ::Vector = σQint_u,
170+
σP0int_u ::Vector = fill(1, max(sum(nint_u), 0)),
171171
nint_ym ::IntVectorOrInt = default_nint(model, i_ym, nint_u),
172172
σQint_ym ::Vector = fill(1, max(sum(nint_ym), 0)),
173-
σP0int_ym::Vector = σQint_ym,
173+
σP0int_ym::Vector = fill(1, max(sum(nint_ym), 0)),
174174
optim::JM = JuMP.Model(DEFAULT_MHE_OPTIMIZER, add_bridges=false),
175175
) where {NT<:Real, SM<:SimModel{NT}, JM<:JuMP.GenericModel}
176176
# estimated covariances matrices (variance = σ²) :

0 commit comments

Comments
 (0)