Skip to content

Commit 317abe1

Browse files
committed
reduce allocation for KalmanFilter and ExtendedKalmanFilter
1 parent 42fe519 commit 317abe1

File tree

4 files changed

+62
-47
lines changed

4 files changed

+62
-47
lines changed

docs/src/manual/installation.md

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,15 +8,15 @@ using Pkg; Pkg.activate(); Pkg.add("ModelPredictiveControl")
88

99
Doing so will install the package to default Julia environnement, that is, accessible
1010
anywhere. To facilitate sharing of code and reproducibility of results, it is recommended to
11-
install packages in a project environnement. To generate a new project named `MyProject`
11+
install packages in a project environnement. To generate a new project named `MPCproject`
1212
with this package in the current working directory, write this in the REPL:
1313

1414
```julia
15-
using Pkg; Pkg.generate("MyProject"); Pkg.activate("."); Pkg.add("ModelPredictiveControl")
15+
using Pkg; Pkg.generate("MPCproject"); Pkg.activate("."); Pkg.add("ModelPredictiveControl")
1616
```
1717

1818
Note that that the construction of linear models typically requires `ss` or `tf` functions,
19-
it is thus recommended to load the package with:
19+
it is thus advised to load the package with:
2020

2121
```julia
2222
using ModelPredictiveControl, ControlSystemsBase

docs/src/manual/linmpc.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,7 @@ function plot_data(t_data, u_data, y_data, ry_data)
134134
p1 = plot(t_data, y_data[1,:], label="meas."); ylabel!("level")
135135
plot!(t_data, ry_data[1,:], label="setpoint", linestyle=:dash, linetype=:steppost)
136136
plot!(t_data, fill(45,size(t_data)), label="min", linestyle=:dot, linewidth=1.5)
137-
p2 = plot(t_data, y_data[2,:], label="meas."); ylabel!("temp.")
137+
p2 = plot(t_data, y_data[2,:], label="meas.", legend=:topleft); ylabel!("temp.")
138138
plot!(t_data, ry_data[2,:],label="setpoint", linestyle=:dash, linetype=:steppost)
139139
p3 = plot(t_data,u_data[1,:],label="cold", linetype=:steppost); ylabel!("flow rate")
140140
plot!(t_data,u_data[2,:],label="hot", linetype=:steppost); xlabel!("time (s)")

src/estimator/kalman.jl

Lines changed: 51 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -21,14 +21,14 @@ struct SteadyKalmanFilter <: StateEstimator
2121
D̂dm ::Matrix{Float64}
2222
::Hermitian{Float64, Matrix{Float64}}
2323
::Hermitian{Float64, Matrix{Float64}}
24-
K::Matrix{Float64}
24+
::Matrix{Float64}
2525
function SteadyKalmanFilter(model, i_ym, nint_u, nint_ym, Q̂, R̂)
2626
nym, nyu = validate_ym(model, i_ym)
2727
As, Cs_u, Cs_y, nxs, nint_u, nint_ym = init_estimstoch(model, i_ym, nint_u, nint_ym)
2828
nx̂ = model.nx + nxs
2929
Â, B̂u, Ĉ, B̂d, D̂d = augment_model(model, As, Cs_u, Cs_y)
3030
validate_kfcov(nym, nx̂, Q̂, R̂)
31-
K = try
31+
= try
3232
Q̂_kalman = Matrix(Q̂) # Matrix() required for Julia 1.6
3333
R̂_kalman = zeros(eltype(R̂), model.ny, model.ny)
3434
R̂_kalman[i_ym, i_ym] =
@@ -54,7 +54,7 @@ struct SteadyKalmanFilter <: StateEstimator
5454
Â, B̂u, Ĉ, B̂d, D̂d,
5555
Ĉm, D̂dm,
5656
Q̂, R̂,
57-
K
57+
5858
)
5959
end
6060
end
@@ -130,7 +130,7 @@ The function [`init_estimstoch`](@ref) builds the stochastic model for estimatio
130130
!!! tip
131131
Increasing `σQint_u` and `σQint_ym` values increases the integral action "gain".
132132
133-
The constructor pre-compute the steady-state Kalman gain `K` with the [`kalman`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/synthesis/#ControlSystemsBase.kalman-Tuple{Any,%20Any,%20Any,%20Any,%20Any,%20Vararg{Any}})
133+
The constructor pre-compute the steady-state Kalman gain `` with the [`kalman`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/synthesis/#ControlSystemsBase.kalman-Tuple{Any,%20Any,%20Any,%20Any,%20Any,%20Vararg{Any}})
134134
function. It can sometimes fail, for example when `model` matrices are ill-conditioned. In
135135
such a case, you can try the alternative time-varying [`KalmanFilter`](@ref).
136136
"""
@@ -165,16 +165,16 @@ SteadyKalmanFilter(model::LinModel, i_ym, nint_u, nint_ym, Q̂, R̂)
165165
166166
Update `estim.x̂` estimate with current inputs `u`, measured outputs `ym` and dist. `d`.
167167
168-
The [`SteadyKalmanFilter`](@ref) updates it with the precomputed Kalman gain ``\mathbf{K}``:
168+
The [`SteadyKalmanFilter`](@ref) updates it with the precomputed Kalman gain ``\mathbf{}``:
169169
```math
170170
\mathbf{x̂}_{k}(k+1) = \mathbf{Â x̂}_{k-1}(k) + \mathbf{B̂_u u}(k) + \mathbf{B̂_d d}(k)
171-
+ \mathbf{K}[\mathbf{y^m}(k) - \mathbf{Ĉ^m x̂}_{k-1}(k) - \mathbf{D̂_d^m d}(k)]
171+
+ \mathbf{}[\mathbf{y^m}(k) - \mathbf{Ĉ^m x̂}_{k-1}(k) - \mathbf{D̂_d^m d}(k)]
172172
```
173173
"""
174174
function update_estimate!(estim::SteadyKalmanFilter, u, ym, d=Float64[])
175175
Â, B̂u, B̂d, Ĉm, D̂dm = estim.Â, estim.B̂u, estim.B̂d, estim.Ĉm, estim.D̂dm
176-
x̂, K = estim.x̂, estim.K
177-
x̂[:] =*+ B̂u*u + B̂d*d + K*(ym - Ĉm*- D̂dm*d)
176+
x̂, = estim.x̂, estim.
177+
x̂[:] =*+ B̂u*u + B̂d*d + *(ym - Ĉm*- D̂dm*d)
178178
return
179179
end
180180

@@ -203,6 +203,8 @@ struct KalmanFilter <: StateEstimator
203203
P̂0::Hermitian{Float64, Matrix{Float64}}
204204
::Hermitian{Float64, Matrix{Float64}}
205205
::Hermitian{Float64, Matrix{Float64}}
206+
::Matrix{Float64}
207+
::Matrix{Float64}
206208
function KalmanFilter(model, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂)
207209
nym, nyu = validate_ym(model, i_ym)
208210
As, Cs_u, Cs_y, nxs, nint_u, nint_ym = init_estimstoch(model, i_ym, nint_u, nint_ym)
@@ -215,14 +217,16 @@ struct KalmanFilter <: StateEstimator
215217
Q̂, R̂ = Hermitian(Q̂, :L), Hermitian(R̂, :L)
216218
P̂0 = Hermitian(P̂0, :L)
217219
= copy(P̂0)
220+
K̂, M̂ = zeros(nx̂, nym), zeros(nx̂, nym)
218221
return new(
219222
model,
220223
lastu0, x̂, P̂,
221224
i_ym, nx̂, nym, nyu, nxs,
222225
As, Cs_u, Cs_y, nint_u, nint_ym,
223226
Â, B̂u, Ĉ, B̂d, D̂d,
224227
Ĉm, D̂dm,
225-
P̂0, Q̂, R̂
228+
P̂0, Q̂, R̂,
229+
K̂, M̂
226230
)
227231
end
228232
end
@@ -298,14 +302,14 @@ Update [`KalmanFilter`](@ref) state `estim.x̂` and estimation error covariance
298302
It implements the time-varying Kalman Filter in its predictor (observer) form :
299303
```math
300304
\begin{aligned}
301-
\mathbf{M}(k) &= \mathbf{P̂}_{k-1}(k)\mathbf{Ĉ^m}'
305+
\mathbf{}(k) &= \mathbf{P̂}_{k-1}(k)\mathbf{Ĉ^m}'
302306
[\mathbf{Ĉ^m P̂}_{k-1}(k)\mathbf{Ĉ^m}' + \mathbf{R̂}]^{-1} \\
303-
\mathbf{K}(k) &= \mathbf{Â M(k)} \\
307+
\mathbf{}(k) &= \mathbf{Â (k)} \\
304308
\mathbf{ŷ^m}(k) &= \mathbf{Ĉ^m x̂}_{k-1}(k) + \mathbf{D̂_d^m d}(k) \\
305309
\mathbf{x̂}_{k}(k+1) &= \mathbf{Â x̂}_{k-1}(k) + \mathbf{B̂_u u}(k) + \mathbf{B̂_d d}(k)
306-
+ \mathbf{K}(k)[\mathbf{y^m}(k) - \mathbf{ŷ^m}(k)] \\
310+
+ \mathbf{}(k)[\mathbf{y^m}(k) - \mathbf{ŷ^m}(k)] \\
307311
\mathbf{P̂}_{k}(k+1) &= \mathbf{Â}[\mathbf{P̂}_{k-1}(k)
308-
- \mathbf{M}(k)\mathbf{Ĉ^m P̂}_{k-1}(k)]\mathbf{Â}' + \mathbf{Q̂}
312+
- \mathbf{}(k)\mathbf{Ĉ^m P̂}_{k-1}(k)]\mathbf{Â}' + \mathbf{Q̂}
309313
\end{aligned}
310314
```
311315
based on the process model described in [`SteadyKalmanFilter`](@ref). The notation
@@ -342,6 +346,7 @@ struct UnscentedKalmanFilter{M<:SimModel} <: StateEstimator
342346
P̂0::Hermitian{Float64, Matrix{Float64}}
343347
::Hermitian{Float64, Matrix{Float64}}
344348
::Hermitian{Float64, Matrix{Float64}}
349+
::Matrix{Float64}
345350
::Int
346351
γ::Float64
347352
::Vector{Float64}
@@ -360,13 +365,15 @@ struct UnscentedKalmanFilter{M<:SimModel} <: StateEstimator
360365
Q̂, R̂ = Hermitian(Q̂, :L), Hermitian(R̂, :L)
361366
P̂0 = Hermitian(P̂0, :L)
362367
= copy(P̂0)
368+
= zeros(nx̂, nym)
363369
return new(
364370
model,
365371
lastu0, x̂, P̂,
366372
i_ym, nx̂, nym, nyu, nxs,
367373
As, Cs_u, Cs_y, nint_u, nint_ym,
368374
Â, B̂u, Ĉ, B̂d, D̂d,
369375
P̂0, Q̂, R̂,
376+
K̂,
370377
nσ, γ, m̂, Ŝ
371378
)
372379
end
@@ -506,10 +513,10 @@ of sigma points, and ``\mathbf{X̂}_{k-1}^j(k)``, the vector at the ``j``th colu
506513
\mathbf{ŷ^m}(k) &= \mathbf{Ŷ^m}(k) \mathbf{m̂} \\
507514
\mathbf{X̄}_{k-1}(k) &= \begin{bmatrix} \mathbf{X̂}_{k-1}^{1}(k) - \mathbf{x̂}_{k-1}(k) & \mathbf{X̂}_{k-1}^{2}(k) - \mathbf{x̂}_{k-1}(k) & \cdots & \mathbf{X̂}_{k-1}^{n_σ}(k) - \mathbf{x̂}_{k-1}(k) \end{bmatrix} \\
508515
\mathbf{Ȳ^m}(k) &= \begin{bmatrix} \mathbf{Ŷ^m}^{1}(k) - \mathbf{ŷ^m}(k) & \mathbf{Ŷ^m}^{2}(k) - \mathbf{ŷ^m}(k) & \cdots & \mathbf{Ŷ^m}^{n_σ}(k) - \mathbf{ŷ^m}(k) \end{bmatrix} \\
509-
\mathbf{M}(k) &= \mathbf{Ȳ^m}(k) \mathbf{Ŝ} \mathbf{Ȳ^m}'(k) + \mathbf{R̂} \\
510-
\mathbf{K}(k) &= \mathbf{X̄}_{k-1}(k) \mathbf{Ŝ} \mathbf{Ȳ^m}'(k) \mathbf{M}(k)^{-1} \\
511-
\mathbf{x̂}_k(k) &= \mathbf{x̂}_{k-1}(k) + \mathbf{K}(k) \big[ \mathbf{y^m}(k) - \mathbf{ŷ^m}(k) \big] \\
512-
\mathbf{P̂}_k(k) &= \mathbf{P̂}_{k-1}(k) - \mathbf{K}(k) \mathbf{M}(k) \mathbf{K}'(k) \\
516+
\mathbf{}(k) &= \mathbf{Ȳ^m}(k) \mathbf{Ŝ} \mathbf{Ȳ^m}'(k) + \mathbf{R̂} \\
517+
\mathbf{}(k) &= \mathbf{X̄}_{k-1}(k) \mathbf{Ŝ} \mathbf{Ȳ^m}'(k) \big[\mathbf{}(k)\big]^{-1} \\
518+
\mathbf{x̂}_k(k) &= \mathbf{x̂}_{k-1}(k) + \mathbf{}(k) \big[ \mathbf{y^m}(k) - \mathbf{ŷ^m}(k) \big] \\
519+
\mathbf{P̂}_k(k) &= \mathbf{P̂}_{k-1}(k) - \mathbf{}(k) \mathbf{}(k) \mathbf{}'(k) \\
513520
\mathbf{X̂}_k(k) &= \bigg[\begin{matrix} \mathbf{x̂}_{k}(k) & \mathbf{x̂}_{k}(k) & \cdots & \mathbf{x̂}_{k}(k) \end{matrix}\bigg] + \bigg[\begin{matrix} \mathbf{0} & \gamma \sqrt{\mathbf{P̂}_{k}(k)} & - \gamma \sqrt{\mathbf{P̂}_{k}(k)} \end{matrix}\bigg] \\
514521
\mathbf{X̂}_{k}(k+1) &= \bigg[\begin{matrix} \mathbf{f̂}\Big( \mathbf{X̂}_{k}^{1}(k), \mathbf{u}(k), \mathbf{d}(k) \Big) & \mathbf{f̂}\Big( \mathbf{X̂}_{k}^{2}(k), \mathbf{u}(k), \mathbf{d}(k) \Big) & \cdots & \mathbf{f̂}\Big( \mathbf{X̂}_{k}^{n_σ}(k), \mathbf{u}(k), \mathbf{d}(k) \Big) \end{matrix}\bigg] \\
515522
\mathbf{x̂}_{k}(k+1) &= \mathbf{X̂}_{k}(k+1)\mathbf{m̂} \\
@@ -527,7 +534,7 @@ noise, respectively.
527534
ISBN9780470045343.
528535
"""
529536
function update_estimate!(estim::UnscentedKalmanFilter, u, ym, d)
530-
x̂, P̂, Q̂, R̂ = estim.x̂, estim.P̂, estim.Q̂, estim.
537+
x̂, P̂, Q̂, R̂, K̂ = estim.x̂, estim.P̂, estim.Q̂, estim., estim.
531538
nym, nx̂, nσ = estim.nym, estim.nx̂, estim.
532539
γ, m̂, Ŝ = estim.γ, estim.m̂, estim.
533540
# --- correction step ---
@@ -540,10 +547,11 @@ function update_estimate!(estim::UnscentedKalmanFilter, u, ym, d)
540547
ŷm = Ŷm *
541548
=.-
542549
Ȳm = Ŷm .- ŷm
543-
M = Hermitian(Ȳm ** Ȳm' + R̂, :L)
544-
K =** Ȳm' / M
545-
x̂_cor =+ K * (ym - ŷm)
546-
P̂_cor =- Hermitian(K * M * K', :L)
550+
= Hermitian(Ȳm ** Ȳm' + R̂, :L)
551+
mul!(K̂, X̄, lmul!(Ŝ, Ȳm'))
552+
rdiv!(K̂, cholesky(M̂))
553+
x̂_cor =+* (ym - ŷm)
554+
P̂_cor =- Hermitian(K̂ **', :L)
547555
# --- prediction step ---
548556
sqrt_P̂_cor = cholesky(P̂_cor).L
549557
X̂_cor = repeat(x̂_cor, 1, nσ) + [zeros(nx̂) +γ*sqrt_P̂_cor -γ*sqrt_P̂_cor]
@@ -553,7 +561,7 @@ function update_estimate!(estim::UnscentedKalmanFilter, u, ym, d)
553561
end
554562
x̂[:] = X̂_next *
555563
X̄_next = X̂_next .-
556-
.data[:] = X̄_next ** X̄_next' +# .data is necessary for Hermitian matrices
564+
.data[:] = X̄_next ** X̄_next' +# .data is necessary for Hermitians
557565
return x̂, P̂
558566
end
559567

@@ -580,6 +588,8 @@ struct ExtendedKalmanFilter{M<:SimModel} <: StateEstimator
580588
P̂0::Hermitian{Float64, Matrix{Float64}}
581589
::Hermitian{Float64, Matrix{Float64}}
582590
::Hermitian{Float64, Matrix{Float64}}
591+
::Matrix{Float64}
592+
::Matrix{Float64}
583593
function ExtendedKalmanFilter{M}(
584594
model, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂
585595
) where {M<:SimModel}
@@ -594,13 +604,15 @@ struct ExtendedKalmanFilter{M<:SimModel} <: StateEstimator
594604
= Hermitian(Q̂, :L)
595605
= Hermitian(R̂, :L)
596606
= copy(P̂0)
607+
K̂, M̂ = zeros(nx̂, nym), zeros(nx̂, nym)
597608
return new(
598609
model,
599610
lastu0, x̂, P̂,
600611
i_ym, nx̂, nym, nyu, nxs,
601612
As, Cs_u, Cs_y, nint_u, nint_ym,
602613
Â, B̂u, Ĉ, B̂d, D̂d,
603-
P̂0, Q̂, R̂
614+
P̂0, Q̂, R̂,
615+
K̂, M̂
604616
)
605617
end
606618
end
@@ -680,14 +692,14 @@ The equations are similar to [`update_estimate!(::KalmanFilter)`](@ref) but with
680692
substitutions ``\mathbf{Â = F̂}(k)`` and ``\mathbf{Ĉ^m = Ĥ^m}(k)``:
681693
```math
682694
\begin{aligned}
683-
\mathbf{M}(k) &= \mathbf{P̂}_{k-1}(k)\mathbf{Ĥ^m}'(k)
695+
\mathbf{}(k) &= \mathbf{P̂}_{k-1}(k)\mathbf{Ĥ^m}'(k)
684696
[\mathbf{Ĥ^m}(k)\mathbf{P̂}_{k-1}(k)\mathbf{Ĥ^m}'(k) + \mathbf{R̂}]^{-1} \\
685-
\mathbf{K}(k) &= \mathbf{F̂}(k) \mathbf{M}(k) \\
697+
\mathbf{}(k) &= \mathbf{F̂}(k) \mathbf{}(k) \\
686698
\mathbf{ŷ^m}(k) &= \mathbf{ĥ^m}\Big( \mathbf{x̂}_{k-1}(k), \mathbf{d}(k) \Big) \\
687699
\mathbf{x̂}_{k}(k+1) &= \mathbf{f̂}\Big( \mathbf{x̂}_{k-1}(k), \mathbf{u}(k), \mathbf{d}(k) \Big)
688-
+ \mathbf{K}(k)[\mathbf{y^m}(k) - \mathbf{ŷ^m}(k)] \\
700+
+ \mathbf{}(k)[\mathbf{y^m}(k) - \mathbf{ŷ^m}(k)] \\
689701
\mathbf{P̂}_{k}(k+1) &= \mathbf{F̂}(k)[\mathbf{P̂}_{k-1}(k)
690-
- \mathbf{M}(k)\mathbf{Ĥ^m}(k)\mathbf{P̂}_{k-1}(k)]\mathbf{F̂}'(k)
702+
- \mathbf{}(k)\mathbf{Ĥ^m}(k)\mathbf{P̂}_{k-1}(k)]\mathbf{F̂}'(k)
691703
+ \mathbf{Q̂}
692704
\end{aligned}
693705
```
@@ -736,16 +748,19 @@ end
736748
737749
Update time-varying/extended Kalman Filter estimates with augmented `Â` and `Ĉm` matrices.
738750
739-
Allows code reuse for the time-varying and extended Kalman filters. They update the state
740-
`x̂` and covariance `P̂` with the same equations. The extended filter substitutes the
741-
augmented model matrices with its Jacobians (`Â = F̂` and `Ĉm = Ĥm`).
751+
Allows code reuse for [`KalmanFilter`](@ref) and [`ExtendedKalmanFilterKalmanFilter`](@ref).
752+
They update the state `x̂` and covariance `P̂` with the same equations. The extended filter
753+
substitutes the augmented model matrices with its Jacobians (`Â = F̂` and `Ĉm = Ĥm`).
754+
The implementation uses in-place operations and explicit factorization to reduce
755+
allocations. See e.g. [`KalmanFilter`](@ref) docstring for the equations.
742756
"""
743757
function update_estimate_kf!(estim, Â, Ĉm, u, ym, d)
744-
x̂, P̂, Q̂, R̂ = estim.x̂, estim.P̂, estim.Q̂, estim.
745-
M = (P̂ * Ĉm') / (Ĉm ** Ĉm' + R̂)
746-
K =* M
758+
x̂, P̂, Q̂, R̂, K̂, M̂ = estim.x̂, estim.P̂, estim.Q̂, estim.R̂, estim.K̂, estim.
759+
mul!(M̂, P̂, Ĉm')
760+
rdiv!(M̂, cholesky!(Hermitian(Ĉm ** Ĉm' + R̂)))
761+
mul!(K̂, Â, M̂)
747762
ŷm = (estim, x̂, d)[estim.i_ym]
748-
x̂[:] = (estim, x̂, u, d) + K * (ym - ŷm)
749-
.data[:] =* (P̂ - M * Ĉm * P̂) *' +# .data is necessary for Hermitian matrices
763+
x̂[:] = (estim, x̂, u, d) + * (ym - ŷm)
764+
.data[:] =* (P̂ - * Ĉm * P̂) *' +# .data is necessary for Hermitians
750765
return x̂, P̂
751766
end

src/estimator/luenberger.jl

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -19,16 +19,16 @@ struct Luenberger <: StateEstimator
1919
D̂d ::Matrix{Float64}
2020
Ĉm ::Matrix{Float64}
2121
D̂dm ::Matrix{Float64}
22-
K::Matrix{Float64}
22+
::Matrix{Float64}
2323
function Luenberger(model, i_ym, nint_u, nint_ym, p̂)
2424
nym, nyu = validate_ym(model, i_ym)
2525
As, Cs_u, Cs_y, nxs, nint_u, nint_ym = init_estimstoch(model, i_ym, nint_u, nint_ym)
2626
nx̂ = model.nx + nxs
2727
Â, B̂u, Ĉ, B̂d, D̂d = augment_model(model, As, Cs_u, Cs_y)
28-
K = try
28+
= try
2929
place(Â, Ĉ, p̂, :o)[:, i_ym]
3030
catch
31-
error("Cannot compute the Luenberger gain L with specified poles p̂.")
31+
error("Cannot compute the Luenberger gain with specified poles p̂.")
3232
end
3333
Ĉm, D̂dm = Ĉ[i_ym, :], D̂d[i_ym, :] # measured outputs ym only
3434
lastu0 = zeros(model.nu)
@@ -40,7 +40,7 @@ struct Luenberger <: StateEstimator
4040
As, Cs_u, Cs_y, nint_u, nint_ym,
4141
Â, B̂u, Ĉ, B̂d, D̂d,
4242
Ĉm, D̂dm,
43-
K
43+
4444
)
4545
end
4646
end
@@ -61,7 +61,7 @@ unmeasured ``\mathbf{y^u}``. `model` matrices are augmented with the stochastic
6161
is specified by the numbers of integrator `nint_u` and `nint_ym` (see [`SteadyKalmanFilter`](@ref)
6262
Extended Help). The argument `p̂` is a vector of `model.nx + sum(nint_ym)` elements
6363
specifying the observer poles/eigenvalues (near ``z=0.5`` by default). The method computes
64-
the observer gain ``\mathbf{K}`` with [`place`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/synthesis/#ControlSystemsBase.place).
64+
the observer gain `` with [`place`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/synthesis/#ControlSystemsBase.place).
6565
6666
# Examples
6767
```jldoctest
@@ -99,7 +99,7 @@ Same than [`update_estimate!(::SteadyKalmanFilter)`](@ref) but using [`Luenberge
9999
"""
100100
function update_estimate!(estim::Luenberger, u, ym, d=Float64[])
101101
Â, B̂u, B̂d, Ĉm, D̂dm = estim.Â, estim.B̂u, estim.B̂d, estim.Ĉm, estim.D̂dm
102-
x̂, K = estim.x̂, estim.K
103-
x̂[:] =*+ B̂u*u + B̂d*d + K*(ym - Ĉm*- D̂dm*d)
102+
x̂, = estim.x̂, estim.
103+
x̂[:] =*+ B̂u*u + B̂d*d + *(ym - Ĉm*- D̂dm*d)
104104
return
105105
end

0 commit comments

Comments
 (0)