Skip to content

Commit 7d8ccde

Browse files
authored
Merge pull request #180 from JuliaControl/diff_interface_ekf
Added: `ExtendedKalmanFilter` now uses `DifferentiationInterface.jl` + now allocation-free
2 parents 179361b + 519d4ed commit 7d8ccde

File tree

9 files changed

+214
-93
lines changed

9 files changed

+214
-93
lines changed

README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ package for Julia.
1111
The package depends on [`ControlSystemsBase.jl`](https://github.com/JuliaControl/ControlSystems.jl)
1212
for the linear systems, [`JuMP.jl`](https://github.com/jump-dev/JuMP.jl) for the
1313
optimization and [`DifferentiationInterface.jl`](https://github.com/JuliaDiff/DifferentiationInterface.jl)
14-
for the differentiation.
14+
for the derivatives.
1515

1616
## Installation
1717

docs/src/index.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ package for Julia.
66
The package depends on [`ControlSystemsBase.jl`](https://github.com/JuliaControl/ControlSystems.jl)
77
for the linear systems, [`JuMP.jl`](https://github.com/jump-dev/JuMP.jl) for the
88
optimization and [`DifferentiationInterface.jl`](https://github.com/JuliaDiff/DifferentiationInterface.jl)
9-
for the differentiation.
9+
for the derivatives.
1010

1111
The objective is to provide a simple, clear and modular framework to quickly design model
1212
predictive controllers (MPCs) in Julia, while preserving the flexibility for advanced

src/controller/transcription.jl

+5-4
Original file line numberDiff line numberDiff line change
@@ -43,11 +43,12 @@ operating point ``\mathbf{x̂_{op}}`` (see [`augment_model`](@ref)):
4343
```
4444
where ``\mathbf{x̂}_i(k+j)`` is the state prediction for time ``k+j``, estimated by the
4545
observer at time ``i=k`` or ``i=k-1`` depending on its `direct` flag. Note that
46-
``\mathbf{X̂_0 = X̂}`` if the operating points is zero, which is typically the case in
47-
practice for [`NonLinModel`](@ref). This transcription method is generally more efficient
48-
for large control horizon ``H_c``, unstable or highly nonlinear plant models/constraints.
46+
``\mathbf{X̂_0 = X̂}`` if the operating point is zero, which is typically the case in practice
47+
for [`NonLinModel`](@ref). This transcription method is generally more efficient for large
48+
control horizon ``H_c``, unstable or highly nonlinear plant models/constraints.
4949
50-
Sparse optimizers like `OSQP` or `Ipopt` are recommended for this method.
50+
Sparse optimizers like `OSQP` or `Ipopt` and sparse Jacobian computations are recommended
51+
for this transcription method.
5152
"""
5253
struct MultipleShooting <: TranscriptionMethod end
5354

src/estimator/execute.jl

+32-13
Original file line numberDiff line numberDiff line change
@@ -36,14 +36,7 @@ where ``\mathbf{x̂_0}(k+1)`` is stored in `x̂next0` argument. The method mutat
3636
function signature for conciseness.
3737
"""
3838
function f̂!(x̂next0, û0, estim::StateEstimator, model::SimModel, x̂0, u0, d0)
39-
# `@views` macro avoid copies with matrix slice operator e.g. [a:b]
40-
@views x̂d, x̂s = x̂0[1:model.nx], x̂0[model.nx+1:end]
41-
@views x̂d_next, x̂s_next = x̂next0[1:model.nx], x̂next0[model.nx+1:end]
42-
mul!(û0, estim.Cs_u, x̂s)
43-
û0 .+= u0
44-
f!(x̂d_next, model, x̂d, û0, d0, model.p)
45-
mul!(x̂s_next, estim.As, x̂s)
46-
return nothing
39+
return f̂!(x̂next0, û0, model, estim.As, estim.Cs_u, x̂0, u0, d0)
4740
end
4841

4942
"""
@@ -58,18 +51,31 @@ function f̂!(x̂next0, _ , estim::StateEstimator, ::LinModel, x̂0, u0, d0)
5851
return nothing
5952
end
6053

54+
"""
55+
f̂!(x̂next0, û0, model::SimModel, As, Cs_u, x̂0, u0, d0)
56+
57+
Same than [`f̂!`](@ref) for [`SimModel`](@ref) but without the `estim` argument.
58+
"""
59+
function f̂!(x̂next0, û0, model::SimModel, As, Cs_u, x̂0, u0, d0)
60+
# `@views` macro avoid copies with matrix slice operator e.g. [a:b]
61+
@views x̂d, x̂s = x̂0[1:model.nx], x̂0[model.nx+1:end]
62+
@views x̂d_next, x̂s_next = x̂next0[1:model.nx], x̂next0[model.nx+1:end]
63+
mul!(û0, Cs_u, x̂s)
64+
û0 .+= u0
65+
f!(x̂d_next, model, x̂d, û0, d0, model.p)
66+
mul!(x̂s_next, As, x̂s)
67+
return nothing
68+
end
69+
6170
@doc raw"""
6271
ĥ!(ŷ0, estim::StateEstimator, model::SimModel, x̂0, d0) -> nothing
6372
6473
Mutating output function ``\mathbf{ĥ}`` of the augmented model, see [`f̂!`](@ref).
6574
"""
6675
function ĥ!(ŷ0, estim::StateEstimator, model::SimModel, x̂0, d0)
67-
# `@views` macro avoid copies with matrix slice operator e.g. [a:b]
68-
@views x̂d, x̂s = x̂0[1:model.nx], x̂0[model.nx+1:end]
69-
h!(ŷ0, model, x̂d, d0, model.p)
70-
mul!(ŷ0, estim.Cs_y, x̂s, 1, 1)
71-
return nothing
76+
return ĥ!(ŷ0, model, estim.Cs_y, x̂0, d0)
7277
end
78+
7379
"""
7480
ĥ!(ŷ0, estim::StateEstimator, model::LinModel, x̂0, d0) -> nothing
7581
@@ -81,6 +87,19 @@ function ĥ!(ŷ0, estim::StateEstimator, ::LinModel, x̂0, d0)
8187
return nothing
8288
end
8389

90+
"""
91+
ĥ!(ŷ0, model::SimModel, Cs_y, x̂0, d0)
92+
93+
Same than [`ĥ!`](@ref) for [`SimModel`](@ref) but without the `estim` argument.
94+
"""
95+
function ĥ!(ŷ0, model::SimModel, Cs_y, x̂0, d0)
96+
# `@views` macro avoid copies with matrix slice operator e.g. [a:b]
97+
@views x̂d, x̂s = x̂0[1:model.nx], x̂0[model.nx+1:end]
98+
h!(ŷ0, model, x̂d, d0, model.p)
99+
mul!(ŷ0, Cs_y, x̂s, 1, 1)
100+
return nothing
101+
end
102+
84103

85104
@doc raw"""
86105
initstate!(estim::StateEstimator, u, ym, d=[]) -> x̂

src/estimator/kalman.jl

+111-33
Original file line numberDiff line numberDiff line change
@@ -624,11 +624,11 @@ This estimator is allocation-free if `model` simulations do not allocate.
624624
disturbances at measured outputs ``\mathbf{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 ``\mathbf{P_{int_{ym}}}(0)`` (composed of integrators).
627-
- `direct=true`: construct with a direct transmission from ``\mathbf{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 ``\mathbf{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
873873
end
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
::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
949957
Construct 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-
``\mathbf{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 ``\mathbf{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 ``\mathbf{y^m}``, the rest
973+
are unmeasured ``\mathbf{y^u}``.
974+
- `σP_0=fill(1/model.nx,model.nx)` or *`sigmaP_0`* : main diagonal of the initial estimate
975+
covariance ``\mathbf{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 ``\mathbf{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+
``\mathbf{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 ``\mathbf{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 ``\mathbf{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 ``\mathbf{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 ``\mathbf{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 ``\mathbf{y^m}`` (a.k.a. current
995+
estimator, in opposition to the delayed/predictor form).
996+
961997
# Examples
962998
```jldoctest
963999
julia> 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
= Hermitian(diagm(NT[σQ; σQint_u; σQint_ym ].^2), :L)
9981035
= 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+
)
10001040
end
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
10051047
Construct the estimator from the augmented covariance matrices `P̂_0`, `Q̂` and `R̂`.
10061048
10071049
This syntax allows nonzero off-diagonal elements in ``\mathbf{P̂}_{-1}(0), \mathbf{Q̂, R̂}``.
10081050
"""
10091051
function 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!
10141098
end
10151099

10161100
"""
@@ -1020,9 +1104,9 @@ Do the same but for the [`ExtendedKalmanFilter`](@ref).
10201104
"""
10211105
function 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)
10281112
end
@@ -1043,8 +1127,8 @@ augmented process model:
10431127
\end{aligned}
10441128
```
10451129
The matrix ``\mathbf{Ĥ^m}`` is the rows of ``\mathbf{Ĥ}`` 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
10691153
function 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.
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̂)
10891167
end
10901168

src/estimator/mhe/execute.jl

+9-2
Original file line numberDiff line numberDiff line change
@@ -445,7 +445,10 @@ end
445445
"Correct the covariance estimate at arrival using `covestim` [`StateEstimator`](@ref)."
446446
function correct_cov!(estim::MovingHorizonEstimator)
447447
nym, nd = estim.nym, estim.model.nd
448-
y0marr, d0arr = @views estim.Y0m[1:nym], estim.D0[1:nd]
448+
buffer = estim.covestim.buffer
449+
y0marr, d0arr = buffer.ym, buffer.d
450+
y0marr .= @views estim.Y0m[1:nym]
451+
d0arr .= @views estim.D0[1:nd]
449452
estim.covestim.x̂0 .= estim.x̂0arr_old
450453
estim.covestim.P̂ .= estim.P̂arr_old
451454
try
@@ -468,7 +471,11 @@ end
468471
"Update the covariance estimate at arrival using `covestim` [`StateEstimator`](@ref)."
469472
function update_cov!(estim::MovingHorizonEstimator)
470473
nu, nd, nym = estim.model.nu, estim.model.nd, estim.nym
471-
u0arr, y0marr, d0arr = @views estim.U0[1:nu], estim.Y0m[1:nym], estim.D0[1:nd]
474+
buffer = estim.covestim.buffer
475+
u0arr, y0marr, d0arr = buffer.u, buffer.ym, buffer.d
476+
u0arr .= @views estim.U0[1:nu]
477+
y0marr .= @views estim.Y0m[1:nym]
478+
d0arr .= @views estim.D0[1:nd]
472479
estim.covestim.x̂0 .= estim.x̂0arr_old
473480
estim.covestim.P̂ .= estim.P̂arr_old
474481
try

src/model/linearization.jl

+2-2
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ The function has the following signature:
88
linfunc!(xnext, y, A, Bu, C, Bd, Dd, backend, x, u, d, cst_x, cst_u, cst_d) -> nothing
99
```
1010
and it should modifies in-place all the arguments before `backend`. The `backend` argument
11-
is an `AbstractADType` backend from `DifferentiationInterface`. The `cst_x`, `cst_u` and
11+
is an `AbstractADType` object from `DifferentiationInterface`. The `cst_x`, `cst_u` and
1212
`cst_d` are `DifferentiationInterface.Constant` objects with the linearization points.
1313
"""
1414
function get_linearization_func(NT, f!, h!, nu, nx, ny, nd, p, backend)
@@ -32,7 +32,7 @@ function get_linearization_func(NT, f!, h!, nu, nx, ny, nd, p, backend)
3232
C_prep = prepare_jacobian(h_x!, y, backend, x, cst_d ; strict)
3333
Dd_prep = prepare_jacobian(h_d!, y, backend, d, cst_x ; strict)
3434
function linfunc!(xnext, y, A, Bu, C, Bd, Dd, backend, x, u, d, cst_x, cst_u, cst_d)
35-
# all the arguments before `x` are mutated in this function
35+
# all the arguments before `backend` are mutated in this function
3636
jacobian!(f_x!, xnext, A, A_prep, backend, x, cst_u, cst_d)
3737
jacobian!(f_u!, xnext, Bu, Bu_prep, backend, u, cst_x, cst_d)
3838
jacobian!(f_d!, xnext, Bd, Bd_prep, backend, d, cst_x, cst_u)

0 commit comments

Comments
 (0)