Skip to content

Commit f5ad896

Browse files
committed
debug julia 1.6
debug: re-insert precompile calls
1 parent c78e191 commit f5ad896

File tree

10 files changed

+82
-50
lines changed

10 files changed

+82
-50
lines changed

src/controller/explicitmpc.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@ struct ExplicitMPC{NT<:Real, SE<:StateEstimator} <: PredictiveController{NT}
1212
R̂u::Vector{NT}
1313
R̂y::Vector{NT}
1414
noR̂u::Bool
15-
::Matrix{Bool}
16-
T::Matrix{Bool}
15+
::BitMatrix
16+
T::BitMatrix
1717
::Matrix{NT}
1818
F::Vector{NT}
1919
G::Matrix{NT}

src/controller/linmpc.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,8 @@ struct LinMPC{
2222
R̂u::Vector{NT}
2323
R̂y::Vector{NT}
2424
noR̂u::Bool
25-
::Matrix{Bool}
26-
T::Matrix{Bool}
25+
::BitMatrix
26+
T::BitMatrix
2727
::Matrix{NT}
2828
F::Vector{NT}
2929
G::Matrix{NT}

src/controller/nonlinmpc.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,8 @@ struct NonLinMPC{
2424
R̂u::Vector{NT}
2525
R̂y::Vector{NT}
2626
noR̂u::Bool
27-
::Matrix{Bool}
28-
T::Matrix{Bool}
27+
::BitMatrix
28+
T::BitMatrix
2929
::Matrix{NT}
3030
F::Vector{NT}
3131
G::Matrix{NT}

src/estimator/kalman.jl

Lines changed: 23 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -160,7 +160,10 @@ Construct the estimator from the augmented covariance matrices `Q̂` and `R̂`.
160160
161161
This syntax allows nonzero off-diagonal elements in ``\mathbf{Q̂, R̂}``.
162162
"""
163-
SteadyKalmanFilter(model::LinModel, i_ym, nint_u, nint_ym, Q̂, R̂)
163+
function SteadyKalmanFilter(model::SM, i_ym, nint_u, nint_ym, Q̂, R̂) where {NT<:Real, SM<:LinModel{NT}}
164+
return SteadyKalmanFilter{NT, SM}(model, i_ym, nint_u, nint_ym, Q̂ , R̂)
165+
end
166+
164167

165168

166169
@doc raw"""
@@ -298,7 +301,9 @@ Construct the estimator from the augmented covariance matrices `P̂0`, `Q̂` and
298301
299302
This syntax allows nonzero off-diagonal elements in ``\mathbf{P̂}_{-1}(0), \mathbf{Q̂, R̂}``.
300303
"""
301-
KalmanFilter(model, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂)
304+
function KalmanFilter(model::SM, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂) where {NT<:Real, SM<:LinModel{NT}}
305+
return KalmanFilter{NT, SM}(model, i_ym, nint_u, nint_ym, P̂0, Q̂ , R̂)
306+
end
302307

303308
@doc raw"""
304309
update_estimate!(estim::KalmanFilter, u, ym, d)
@@ -366,7 +371,7 @@ struct UnscentedKalmanFilter{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
366371
nx̂ = model.nx + nxs
367372
Â, B̂u, Ĉ, B̂d, D̂d = augment_model(model, As, Cs_u, Cs_y)
368373
validate_kfcov(nym, nx̂, Q̂, R̂, P̂0)
369-
nσ, γ, m̂, Ŝ = init_ukf(nx̂, α, β, κ)
374+
nσ, γ, m̂, Ŝ = init_ukf(model, nx̂, α, β, κ)
370375
lastu0 = zeros(NT, model.nu)
371376
= [zeros(NT, model.nx); zeros(NT, nxs)]
372377
Q̂, R̂ = Hermitian(Q̂, :L), Hermitian(R̂, :L)
@@ -459,17 +464,21 @@ function UnscentedKalmanFilter(
459464
end
460465

461466
@doc raw"""
462-
UnscentedKalmanFilter{SM<:SimModel}(model::SM, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂, α, β, κ)
467+
UnscentedKalmanFilter(model, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂, α, β, κ)
463468
464469
Construct the estimator from the augmented covariance matrices `P̂0`, `Q̂` and `R̂`.
465470
466471
This syntax allows nonzero off-diagonal elements in ``\mathbf{P̂}_{-1}(0), \mathbf{Q̂, R̂}``.
467472
"""
468-
UnscentedKalmanFilter{SM}(model::SM, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂, α, β, κ) where {SM<:SimModel}
473+
function UnscentedKalmanFilter(
474+
model::SM, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂, α, β, κ
475+
) where {NT<:Real, SM<:SimModel{NT}}
476+
return UnscentedKalmanFilter{NT, SM}(model, i_ym, nint_u, nint_ym, P̂0, Q̂ , R̂, α, β, κ)
477+
end
469478

470479

471480
@doc raw"""
472-
init_ukf(nx̂, α, β, κ) -> nσ, γ, m̂, Ŝ
481+
init_ukf(model, nx̂, α, β, κ) -> nσ, γ, m̂, Ŝ
473482
474483
Compute the [`UnscentedKalmanFilter`](@ref) constants from ``α, β`` and ``κ``.
475484
@@ -489,14 +498,14 @@ covariance are respectively:
489498
```
490499
See [`update_estimate!(::UnscentedKalmanFilter)`](@ref) for other details.
491500
"""
492-
function init_ukf(nx̂, α, β, κ)
501+
function init_ukf(::SimModel{NT}, nx̂, α, β, κ) where {NT<:Real}
493502
= 2nx̂ + 1 # number of sigma points
494503
γ = α * (nx̂ + κ) # constant factor of standard deviation √P
495504
m̂_0 = 1 - nx̂ / γ^2
496505
Ŝ_0 = m̂_0 + 1 - α^2 + β
497506
w = 1 / 2 / γ^2
498-
= [m̂_0; fill(w, 2 * nx̂)] # weights for the mean
499-
= Diagonal([Ŝ_0; fill(w, 2 * nx̂)]) # weights for the covariance
507+
= NT[m̂_0; fill(w, 2 * nx̂)] # weights for the mean
508+
= Diagonal(NT[Ŝ_0; fill(w, 2 * nx̂)]) # weights for the covariance
500509
return nσ, γ, m̂, Ŝ
501510
end
502511

@@ -678,13 +687,16 @@ function ExtendedKalmanFilter(
678687
end
679688

680689
@doc raw"""
681-
ExtendedKalmanFilter{SM<:SimModel}(model::SM, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂)
690+
ExtendedKalmanFilter(model, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂)
682691
683692
Construct the estimator from the augmented covariance matrices `P̂0`, `Q̂` and `R̂`.
684693
685694
This syntax allows nonzero off-diagonal elements in ``\mathbf{P̂}_{-1}(0), \mathbf{Q̂, R̂}``.
686695
"""
687-
ExtendedKalmanFilter{SM}(model::SM, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂) where {SM<:SimModel}
696+
function ExtendedKalmanFilter(model::SM, i_ym, nint_u, nint_ym,P̂0, Q̂, R̂) where {NT<:Real, SM<:SimModel{NT}}
697+
return ExtendedKalmanFilter{NT, SM}(model, i_ym, nint_u, nint_ym, P̂0, Q̂ , R̂)
698+
end
699+
688700

689701
@doc raw"""
690702
update_estimate!(estim::ExtendedKalmanFilter, u, ym, d=empty(estim.x̂))

src/model/linearization.jl

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
LinModel(model::NonLinModel; x=model.x, u=model.uop, d=model.dop)
44
55
Call [`linearize(model; x, u, d)`](@ref) and return the resulting linear model.
6-
```
76
"""
87
LinModel(model::NonLinModel; kwargs...) = linearize(model; kwargs...)
98

src/model/linmodel.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -205,7 +205,7 @@ function LinModel(
205205
Dd::Matrix{<:Real},
206206
Ts::Real
207207
)
208-
A, Bu, C, Bd, Dd, Ts_arr = promote(A, Bu, C, Bd, Dd, [Ts;;])
208+
A, Bu, C, Bd, Dd, Ts_arr = promote(A, Bu, C, Bd, Dd, Ts*ones(1,1))
209209
return LinModel(A, Bu, C, Bd, Dd, Ts_arr[])
210210
end
211211

src/precompile_calls.jl

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,3 @@
1-
#=
2-
31
sys = [
42
tf(1.90, [18, 1]) tf(1.90, [18, 1]);
53
tf(-0.74,[8, 1]) tf(0.74, [8, 1])
@@ -87,4 +85,3 @@ end
8785
empc = setconstraint!(NonLinMPC(nlmodel, Mwt=[0, 0], Hp=10, Cwt=Inf, Ewt=1, JE=JE), ymin=[45, -Inf])
8886
u = empc()
8987
sim!(empc, 3)
90-
=#

src/predictive_control.jl

Lines changed: 22 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -753,9 +753,10 @@ are calculated by:
753753
```
754754
"""
755755
function init_ΔUtoU(nu, Hp, Hc)
756-
S_Hc = LowerTriangular(repeat(I(nu), Hc, Hc))
757-
S = [S_Hc; repeat(I(nu), Hp - Hc, Hc)]
758-
T = repeat(I(nu), Hp)
756+
I_nu = BitMatrix(I(nu))
757+
S_Hc = LowerTriangular(repeat(I_nu, Hc, Hc))
758+
S = [S_Hc; repeat(I_nu, Hp - Hc, Hc)]
759+
T = repeat(I_nu, Hp)
759760
return S, T
760761
end
761762

@@ -834,7 +835,7 @@ For the terminal constraints, the matrices are computed with the function
834835
\end{aligned}
835836
```
836837
"""
837-
function init_predmat(estim::StateEstimator, model::LinModel{NT}, Hp, Hc) where {NT<:Real}
838+
function init_predmat(estim::StateEstimator{NT}, model::LinModel, Hp, Hc) where {NT<:Real}
838839
Â, B̂u, Ĉ, B̂d, D̂d = estim.Â, estim.B̂u, estim.Ĉ, estim.B̂d, estim.D̂d
839840
nu, nx̂, ny, nd = model.nu, estim.nx̂, model.ny, model.nd
840841
# --- pre-compute matrix powers ---
@@ -893,7 +894,7 @@ function init_predmat(estim::StateEstimator, model::LinModel{NT}, Hp, Hc) where
893894
end
894895

895896
"Return empty matrices if `model` is not a [`LinModel`](@ref)"
896-
function init_predmat(estim::StateEstimator, model::SimModel{NT}, Hp, Hc) where {NT<:Real}
897+
function init_predmat(estim::StateEstimator{NT}, model::SimModel, Hp, Hc) where {NT<:Real}
897898
nu, nx̂, nd = model.nu, estim.nx̂, model.nd
898899
E = zeros(NT, 0, nu*Hc)
899900
G = zeros(NT, 0, nd)
@@ -1025,8 +1026,8 @@ function init_defaultcon(
10251026
repeat_constraints(Hp, Hc, umin, umax, Δumin, Δumax, ymin, ymax)
10261027
C_umin, C_umax, C_Δumin, C_Δumax, C_ymin, C_ymax =
10271028
repeat_constraints(Hp, Hc, c_umin, c_umax, c_Δumin, c_Δumax, c_ymin, c_ymax)
1028-
A_Umin, A_Umax, S̃ = relaxU(C, C_umin, C_umax, S)
1029-
A_ΔŨmin, A_ΔŨmax, ΔŨmin, ΔŨmax, Ñ_Hc = relaxΔU(C, C_Δumin, C_Δumax, ΔUmin, ΔUmax, N_Hc)
1029+
A_Umin, A_Umax, S̃ = relaxU(model, C, C_umin, C_umax, S)
1030+
A_ΔŨmin, A_ΔŨmax, ΔŨmin, ΔŨmax, Ñ_Hc = relaxΔU(model, C, C_Δumin, C_Δumax, ΔUmin, ΔUmax, N_Hc)
10301031
A_Ymin, A_Ymax, Ẽ = relaxŶ(model, C, C_ymin, C_ymax, E)
10311032
A_x̂min, A_x̂max, ẽx̂ = relaxterminal(model, C, c_x̂min, c_x̂max, ex̂)
10321033
i_Umin, i_Umax = .!isinf.(Umin), .!isinf.(Umax)
@@ -1060,7 +1061,7 @@ function repeat_constraints(Hp, Hc, umin, umax, Δumin, Δumax, ymin, ymax)
10601061
end
10611062

10621063
@doc raw"""
1063-
relaxU(C, C_umin, C_umax, S) -> A_Umin, A_Umax, S̃
1064+
relaxU(model, C, C_umin, C_umax, S) -> A_Umin, A_Umax, S̃
10641065
10651066
Augment manipulated inputs constraints with slack variable ϵ for softening.
10661067
@@ -1080,21 +1081,24 @@ constraints:
10801081
\end{bmatrix}
10811082
```
10821083
"""
1083-
function relaxU(C, C_umin, C_umax, S)
1084+
function relaxU(::SimModel{NT}, C, C_umin, C_umax, S) where {NT<:Real}
1085+
S_NT = convert(Matrix{NT}, S)
10841086
if !isinf(C) # ΔŨ = [ΔU; ϵ]
10851087
# ϵ impacts ΔU → U conversion for constraint calculations:
1086-
A_Umin, A_Umax = -[S C_umin], [S -C_umax]
1088+
A_Umin, A_Umax = -[S_NT C_umin], [S_NT -C_umax]
10871089
# ϵ has no impact on ΔU → U conversion for prediction calculations:
10881090
= [S falses(size(S, 1))]
10891091
else # ΔŨ = ΔU (only hard constraints)
1090-
A_Umin, A_Umax = -S, S
1092+
A_Umin, A_Umax = -S_NT, S_NT
10911093
= S
10921094
end
10931095
return A_Umin, A_Umax, S̃
10941096
end
10951097

10961098
@doc raw"""
1097-
relaxΔU(C, C_Δumin, C_Δumax, ΔUmin, ΔUmax, N_Hc) -> A_ΔŨmin, A_ΔŨmax, ΔŨmin, ΔŨmax, Ñ_Hc
1099+
relaxΔU(
1100+
model, C, C_Δumin, C_Δumax, ΔUmin, ΔUmax, N_Hc
1101+
) -> A_ΔŨmin, A_ΔŨmax, ΔŨmin, ΔŨmax, Ñ_Hc
10981102
10991103
Augment input increments constraints with slack variable ϵ for softening.
11001104
@@ -1114,18 +1118,19 @@ returns the augmented constraints ``\mathbf{ΔŨ_{min}}`` and ``\mathbf{ΔŨ_{
11141118
\end{bmatrix}
11151119
```
11161120
"""
1117-
function relaxΔU(C::NT, C_Δumin, C_Δumax, ΔUmin, ΔUmax, N_Hc) where {NT<:Real}
1121+
function relaxΔU(::SimModel{NT}, C, C_Δumin, C_Δumax, ΔUmin, ΔUmax, N_Hc) where {NT<:Real}
1122+
diag_N_Hc = diag(N_Hc)
11181123
if !isinf(C) # ΔŨ = [ΔU; ϵ]
11191124
# 0 ≤ ϵ ≤ ∞
1120-
ΔŨmin, ΔŨmax = [ΔUmin; 0.0], [ΔUmax; Inf]
1121-
A_ϵ = [zeros(NT, 1, length(ΔUmin)) [1.0]]
1125+
ΔŨmin, ΔŨmax = [ΔUmin; NT[0.0]], [ΔUmax; NT[Inf]]
1126+
A_ϵ = [zeros(NT, 1, length(ΔUmin)) NT[1.0]]
11221127
A_ΔŨmin, A_ΔŨmax = -[I C_Δumin; A_ϵ], [I -C_Δumax; A_ϵ]
1123-
Ñ_Hc = Diagonal([diag(N_Hc); C])
1128+
Ñ_Hc = Diagonal{NT}([diag_N_Hc; C])
11241129
else # ΔŨ = ΔU (only hard constraints)
11251130
ΔŨmin, ΔŨmax = ΔUmin, ΔUmax
11261131
I_Hc = Matrix{NT}(I, size(N_Hc))
11271132
A_ΔŨmin, A_ΔŨmax = -I_Hc, I_Hc
1128-
Ñ_Hc = N_Hc
1133+
Ñ_Hc = Diagonal{NT}(diag_N_Hc)
11291134
end
11301135
return A_ΔŨmin, A_ΔŨmax, ΔŨmin, ΔŨmax, Ñ_Hc
11311136
end

test/test_predictive_control.jl

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ sys = [ tf(1.90,[18.0,1]) tf(1.90,[18.0,1]) tf(1.90,[18.0,1]);
3232
@test mpc11.Ñ_Hc Diagonal([0.1,0.11,0.12,0.13])
3333
mcp12 = LinMPC(model, L_Hp=Diagonal(collect(0.001:0.001:0.02)))
3434
@test mcp12.L_Hp Diagonal(collect(0.001:0.001:0.02))
35-
model2 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
35+
model2 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
3636
mpc13 = LinMPC(model2)
3737
@test isa(mpc13, LinMPC{Float32})
3838
@test isa(mpc13.optim, JuMP.GenericModel{Float64}) # OSQP does not support Float32
@@ -67,7 +67,7 @@ end
6767
mpc3 = LinMPC(linmodel, Mwt=[0], Nwt=[0], Lwt=[1])
6868
u = moveinput!(mpc3, [0], R̂u=fill(12, mpc3.Hp))
6969
@test u [12] atol=1e-2
70-
model2 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
70+
model2 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
7171
mpc4 = LinMPC(model2)
7272
moveinput!(mpc4, [0]) [0.0]
7373

@@ -255,7 +255,7 @@ end
255255
@test mpc11.Ñ_Hc Diagonal([0.1,0.11,0.12,0.13])
256256
mcp12 = ExplicitMPC(model, L_Hp=Diagonal(collect(0.001:0.001:0.02)))
257257
@test mcp12.L_Hp Diagonal(collect(0.001:0.001:0.02))
258-
model2 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
258+
model2 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
259259
mpc13 = ExplicitMPC(model2)
260260
@test isa(mpc13, ExplicitMPC{Float32})
261261
end
@@ -276,7 +276,7 @@ end
276276
mpc3 = ExplicitMPC(LinModel(tf(5, [2, 1]), 3), Mwt=[0], Nwt=[0], Lwt=[1])
277277
u = moveinput!(mpc3, [0], R̂u=fill(12, mpc3.Hp))
278278
@test u [12] atol=1e-2
279-
model2 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
279+
model2 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
280280
mpc4 = ExplicitMPC(model2)
281281
moveinput!(mpc4, [0]) [0.0]
282282
end
@@ -434,7 +434,7 @@ end
434434
@test g_Ymax_end((1.0, 1.0)) 0.0 # test gfunc_i(i,::NTuple{N, Float64})
435435
# test gfunc_i(i,::NTuple{N, ForwardDiff.Dual}) :
436436
@test ForwardDiff.gradient(g_Ymax_end, [1.0, 1.0]) [0.0, 0.0]
437-
linmodel3 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
437+
linmodel3 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
438438
nmpc6 = NonLinMPC(linmodel3, Hp=10)
439439
moveinput!(nmpc6, [0]) [0.0]
440440
nonlinmodel2 = NonLinModel{Float32}(f, h, 300.0, 1, 2, 1, 1)

test/test_state_estim.jl

Lines changed: 25 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -44,10 +44,14 @@ sys = [ tf(1.90,[18.0,1]) tf(1.90,[18.0,1]) tf(1.90,[18.0,1]);
4444
@test skalmanfilter7.nint_u == [1, 1]
4545
@test skalmanfilter7.nint_ym == [0, 0]
4646

47-
linmodel2 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
47+
linmodel2 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
4848
skalmanfilter8 = SteadyKalmanFilter(linmodel2)
4949
@test isa(skalmanfilter8, SteadyKalmanFilter{Float32})
5050

51+
skalmanfilter9 = SteadyKalmanFilter(linmodel1, 1:2, 0, [1, 1], I(4), I(2))
52+
@test skalmanfilter9. I(4)
53+
@test skalmanfilter9. I(2)
54+
5155
@test_throws ErrorException SteadyKalmanFilter(linmodel1, nint_ym=[1,1,1])
5256
@test_throws ErrorException SteadyKalmanFilter(linmodel1, nint_ym=[-1,0])
5357
@test_throws ErrorException SteadyKalmanFilter(linmodel1, nint_ym=0, σQ=[1])
@@ -134,7 +138,12 @@ end
134138
@test kalmanfilter7.nint_u == [1, 1]
135139
@test kalmanfilter7.nint_ym == [0, 0]
136140

137-
linmodel2 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
141+
kalmanfilter8 = KalmanFilter(linmodel1, 1:2, 0, [1, 1], I(4), I(4), I(2))
142+
@test kalmanfilter8.P̂0 I(4)
143+
@test kalmanfilter8. I(4)
144+
@test kalmanfilter8. I(2)
145+
146+
linmodel2 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
138147
kalmanfilter8 = KalmanFilter(linmodel2)
139148
@test isa(kalmanfilter8, KalmanFilter{Float32})
140149

@@ -201,7 +210,7 @@ end
201210
@test lo5.nint_u == [1, 1]
202211
@test lo5.nint_ym == [0, 0]
203212

204-
linmodel2 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
213+
linmodel2 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
205214
lo6 = Luenberger(linmodel2)
206215
@test isa(lo6, Luenberger{Float32})
207216

@@ -299,7 +308,7 @@ end
299308
@test internalmodel7.Cs stoch_ym_disc.C
300309
@test internalmodel7.Ds stoch_ym_disc.D
301310

302-
linmodel3 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
311+
linmodel3 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
303312
internalmodel8 = InternalModel(linmodel3)
304313
@test isa(internalmodel8, InternalModel{Float32})
305314

@@ -379,7 +388,12 @@ end
379388
@test ukf8.nint_u == [1, 1]
380389
@test ukf8.nint_ym == [0, 0]
381390

382-
linmodel2 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
391+
ukf9 = UnscentedKalmanFilter(nonlinmodel, 1:2, 0, [1, 1], I(6), I(6), I(2), 0.1, 2, 0)
392+
@test ukf9.P̂0 I(6)
393+
@test ukf9. I(6)
394+
@test ukf9. I(2)
395+
396+
linmodel2 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
383397
ukf9 = UnscentedKalmanFilter(linmodel2)
384398
@test isa(ukf9, UnscentedKalmanFilter{Float32})
385399
end
@@ -460,7 +474,12 @@ end
460474
@test ekf7.nint_u == [1, 1]
461475
@test ekf7.nint_ym == [0, 0]
462476

463-
linmodel2 = LinModel{Float32}([0.5;;], [1;;], [1;;], zeros(1,0), zeros(1,0), 1.0)
477+
ekf8 = ExtendedKalmanFilter(nonlinmodel, 1:2, 0, [1, 1], I(6), I(6), I(2))
478+
@test ekf8.P̂0 I(6)
479+
@test ekf8. I(6)
480+
@test ekf8. I(2)
481+
482+
linmodel2 = LinModel{Float32}(0.5*ones(1,1), ones(1,1), ones(1,1), zeros(1,0), zeros(1,0), 1.0)
464483
ekf8 = ExtendedKalmanFilter(linmodel2)
465484
@test isa(ekf8, ExtendedKalmanFilter{Float32})
466485
end

0 commit comments

Comments
 (0)