@@ -624,11 +624,11 @@ This estimator is allocation-free if `model` simulations do not allocate.
624624 disturbances at measured outputs ``\m athbf{Q_{int_{ym}}}`` (composed of integrators).
625625- `σPint_ym_0=fill(1,sum(nint_ym))` or *`sigmaPint_ym_0`* : same than `σP_0` but for the unmeasured
626626 disturbances at measured outputs ``\m athbf{P_{int_{ym}}}(0)`` (composed of integrators).
627- - `direct=true`: construct with a direct transmission from ``\m athbf{y^m}`` (a.k.a. current
628- estimator, in opposition to the delayed/predictor form).
629627- `α=1e-3` or *`alpha`* : alpha parameter, spread of the state distribution ``(0 < α ≤ 1)``.
630628- `β=2` or *`beta`* : beta parameter, skewness and kurtosis of the states distribution ``(β ≥ 0)``.
631629- `κ=0` or *`kappa`* : kappa parameter, another spread parameter ``(0 ≤ κ ≤ 3)``.
630+ - `direct=true`: construct with a direct transmission from ``\m athbf{y^m}`` (a.k.a. current
631+ estimator, in opposition to the delayed/predictor form).
632632
633633# Examples
634634```jldoctest
@@ -872,7 +872,12 @@ function update_estimate!(estim::UnscentedKalmanFilter, y0m, d0, u0)
872872 return nothing
873873end
874874
875- struct ExtendedKalmanFilter{NT<: Real , SM<: SimModel } <: StateEstimator{NT}
875+ struct ExtendedKalmanFilter{
876+ NT<: Real ,
877+ SM<: SimModel ,
878+ JB<: AbstractADType ,
879+ LF<: Function
880+ } <: StateEstimator{NT}
876881 model:: SM
877882 lastu0:: Vector{NT}
878883 x̂op :: Vector{NT}
@@ -904,12 +909,14 @@ struct ExtendedKalmanFilter{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
904909 F̂ :: Matrix{NT}
905910 Ĥ :: Matrix{NT}
906911 Ĥm :: Matrix{NT}
912+ jacobian:: JB
913+ linfunc!:: LF
907914 direct:: Bool
908915 corrected:: Vector{Bool}
909916 buffer:: StateEstimatorBuffer{NT}
910917 function ExtendedKalmanFilter {NT} (
911- model:: SM , i_ym, nint_u, nint_ym, P̂_0, Q̂, R̂; direct= true
912- ) where {NT<: Real , SM<: SimModel }
918+ model:: SM , i_ym, nint_u, nint_ym, P̂_0, Q̂, R̂; jacobian :: JB , linfunc! :: LF , direct= true
919+ ) where {NT<: Real , SM<: SimModel , JB <: AbstractADType , LF <: Function }
913920 nu, ny, nd = model. nu, model. ny, model. nd
914921 nym, nyu = validate_ym (model, i_ym)
915922 As, Cs_u, Cs_y, nint_u, nint_ym = init_estimstoch (model, i_ym, nint_u, nint_ym)
@@ -928,7 +935,7 @@ struct ExtendedKalmanFilter{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
928935 Ĥ, Ĥm = zeros (NT, ny, nx̂), zeros (NT, nym, nx̂)
929936 corrected = [false ]
930937 buffer = StateEstimatorBuffer {NT} (nu, nx̂, nym, ny, nd)
931- return new {NT, SM} (
938+ return new {NT, SM, JB, LF } (
932939 model,
933940 lastu0, x̂op, f̂op, x̂0, P̂,
934941 i_ym, nx̂, nym, nyu, nxs,
@@ -937,6 +944,7 @@ struct ExtendedKalmanFilter{NT<:Real, SM<:SimModel} <: StateEstimator{NT}
937944 P̂_0, Q̂, R̂,
938945 K̂,
939946 F̂_û, F̂, Ĥ, Ĥm,
947+ jacobian, linfunc!,
940948 direct, corrected,
941949 buffer
942950 )
@@ -948,16 +956,44 @@ end
948956
949957Construct an extended Kalman Filter with the [`SimModel`](@ref) `model`.
950958
951- Both [`LinModel`](@ref) and [`NonLinModel`](@ref) are supported. The process model and the
952- keyword arguments are identical to [`UnscentedKalmanFilter`](@ref), except for `α`, `β` and
953- `κ` which do not apply to the extended Kalman Filter. The Jacobians of the augmented model
954- ``\m athbf{f̂, ĥ}`` are computed with [`ForwardDiff`](@extref ForwardDiff) automatic
955- differentiation. This estimator allocates memory for the Jacobians.
956-
959+ Both [`LinModel`](@ref) and [`NonLinModel`](@ref) are supported. The process model is
960+ identical to [`UnscentedKalmanFilter`](@ref). By default, the Jacobians of the augmented
961+ model ``\m athbf{f̂, ĥ}`` are computed with [`ForwardDiff`](@extref ForwardDiff) automatic
962+ differentiation. This estimator is allocation-free if `model` simulations do not allocate.
957963!!! warning
958964 See the Extended Help of [`linearize`](@ref) function if you get an error like:
959965 `MethodError: no method matching (::var"##")(::Vector{ForwardDiff.Dual})`.
960966
967+ # Arguments
968+ !!! info
969+ Keyword arguments with *`emphasis`* are non-Unicode alternatives.
970+
971+ - `model::SimModel` : (deterministic) model for the estimations.
972+ - `i_ym=1:model.ny` : `model` output indices that are measured ``\m athbf{y^m}``, the rest
973+ are unmeasured ``\m athbf{y^u}``.
974+ - `σP_0=fill(1/model.nx,model.nx)` or *`sigmaP_0`* : main diagonal of the initial estimate
975+ covariance ``\m athbf{P}(0)``, specified as a standard deviation vector.
976+ - `σQ=fill(1/model.nx,model.nx)` or *`sigmaQ`* : main diagonal of the process noise
977+ covariance ``\m athbf{Q}`` of `model`, specified as a standard deviation vector.
978+ - `σR=fill(1,length(i_ym))` or *`sigmaR`* : main diagonal of the sensor noise covariance
979+ ``\m athbf{R}`` of `model` measured outputs, specified as a standard deviation vector.
980+ - `nint_u=0`: integrator quantity for the stochastic model of the unmeasured disturbances at
981+ the manipulated inputs (vector), use `nint_u=0` for no integrator (see Extended Help).
982+ - `nint_ym=default_nint(model,i_ym,nint_u)` : same than `nint_u` but for the unmeasured
983+ disturbances at the measured outputs, use `nint_ym=0` for no integrator (see Extended Help).
984+ - `σQint_u=fill(1,sum(nint_u))` or *`sigmaQint_u`* : same than `σQ` but for the unmeasured
985+ disturbances at manipulated inputs ``\m athbf{Q_{int_u}}`` (composed of integrators).
986+ - `σPint_u_0=fill(1,sum(nint_u))` or *`sigmaPint_u_0`* : same than `σP_0` but for the unmeasured
987+ disturbances at manipulated inputs ``\m athbf{P_{int_u}}(0)`` (composed of integrators).
988+ - `σQint_ym=fill(1,sum(nint_ym))` or *`sigmaQint_u`* : same than `σQ` for the unmeasured
989+ disturbances at measured outputs ``\m athbf{Q_{int_{ym}}}`` (composed of integrators).
990+ - `σPint_ym_0=fill(1,sum(nint_ym))` or *`sigmaPint_ym_0`* : same than `σP_0` but for the unmeasured
991+ disturbances at measured outputs ``\m athbf{P_{int_{ym}}}(0)`` (composed of integrators).
992+ - `jacobian=AutoForwardDiff()`: an `AbstractADType` backend for the Jacobians of the augmented
993+ model, see [`DifferentiationInterface` doc](@extref DifferentiationInterface List).
994+ - `direct=true`: construct with a direct transmission from ``\m athbf{y^m}`` (a.k.a. current
995+ estimator, in opposition to the delayed/predictor form).
996+
961997# Examples
962998```jldoctest
963999julia> model = NonLinModel((x,u,_,_)->0.2x+u, (x,_,_)->-3x, 5.0, 1, 1, 1, solver=nothing);
@@ -983,6 +1019,7 @@ function ExtendedKalmanFilter(
9831019 sigmaQint_u = fill (1 , max (sum (nint_u), 0 )),
9841020 sigmaPint_ym_0 = fill (1 , max (sum (nint_ym), 0 )),
9851021 sigmaQint_ym = fill (1 , max (sum (nint_ym), 0 )),
1022+ jacobian = AutoForwardDiff (),
9861023 direct = true ,
9871024 σP_0 = sigmaP_0,
9881025 σQ = sigmaQ,
@@ -996,21 +1033,68 @@ function ExtendedKalmanFilter(
9961033 P̂_0 = Hermitian (diagm (NT[σP_0; σPint_u_0; σPint_ym_0]. ^ 2 ), :L )
9971034 Q̂ = Hermitian (diagm (NT[σQ; σQint_u; σQint_ym ]. ^ 2 ), :L )
9981035 R̂ = Hermitian (diagm (NT[σR;]. ^ 2 ), :L )
999- return ExtendedKalmanFilter {NT} (model, i_ym, nint_u, nint_ym, P̂_0, Q̂, R̂; direct)
1036+ linfunc! = get_ekf_linfunc (NT, model, i_ym, nint_u, nint_ym, jacobian)
1037+ return ExtendedKalmanFilter {NT} (
1038+ model, i_ym, nint_u, nint_ym, P̂_0, Q̂, R̂; jacobian, linfunc!, direct
1039+ )
10001040end
10011041
10021042@doc raw """
1003- ExtendedKalmanFilter(model, i_ym, nint_u, nint_ym, P̂_0, Q̂, R̂; direct=true)
1043+ ExtendedKalmanFilter(
1044+ model, i_ym, nint_u, nint_ym, P̂_0, Q̂, R̂; jacobian=AutoForwardDiff(), direct=true
1045+ )
10041046
10051047Construct the estimator from the augmented covariance matrices `P̂_0`, `Q̂` and `R̂`.
10061048
10071049This syntax allows nonzero off-diagonal elements in ``\m athbf{P̂}_{-1}(0), \m athbf{Q̂, R̂}``.
10081050"""
10091051function ExtendedKalmanFilter (
1010- model:: SM , i_ym, nint_u, nint_ym,P̂_0, Q̂, R̂; direct= true
1052+ model:: SM , i_ym, nint_u, nint_ym, P̂_0, Q̂, R̂; jacobian = AutoForwardDiff (), direct= true
10111053) where {NT<: Real , SM<: SimModel{NT} }
1012- P̂_0, Q̂, R̂ = to_mat (P̂_0), to_mat (Q̂), to_mat (R̂)
1013- return ExtendedKalmanFilter {NT} (model, i_ym, nint_u, nint_ym, P̂_0, Q̂, R̂; direct)
1054+ P̂_0, Q̂, R̂ = to_mat (P̂_0), to_mat (Q̂), to_mat (R̂)
1055+ linfunc! = get_ekf_linfunc (NT, model, i_ym, nint_u, nint_ym, jacobian)
1056+ return ExtendedKalmanFilter {NT} (
1057+ model, i_ym, nint_u, nint_ym, P̂_0, Q̂, R̂; jacobian, direct, linfunc!
1058+ )
1059+ end
1060+
1061+ """
1062+ get_ekf_linfunc(NT, model, i_ym, nint_u, nint_ym, jacobian) -> linfunc!
1063+
1064+ Return the `linfunc!` function that computes the Jacobians of the augmented model.
1065+
1066+ The function has the two following methods:
1067+ ```
1068+ linfunc!(x̂0next , ::Nothing, F̂ , ::Nothing, backend, x̂0, cst_u0, cst_d0) -> nothing
1069+ linfunc!(::Nothing, ŷ0 , ::Nothing, Ĥ , backend, x̂0, _ , cst_d0) -> nothing
1070+ ```
1071+ To respectively compute only `F̂` or `Ĥ` Jacobian. The methods mutate all the arguments
1072+ before `backend` argument. The `backend` argument is an `AbstractADType` object from
1073+ `DifferentiationInterface`. The `cst_u0` and `cst_d0` are `DifferentiationInterface.Constant`
1074+ objects with the linearization points.
1075+ """
1076+ function get_ekf_linfunc (NT, model, i_ym, nint_u, nint_ym, jacobian)
1077+ As, Cs_u, Cs_y = init_estimstoch (model, i_ym, nint_u, nint_ym)
1078+ f̂_ekf! (x̂0next, x̂0, û0, u0, d0) = f̂! (x̂0next, û0, model, As, Cs_u, x̂0, u0, d0)
1079+ ĥ_ekf! (ŷ0, x̂0, d0) = ĥ! (ŷ0, model, Cs_y, x̂0, d0)
1080+ strict = Val (true )
1081+ nu, ny, nd = model. nu, model. ny, model. nd
1082+ nx̂ = model. nx + size (As, 1 )
1083+ x̂0next = zeros (NT, nx̂)
1084+ ŷ0 = zeros (NT, ny)
1085+ x̂0 = zeros (NT, nx̂)
1086+ tmp_û0 = Cache (zeros (NT, nu))
1087+ cst_u0 = Constant (zeros (NT, nu))
1088+ cst_d0 = Constant (zeros (NT, nd))
1089+ F̂_prep = prepare_jacobian (f̂_ekf!, x̂0next, jacobian, x̂0, tmp_û0, cst_u0, cst_d0; strict)
1090+ Ĥ_prep = prepare_jacobian (ĥ_ekf!, ŷ0, jacobian, x̂0, cst_d0; strict)
1091+ function linfunc! (x̂0next, ŷ0:: Nothing , F̂, Ĥ:: Nothing , backend, x̂0, cst_u0, cst_d0)
1092+ return jacobian! (f̂_ekf!, x̂0next, F̂, F̂_prep, backend, x̂0, tmp_û0, cst_u0, cst_d0)
1093+ end
1094+ function linfunc! (x̂0next:: Nothing , ŷ0, F̂:: Nothing , Ĥ, backend, x̂0, _ , cst_d0)
1095+ return jacobian! (ĥ_ekf!, ŷ0, Ĥ, Ĥ_prep, backend, x̂0, cst_d0)
1096+ end
1097+ return linfunc!
10141098end
10151099
10161100"""
@@ -1020,9 +1104,9 @@ Do the same but for the [`ExtendedKalmanFilter`](@ref).
10201104"""
10211105function correct_estimate! (estim:: ExtendedKalmanFilter , y0m, d0)
10221106 model, x̂0 = estim. model, estim. x̂0
1023- ŷ0 = estim . buffer . ŷ
1024- ĥAD! = ( ŷ0, x̂0) -> ĥ! (ŷ0, estim, model, x̂0, d0)
1025- ForwardDiff . jacobian! ( estim. Ĥ, ĥAD!, ŷ0, x̂0 )
1107+ cst_d0 = Constant (d0)
1108+ ŷ0, Ĥ = estim. buffer . ŷ, estim . Ĥ
1109+ estim . linfunc! ( nothing , ŷ0, nothing , Ĥ, estim. jacobian, x̂0, nothing , cst_d0 )
10261110 estim. Ĥm .= @views estim. Ĥ[estim. i_ym, :]
10271111 return correct_estimate_kf! (estim, y0m, d0, estim. Ĥm)
10281112end
@@ -1043,8 +1127,8 @@ augmented process model:
10431127\e nd{aligned}
10441128```
10451129The matrix ``\m athbf{Ĥ^m}`` is the rows of ``\m athbf{Ĥ}`` that are measured outputs. The
1046- Jacobians are computed with [`ForwardDiff`](@extref ForwardDiff). The correction and
1047- prediction step equations are provided below. The correction step is skipped if
1130+ Jacobians are computed with [`ForwardDiff`](@extref ForwardDiff) bu default . The correction
1131+ and prediction step equations are provided below. The correction step is skipped if
10481132`estim.direct == true` since it's already done by the user.
10491133
10501134# Correction Step
@@ -1069,22 +1153,16 @@ prediction step equations are provided below. The correction step is skipped if
10691153function update_estimate! (estim:: ExtendedKalmanFilter{NT} , y0m, d0, u0) where NT<: Real
10701154 model, x̂0 = estim. model, estim. x̂0
10711155 nx̂, nu = estim. nx̂, model. nu
1156+ cst_u0, cst_d0 = Constant (u0), Constant (d0)
10721157 if ! estim. direct
1073- ŷ0 = estim. buffer. ŷ
1074- ĥAD! = (ŷ0, x̂0) -> ĥ! (ŷ0, estim, model, x̂0, d0)
1075- ForwardDiff. jacobian! (estim. Ĥ, ĥAD!, ŷ0, x̂0)
1158+ ŷ0, Ĥ = estim. buffer. ŷ, estim. Ĥ
1159+ estim. linfunc! (nothing , ŷ0, nothing , Ĥ, estim. jacobian, x̂0, nothing , cst_d0)
10761160 estim. Ĥm .= @views estim. Ĥ[estim. i_ym, :]
10771161 correct_estimate_kf! (estim, y0m, d0, estim. Ĥm)
10781162 end
10791163 x̂0corr = estim. x̂0
1080- # concatenate x̂0next and û0 vectors to allows û0 vector with dual numbers for AD:
1081- # TODO : remove this allocation using estim.buffer
1082- x̂0nextû = Vector {NT} (undef, nx̂ + nu)
1083- f̂AD! = (x̂0nextû, x̂0corr) -> @views f̂! (
1084- x̂0nextû[1 : nx̂], x̂0nextû[nx̂+ 1 : end ], estim, model, x̂0corr, u0, d0
1085- )
1086- ForwardDiff. jacobian! (estim. F̂_û, f̂AD!, x̂0nextû, x̂0corr)
1087- estim. F̂ .= @views estim. F̂_û[1 : estim. nx̂, :]
1164+ x̂0next, F̂ = estim. buffer. x̂, estim. F̂
1165+ estim. linfunc! (x̂0next, nothing , F̂, nothing , estim. jacobian, x̂0corr, cst_u0, cst_d0)
10881166 return predict_estimate_kf! (estim, u0, d0, estim. F̂)
10891167end
10901168
0 commit comments