@@ -21,14 +21,14 @@ struct SteadyKalmanFilter <: StateEstimator
2121 D̂dm :: Matrix{Float64}
2222 Q̂:: Hermitian{Float64, Matrix{Float64}}
2323 R̂:: Hermitian{Float64, Matrix{Float64}}
24- K :: Matrix{Float64}
24+ K̂ :: 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+ K̂ = 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] = R̂
@@ -54,7 +54,7 @@ struct SteadyKalmanFilter <: StateEstimator
5454 Â, B̂u, Ĉ, B̂d, D̂d,
5555 Ĉm, D̂dm,
5656 Q̂, R̂,
57- K
57+ K̂
5858 )
5959 end
6060end
@@ -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 `K̂ ` with the [`kalman`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/synthesis/#ControlSystemsBase.kalman-Tuple{Any,%20Any,%20Any,%20Any,%20Any,%20Vararg{Any}})
134134function. It can sometimes fail, for example when `model` matrices are ill-conditioned. In
135135such 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
166166Update `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 ``\m athbf{K }``:
168+ The [`SteadyKalmanFilter`](@ref) updates it with the precomputed Kalman gain ``\m athbf{K̂ }``:
169169```math
170170\m athbf{x̂}_{k}(k+1) = \m athbf{Â x̂}_{k-1}(k) + \m athbf{B̂_u u}(k) + \m athbf{B̂_d d}(k)
171- + \m athbf{K }[\m athbf{y^m}(k) - \m athbf{Ĉ^m x̂}_{k-1}(k) - \m athbf{D̂_d^m d}(k)]
171+ + \m athbf{K̂ }[\m athbf{y^m}(k) - \m athbf{Ĉ^m x̂}_{k-1}(k) - \m athbf{D̂_d^m d}(k)]
172172```
173173"""
174174function 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̂[:] = Â* x̂ + B̂u* u + B̂d* d + K * (ym - Ĉm* x̂ - D̂dm* d)
176+ x̂, K̂ = estim. x̂, estim. K̂
177+ x̂[:] = Â* x̂ + B̂u* u + B̂d* d + K̂ * (ym - Ĉm* x̂ - D̂dm* d)
178178 return x̂
179179end
180180
@@ -203,6 +203,8 @@ struct KalmanFilter <: StateEstimator
203203 P̂0:: Hermitian{Float64, Matrix{Float64}}
204204 Q̂:: Hermitian{Float64, Matrix{Float64}}
205205 R̂:: Hermitian{Float64, Matrix{Float64}}
206+ K̂:: Matrix{Float64}
207+ M̂:: 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 P̂ = 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
228232end
@@ -298,14 +302,14 @@ Update [`KalmanFilter`](@ref) state `estim.x̂` and estimation error covariance
298302It implements the time-varying Kalman Filter in its predictor (observer) form :
299303```math
300304\b egin{aligned}
301- \m athbf{M }(k) &= \m athbf{P̂}_{k-1}(k)\m athbf{Ĉ^m}'
305+ \m athbf{M̂ }(k) &= \m athbf{P̂}_{k-1}(k)\m athbf{Ĉ^m}'
302306 [\m athbf{Ĉ^m P̂}_{k-1}(k)\m athbf{Ĉ^m}' + \m athbf{R̂}]^{-1} \\
303- \m athbf{K }(k) &= \m athbf{Â M (k)} \\
307+ \m athbf{K̂ }(k) &= \m athbf{Â M̂ (k)} \\
304308 \m athbf{ŷ^m}(k) &= \m athbf{Ĉ^m x̂}_{k-1}(k) + \m athbf{D̂_d^m d}(k) \\
305309 \m athbf{x̂}_{k}(k+1) &= \m athbf{Â x̂}_{k-1}(k) + \m athbf{B̂_u u}(k) + \m athbf{B̂_d d}(k)
306- + \m athbf{K }(k)[\m athbf{y^m}(k) - \m athbf{ŷ^m}(k)] \\
310+ + \m athbf{K̂ }(k)[\m athbf{y^m}(k) - \m athbf{ŷ^m}(k)] \\
307311 \m athbf{P̂}_{k}(k+1) &= \m athbf{Â}[\m athbf{P̂}_{k-1}(k)
308- - \m athbf{M }(k)\m athbf{Ĉ^m P̂}_{k-1}(k)]\m athbf{Â}' + \m athbf{Q̂}
312+ - \m athbf{M̂ }(k)\m athbf{Ĉ^m P̂}_{k-1}(k)]\m athbf{Â}' + \m athbf{Q̂}
309313\e nd{aligned}
310314```
311315based 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 Q̂:: Hermitian{Float64, Matrix{Float64}}
344348 R̂:: Hermitian{Float64, Matrix{Float64}}
349+ K̂:: Matrix{Float64}
345350 nσ:: Int
346351 γ:: Float64
347352 m̂:: 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 P̂ = copy (P̂0)
368+ K̂ = 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 \m athbf{ŷ^m}(k) &= \m athbf{Ŷ^m}(k) \m athbf{m̂} \\
507514 \m athbf{X̄}_{k-1}(k) &= \b egin{bmatrix} \m athbf{X̂}_{k-1}^{1}(k) - \m athbf{x̂}_{k-1}(k) & \m athbf{X̂}_{k-1}^{2}(k) - \m athbf{x̂}_{k-1}(k) & \c dots & \m athbf{X̂}_{k-1}^{n_σ}(k) - \m athbf{x̂}_{k-1}(k) \e nd{bmatrix} \\
508515 \m athbf{Ȳ^m}(k) &= \b egin{bmatrix} \m athbf{Ŷ^m}^{1}(k) - \m athbf{ŷ^m}(k) & \m athbf{Ŷ^m}^{2}(k) - \m athbf{ŷ^m}(k) & \c dots & \m athbf{Ŷ^m}^{n_σ}(k) - \m athbf{ŷ^m}(k) \e nd{bmatrix} \\
509- \m athbf{M }(k) &= \m athbf{Ȳ^m}(k) \m athbf{Ŝ} \m athbf{Ȳ^m}'(k) + \m athbf{R̂} \\
510- \m athbf{K }(k) &= \m athbf{X̄}_{k-1}(k) \m athbf{Ŝ} \m athbf{Ȳ^m}'(k) \m athbf{M }(k)^{-1} \\
511- \m athbf{x̂}_k(k) &= \m athbf{x̂}_{k-1}(k) + \m athbf{K }(k) \b ig[ \m athbf{y^m}(k) - \m athbf{ŷ^m}(k) \b ig] \\
512- \m athbf{P̂}_k(k) &= \m athbf{P̂}_{k-1}(k) - \m athbf{K }(k) \m athbf{M }(k) \m athbf{K }'(k) \\
516+ \m athbf{M̂ }(k) &= \m athbf{Ȳ^m}(k) \m athbf{Ŝ} \m athbf{Ȳ^m}'(k) + \m athbf{R̂} \\
517+ \m athbf{K̂ }(k) &= \m athbf{X̄}_{k-1}(k) \m athbf{Ŝ} \m athbf{Ȳ^m}'(k) \b ig[ \ m athbf{M̂ }(k)\b ig] ^{-1} \\
518+ \m athbf{x̂}_k(k) &= \m athbf{x̂}_{k-1}(k) + \m athbf{K̂ }(k) \b ig[ \m athbf{y^m}(k) - \m athbf{ŷ^m}(k) \b ig] \\
519+ \m athbf{P̂}_k(k) &= \m athbf{P̂}_{k-1}(k) - \m athbf{K̂ }(k) \m athbf{M̂ }(k) \m athbf{K̂ }'(k) \\
513520 \m athbf{X̂}_k(k) &= \b igg[\b egin{matrix} \m athbf{x̂}_{k}(k) & \m athbf{x̂}_{k}(k) & \c dots & \m athbf{x̂}_{k}(k) \e nd{matrix}\b igg] + \b igg[\b egin{matrix} \m athbf{0} & \g amma \s qrt{\m athbf{P̂}_{k}(k)} & - \g amma \s qrt{\m athbf{P̂}_{k}(k)} \e nd{matrix}\b igg] \\
514521 \m athbf{X̂}_{k}(k+1) &= \b igg[\b egin{matrix} \m athbf{f̂}\B ig( \m athbf{X̂}_{k}^{1}(k), \m athbf{u}(k), \m athbf{d}(k) \B ig) & \m athbf{f̂}\B ig( \m athbf{X̂}_{k}^{2}(k), \m athbf{u}(k), \m athbf{d}(k) \B ig) & \c dots & \m athbf{f̂}\B ig( \m athbf{X̂}_{k}^{n_σ}(k), \m athbf{u}(k), \m athbf{d}(k) \B ig) \e nd{matrix}\b igg] \\
515522 \m athbf{x̂}_{k}(k+1) &= \m athbf{X̂}_{k}(k+1)\m athbf{m̂} \\
@@ -527,7 +534,7 @@ noise, respectively.
527534 ISBN9780470045343.
528535"""
529536function update_estimate! (estim:: UnscentedKalmanFilter , u, ym, d)
530- x̂, P̂, Q̂, R̂ = estim. x̂, estim. P̂, estim. Q̂, estim. R̂
537+ x̂, P̂, Q̂, R̂, K̂ = estim. x̂, estim. P̂, estim. Q̂, estim. R̂, estim . K̂
531538 nym, nx̂, nσ = estim. nym, estim. nx̂, estim. nσ
532539 γ, m̂, Ŝ = estim. γ, estim. m̂, estim. Ŝ
533540 # --- correction step ---
@@ -540,10 +547,11 @@ function update_estimate!(estim::UnscentedKalmanFilter, u, ym, d)
540547 ŷm = Ŷm * m̂
541548 X̄ = X̂ .- x̂
542549 Ȳm = Ŷm .- ŷm
543- M = Hermitian (Ȳm * Ŝ * Ȳm' + R̂, :L )
544- K = X̄ * Ŝ * Ȳm' / M
545- x̂_cor = x̂ + K * (ym - ŷm)
546- P̂_cor = P̂ - Hermitian (K * M * K' , :L )
550+ M̂ = Hermitian (Ȳm * Ŝ * Ȳm' + R̂, :L )
551+ mul! (K̂, X̄, lmul! (Ŝ, Ȳm' ))
552+ rdiv! (K̂, cholesky (M̂))
553+ x̂_cor = x̂ + K̂ * (ym - ŷm)
554+ P̂_cor = P̂ - Hermitian (K̂ * M̂ * 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 * m̂
555563 X̄_next = X̂_next .- x̂
556- P̂. data[:] = X̄_next * Ŝ * X̄_next' + Q̂ # .data is necessary for Hermitian matrices
564+ P̂. data[:] = X̄_next * Ŝ * X̄_next' + Q̂ # .data is necessary for Hermitians
557565 return x̂, P̂
558566end
559567
@@ -580,6 +588,8 @@ struct ExtendedKalmanFilter{M<:SimModel} <: StateEstimator
580588 P̂0:: Hermitian{Float64, Matrix{Float64}}
581589 Q̂:: Hermitian{Float64, Matrix{Float64}}
582590 R̂:: Hermitian{Float64, Matrix{Float64}}
591+ K̂:: Matrix{Float64}
592+ M̂:: 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 Q̂ = Hermitian (Q̂, :L )
595605 R̂ = Hermitian (R̂, :L )
596606 P̂ = 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
606618end
@@ -680,14 +692,14 @@ The equations are similar to [`update_estimate!(::KalmanFilter)`](@ref) but with
680692substitutions ``\m athbf{Â = F̂}(k)`` and ``\m athbf{Ĉ^m = Ĥ^m}(k)``:
681693```math
682694\b egin{aligned}
683- \m athbf{M }(k) &= \m athbf{P̂}_{k-1}(k)\m athbf{Ĥ^m}'(k)
695+ \m athbf{M̂ }(k) &= \m athbf{P̂}_{k-1}(k)\m athbf{Ĥ^m}'(k)
684696 [\m athbf{Ĥ^m}(k)\m athbf{P̂}_{k-1}(k)\m athbf{Ĥ^m}'(k) + \m athbf{R̂}]^{-1} \\
685- \m athbf{K }(k) &= \m athbf{F̂}(k) \m athbf{M }(k) \\
697+ \m athbf{K̂ }(k) &= \m athbf{F̂}(k) \m athbf{M̂ }(k) \\
686698 \m athbf{ŷ^m}(k) &= \m athbf{ĥ^m}\B ig( \m athbf{x̂}_{k-1}(k), \m athbf{d}(k) \B ig) \\
687699 \m athbf{x̂}_{k}(k+1) &= \m athbf{f̂}\B ig( \m athbf{x̂}_{k-1}(k), \m athbf{u}(k), \m athbf{d}(k) \B ig)
688- + \m athbf{K }(k)[\m athbf{y^m}(k) - \m athbf{ŷ^m}(k)] \\
700+ + \m athbf{K̂ }(k)[\m athbf{y^m}(k) - \m athbf{ŷ^m}(k)] \\
689701 \m athbf{P̂}_{k}(k+1) &= \m athbf{F̂}(k)[\m athbf{P̂}_{k-1}(k)
690- - \m athbf{M }(k)\m athbf{Ĥ^m}(k)\m athbf{P̂}_{k-1}(k)]\m athbf{F̂}'(k)
702+ - \m athbf{M̂ }(k)\m athbf{Ĥ^m}(k)\m athbf{P̂}_{k-1}(k)]\m athbf{F̂}'(k)
691703 + \m athbf{Q̂}
692704\e nd{aligned}
693705```
@@ -736,16 +748,19 @@ end
736748
737749Update 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"""
743757function update_estimate_kf! (estim, Â, Ĉm, u, ym, d)
744- x̂, P̂, Q̂, R̂ = estim. x̂, estim. P̂, estim. Q̂, estim. R̂
745- M = (P̂ * Ĉm' ) / (Ĉm * P̂ * Ĉm' + R̂)
746- K = Â * M
758+ x̂, P̂, Q̂, R̂, K̂, M̂ = estim. x̂, estim. P̂, estim. Q̂, estim. R̂, estim. K̂, estim. M̂
759+ mul! (M̂, P̂, Ĉm' )
760+ rdiv! (M̂, cholesky! (Hermitian (Ĉm * P̂ * Ĉm' + R̂)))
761+ mul! (K̂, Â, M̂)
747762 ŷm = ĥ (estim, x̂, d)[estim. i_ym]
748- x̂[:] = f̂ (estim, x̂, u, d) + K * (ym - ŷm)
749- P̂. data[:] = Â * (P̂ - M * Ĉm * P̂) * Â' + Q̂ # .data is necessary for Hermitian matrices
763+ x̂[:] = f̂ (estim, x̂, u, d) + K̂ * (ym - ŷm)
764+ P̂. data[:] = Â * (P̂ - M̂ * Ĉm * P̂) * Â' + Q̂ # .data is necessary for Hermitians
750765 return x̂, P̂
751766end
0 commit comments