Functions: State Estimators
This module includes many state estimators (or state observer), both for deterministic and stochastic systems. The implementations focus on control applications, that is, relying on the estimates to compute a full state feedback (predictive controllers, in this package). They all incorporates some kind of integral action by default, since it is generally desired to eliminate the steady-state error with closed-loop control (offset-free tracking).
If you plan to use the estimators for other contexts than this specific package (e.g. : filter, parameter estimation, etc.), careful must be taken at construction since the integral action is not necessarily desired. The options |
The estimators are all implemented in the predictor form (a.k.a. observer form), that is, they all estimates at each discrete time the states of the next period [1]. In contrast, the filter form that estimates is sometimes slightly more accurate.
The predictor form comes in handy for control applications since the estimations come after the controller computations, without introducing any additional delays. Moreover, the moveinput!
method of the predictive controllers does not automatically update the estimates with updatestate!
. This allows applying the calculated inputs on the real plant before starting the potentially expensive estimator computations (see Manual for examples).
All the estimators support measured and unmeasured model outputs, where refers to all of them. |
StateEstimator
#
ModelPredictiveControl.StateEstimator
— Type
Abstract supertype of all state estimators.
(estim::StateEstimator)(d=[]) -> ŷ
Functor allowing callable StateEstimator
object as an alias for evaloutput
.
Examples
julia> kf = KalmanFilter(setop!(LinModel(tf(3, [10, 1]), 2), yop=[20]));
julia> ŷ = kf()
1-element Vector{Float64}:
20.0
SteadyKalmanFilter
#
ModelPredictiveControl.SteadyKalmanFilter
— Type
SteadyKalmanFilter(model::LinModel; <keyword arguments>)
Construct a steady-state Kalman Filter with the LinModel
model
.
The steady-state (or asymptotic) Kalman filter is based on the process model :
with sensor and process noises as uncorrelated zero mean white noise vectors, with a respective covariance of and . The arguments are in standard deviations σ, i.e. same units than outputs and states. The matrices are model
matrices augmented with the stochastic model, which is specified by the numbers of integrator nint_u
and nint_ym
(see Extended Help). Likewise, the covariance matrices are augmented with and . The matrices are the rows of that correspond to measured outputs (and unmeasured ones, for ).
Arguments
-
model::LinModel
: (deterministic) model for the estimations. -
i_ym=1:model.ny
:model
output indices that are measured , the rest are unmeasured . -
σQ=fill(1/model.nx,model.nx)
: main diagonal of the process noise covariance ofmodel
, specified as a standard deviation vector. -
σR=fill(1,length(i_ym))
: main diagonal of the sensor noise covariance ofmodel
measured outputs, specified as a standard deviation vector. -
nint_u=0
: integrator quantity for the stochastic model of the unmeasured disturbances at the manipulated inputs (vector), usenint_u=0
for no integrator (see Extended Help). -
σQint_u=fill(1,sum(nint_u))
: same thanσQ
but for the unmeasured disturbances at manipulated inputs (composed of integrators). -
nint_ym=default_nint(model,i_ym,nint_u)
: same thannint_u
but for the unmeasured disturbances at the measured outputs, usenint_ym=0
for no integrator (see Extended Help). -
σQint_ym=fill(1,sum(nint_ym))
: same thanσQ
for the unmeasured disturbances at measured outputs (composed of integrators).
Examples
julia> model = LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 0.5);
julia> estim = SteadyKalmanFilter(model, i_ym=[2], σR=[1], σQint_ym=[0.01])
SteadyKalmanFilter estimator with a sample time Ts = 0.5 s, LinModel and:
1 manipulated inputs u (0 integrating states)
3 estimated states x̂
1 measured outputs ym (1 integrating states)
1 unmeasured outputs yu
0 measured disturbances d
Extended Help
The model augmentation with nint_u
vector adds integrators at model manipulated inputs, and nint_ym
, at measured outputs. They create the integral action when the estimator is used in a controller as state feedback. By default, the method default_nint
adds one integrator per measured output if feasible. The argument nint_ym
can also be tweaked by following these rules on each measured output:
* Use 0 integrator if the model output is already integrating (else it will be unobservable) * Use 1 integrator if the disturbances on the output are typically "step-like" * Use 2 integrators if the disturbances on the output are typically "ramp-like"
The function init_estimstoch
builds the stochastic model for estimation.
Increasing |
The constructor pre-compute the steady-state Kalman gain K̂
with the kalman
function. It can sometimes fail, for example when model
matrices are ill-conditioned. In such a case, you can try the alternative time-varying KalmanFilter
.
SteadyKalmanFilter(model, i_ym, nint_u, nint_ym, Q̂, R̂)
Construct the estimator from the augmented covariance matrices Q̂
and R̂
.
This syntax allows nonzero off-diagonal elements in .
KalmanFilter
#
ModelPredictiveControl.KalmanFilter
— Type
KalmanFilter(model::LinModel; <keyword arguments>)
Construct a time-varying Kalman Filter with the LinModel
model
.
The process model is identical to SteadyKalmanFilter
. The matrix is the estimation error covariance of model
states augmented with the stochastic ones (specified by nint_u
and nint_ym
). Three keyword arguments modify its initial value with .
Arguments
-
model::LinModel
: (deterministic) model for the estimations. -
σP0=fill(1/model.nx,model.nx)
: main diagonal of the initial estimate covariance , specified as a standard deviation vector. -
σP0int_u=fill(1,sum(nint_u))
: same thanσP0
but for the unmeasured disturbances at manipulated inputs (composed of integrators). -
σP0int_ym=fill(1,sum(nint_ym))
: same thanσP0
but for the unmeasured disturbances at measured outputs (composed of integrators). -
<keyword arguments>
ofSteadyKalmanFilter
constructor.
Examples
julia> model = LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 0.5);
julia> estim = KalmanFilter(model, i_ym=[2], σR=[1], σP0=[100, 100], σQint_ym=[0.01])
KalmanFilter estimator with a sample time Ts = 0.5 s, LinModel and:
1 manipulated inputs u (0 integrating states)
3 estimated states x̂
1 measured outputs ym (1 integrating states)
1 unmeasured outputs yu
0 measured disturbances d
KalmanFilter(model, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂)
Construct the estimator from the augmented covariance matrices P̂0
, Q̂
and R̂
.
This syntax allows nonzero off-diagonal elements in .
Luenberger
#
ModelPredictiveControl.Luenberger
— Type
Luenberger(
model::LinModel;
i_ym = 1:model.ny,
nint_u = 0,
nint_ym = default_nint(model, i_ym),
p̂ = 1e-3*(1:(model.nx + sum(nint_u) + sum(nint_ym))) .+ 0.5
)
Construct a Luenberger observer with the LinModel
model
.
i_ym
provides the model
output indices that are measured , the rest are unmeasured . model
matrices are augmented with the stochastic model, which is specified by the numbers of integrator nint_u
and nint_ym
(see SteadyKalmanFilter
Extended Help). The argument p̂
is a vector of model.nx + sum(nint_u) + sum(nint_ym)
elements specifying the observer poles/eigenvalues (near by default). The method computes the observer gain K̂
with place
.
Examples
julia> model = LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 0.5);
julia> estim = Luenberger(model, nint_ym=[1, 1], p̂=[0.61, 0.62, 0.63, 0.64])
Luenberger estimator with a sample time Ts = 0.5 s, LinModel and:
1 manipulated inputs u (0 integrating states)
4 estimated states x̂
2 measured outputs ym (2 integrating states)
0 unmeasured outputs yu
0 measured disturbances d
UnscentedKalmanFilter
#
ModelPredictiveControl.UnscentedKalmanFilter
— Type
UnscentedKalmanFilter(model::SimModel; <keyword arguments>)
Construct an unscented Kalman Filter with the SimModel
model
.
Both LinModel
and NonLinModel
are supported. The unscented Kalman filter is based on the process model :
See SteadyKalmanFilter
for details on noises and covariances. The functions are model
state-space functions augmented with the stochastic model, which is specified by the numbers of integrator nint_u
and nint_ym
(see Extended Help). The function represents the measured outputs of function (and unmeasured ones, for ).
Arguments
-
model::SimModel
: (deterministic) model for the estimations. -
α=1e-3
: alpha parameter, spread of the state distribution . -
β=2
: beta parameter, skewness and kurtosis of the states distribution . -
κ=0
: kappa parameter, another spread parameter . -
<keyword arguments>
ofSteadyKalmanFilter
constructor. -
<keyword arguments>
ofKalmanFilter
constructor.
Examples
julia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1);
julia> estim = UnscentedKalmanFilter(model, σR=[1], nint_ym=[2], σP0int_ym=[1, 1])
UnscentedKalmanFilter estimator with a sample time Ts = 10.0 s, NonLinModel and:
1 manipulated inputs u (0 integrating states)
3 estimated states x̂
1 measured outputs ym (2 integrating states)
0 unmeasured outputs yu
0 measured disturbances d
Extended Help
The Extended Help of SteadyKalmanFilter
details the augmentation with nint_ym
and nint_u
arguments. Note that the constructor does not validate the observability of the resulting augmented NonLinModel
. In such cases, it is the user’s responsibility to ensure that the augmented model is still observable.
UnscentedKalmanFilter(model, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂, α, β, κ)
Construct the estimator from the augmented covariance matrices P̂0
, Q̂
and R̂
.
This syntax allows nonzero off-diagonal elements in .
ExtendedKalmanFilter
#
ModelPredictiveControl.ExtendedKalmanFilter
— Type
ExtendedKalmanFilter(model::SimModel; <keyword arguments>)
Construct an extended Kalman Filter with the SimModel
model
.
Both LinModel
and NonLinModel
are supported. The process model is identical to UnscentedKalmanFilter
. The Jacobians of the augmented model are computed with ForwardDiff.jl
automatic differentiation.
See the Extended Help of |
Arguments
-
model::SimModel
: (deterministic) model for the estimations. -
<keyword arguments>
ofSteadyKalmanFilter
constructor. -
<keyword arguments>
ofKalmanFilter
constructor.
Examples
julia> model = NonLinModel((x,u,_)->0.2x+u, (x,_)->-3x, 5.0, 1, 1, 1);
julia> estim = ExtendedKalmanFilter(model, σQ=[2], σQint_ym=[2], σP0=[0.1], σP0int_ym=[0.1])
ExtendedKalmanFilter estimator with a sample time Ts = 5.0 s, NonLinModel and:
1 manipulated inputs u (0 integrating states)
2 estimated states x̂
1 measured outputs ym (1 integrating states)
0 unmeasured outputs yu
0 measured disturbances d
ExtendedKalmanFilter(model, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂)
Construct the estimator from the augmented covariance matrices P̂0
, Q̂
and R̂
.
This syntax allows nonzero off-diagonal elements in .
MovingHorizonEstimator
#
ModelPredictiveControl.MovingHorizonEstimator
— Type
MovingHorizonEstimator(model::SimModel; <keyword arguments>)
Construct a moving horizon estimator (MHE) based on model
(LinModel
or NonLinModel
).
It can handle constraints on the estimates, see setconstraint!
. Additionally, model
is not linearized like the ExtendedKalmanFilter
, and the probability distribution is not approximated like the UnscentedKalmanFilter
. The computational costs are drastically higher, however, since it minimizes the following objective function at each discrete time :
in which the arrival costs are evaluated from the states estimated at time :
and the covariances are repeated times:
The estimation horizon limits the window length:
The vectors and encompass the estimated process noise and sensor noise from to . The Extended Help defines the two vectors and the scalar . See UnscentedKalmanFilter
for details on he augmented process model and covariances. The matrix is estimated with an ExtendedKalmanFilter
.
See the Extended Help if you get an error like: |
Arguments
-
model::SimModel
: (deterministic) model for the estimations. -
He=nothing
: estimation horizon , must be specified. -
Cwt=Inf
: slack variable weight , default toInf
meaning hard constraints only. -
optim=default_optim_mhe(model)
: aJuMP.Model
with a quadratic/nonlinear optimizer for solving (default toIpopt
, orOSQP
ifmodel
is aLinModel
). -
<keyword arguments>
ofSteadyKalmanFilter
constructor. -
<keyword arguments>
ofKalmanFilter
constructor.
Examples
julia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1);
julia> estim = MovingHorizonEstimator(model, He=5, σR=[1], σP0=[0.01])
MovingHorizonEstimator estimator with a sample time Ts = 10.0 s, Ipopt optimizer, NonLinModel and:
5 estimation steps He
1 manipulated inputs u (0 integrating states)
2 estimated states x̂
1 measured outputs ym (1 integrating states)
0 unmeasured outputs yu
0 measured disturbances d
Extended Help
The estimated process and sensor noises are defined as:
based on the augmented model functions
The slack variable setconstraint!
. It is disabled by default for the MHE (from Cwt=Inf
) but it should be activated for problems with two or more types of bounds, to ensure feasibility (e.g. on the estimated state and sensor noise).
For LinModel
, the optimization is treated as a quadratic program with a time-varying Hessian, which is generally cheaper than nonlinear programming.
For NonLinModel
, the optimization relies on automatic differentiation (AD). Optimizers generally benefit from exact derivatives like AD. However, the f
and h
functions must be compatible with this feature. See Automatic differentiation for common mistakes when writing these functions.
Note that if Cwt≠Inf
, the attribute nlp_scaling_max_gradient
of Ipopt
is set to 10/Cwt
(if not already set), to scale the small values of
MovingHorizonEstimator(model, He, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂, Cwt, optim)
Construct the estimator from the augmented covariance matrices P̂0
, Q̂
and R̂
.
This syntax allows nonzero off-diagonal elements in
InternalModel
#
ModelPredictiveControl.InternalModel
— Type
InternalModel(model::SimModel; i_ym=1:model.ny, stoch_ym=ss(I,I,I,I,model.Ts))
Construct an internal model estimator based on model
(LinModel
or NonLinModel
).
i_ym
provides the model
output indices that are measured model
evaluates the deterministic predictions stoch_ym
, the stochastic predictions of the measured outputs
|
Examples
julia> estim = InternalModel(LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 0.5), i_ym=[2])
InternalModel estimator with a sample time Ts = 0.5 s, LinModel and:
1 manipulated inputs u
2 estimated states x̂
1 measured outputs ym
1 unmeasured outputs yu
0 measured disturbances d
Extended Help
stoch_ym
is a TransferFunction
or StateSpace
object that models disturbances on stoch_ym
supposes 1 integrator per measured outputs by default, assuming that the current stochastic estimate stoch_ym
can mitigate this.
Default Model Augmentation
#
ModelPredictiveControl.default_nint
— Function
default_nint(model::LinModel, i_ym=1:model.ny, nint_u=0) -> nint_ym
Get default integrator quantity per measured outputs nint_ym
for LinModel
.
The arguments i_ym
and nint_u
are the measured output indices and the integrator quantity on each manipulated input, respectively. By default, one integrator is added on each measured outputs. If model
(see Examples).
Examples
julia> model = LinModel(append(tf(3, [10, 1]), tf(2, [1, 0]), tf(4,[-5, 1])), 1.0);
julia> nint_ym = default_nint(model)
3-element Vector{Int64}:
1
0
1
default_nint(model::SimModel, i_ym=1:model.ny, nint_u=0)
One integrator on each measured output by default if model
is not a LinModel
.
If the integrator quantity per manipulated input nint_u ≠ 0
, the method returns zero integrator on each measured output.