Functions: Generic Functions

This page contains the documentation of functions that are generic to SimModel, StateEstimator and PredictiveController types.

Set Constraint

ModelPredictiveControl.setconstraint!Function
setconstraint!(estim::MovingHorizonEstimator; <keyword arguments>) -> estim

Set the constraint parameters of the MovingHorizonEstimator estim.

It supports both soft and hard constraints on the estimated state $\mathbf{x̂}$, process noise $\mathbf{ŵ}$ and sensor noise $\mathbf{v̂}$:

\[\begin{alignat*}{3} \mathbf{x̂_{min} - c_{x̂_{min}}} ϵ ≤&&\ \mathbf{x̂}_k(k-j+p) &≤ \mathbf{x̂_{max} + c_{x̂_{max}}} ϵ &&\qquad j = N_k, N_k - 1, ... , 0 \\ \mathbf{ŵ_{min} - c_{ŵ_{min}}} ϵ ≤&&\ \mathbf{ŵ}(k-j+p) &≤ \mathbf{ŵ_{max} + c_{ŵ_{max}}} ϵ &&\qquad j = N_k, N_k - 1, ... , 1 \\ \mathbf{v̂_{min} - c_{v̂_{min}}} ϵ ≤&&\ \mathbf{v̂}(k-j+1) &≤ \mathbf{v̂_{max} + c_{v̂_{max}}} ϵ &&\qquad j = N_k, N_k - 1, ... , 1 \end{alignat*}\]

and also $ϵ ≥ 0$. All the constraint parameters are vector. Use ±Inf values when there is no bound. The constraint softness parameters $\mathbf{c}$, also called equal concern for relaxation, are non-negative values that specify the softness of the associated bound. Use 0.0 values for hard constraints (default for all of them). Notice that constraining the estimated sensor noises is equivalent to bounding the innovation term, since $\mathbf{v̂}(k) = \mathbf{y^m}(k) - \mathbf{ŷ^m}(k)$. See Extended Help for details on the constant $p$, on model augmentation and on time-varying constraints.

Arguments

Info

All the keyword arguments have non-Unicode alternatives e.g. xhatmin or Vhatmax.

The default constraints are mentioned here for clarity but omitting a keyword argument will not re-assign to its default value (defaults are set at construction only).

  • estim::MovingHorizonEstimator : moving horizon estimator to set constraints
  • x̂min=fill(-Inf,nx̂) / x̂max=fill(+Inf,nx̂) : estimated state bound $\mathbf{x̂_{min/max}}$
  • ŵmin=fill(-Inf,nx̂) / ŵmax=fill(+Inf,nx̂) : estimated process noise bound $\mathbf{ŵ_{min/max}}$
  • v̂min=fill(-Inf,nym) / v̂max=fill(+Inf,nym) : estimated sensor noise bound $\mathbf{v̂_{min/max}}$
  • c_x̂min=fill(0.0,nx̂) / c_x̂max=fill(0.0,nx̂) : x̂min / x̂max softness weight $\mathbf{c_{x̂_{min/max}}}$
  • c_ŵmin=fill(0.0,nx̂) / c_ŵmax=fill(0.0,nx̂) : ŵmin / ŵmax softness weight $\mathbf{c_{ŵ_{min/max}}}$
  • c_v̂min=fill(0.0,nym) / c_v̂max=fill(0.0,nym) : v̂min / v̂max softness weight $\mathbf{c_{v̂_{min/max}}}$
  • all the keyword arguments above but with a first capital letter, e.g. X̂max or C_ŵmax: for time-varying constraints (see Extended Help)

Examples

julia> estim = MovingHorizonEstimator(LinModel(ss(0.5,1,1,0,1)), He=3);

julia> estim = setconstraint!(estim, x̂min=[-50, -50], x̂max=[50, 50])
MovingHorizonEstimator estimator with a sample time Ts = 1.0 s, OSQP optimizer, LinModel and:
 3 estimation steps He
 0 slack variable ϵ (estimation constraints)
 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

Extended Help

The constant $p=0$ if estim.direct==true (current form), else $p=1$ (prediction form). Note that the state $\mathbf{x̂}$ and process noise $\mathbf{ŵ}$ constraints are applied on the augmented model, detailed in SteadyKalmanFilter Extended Help. For variable constraints, the bounds can be modified after calling updatestate!, that is, at runtime, except for ±Inf bounds. Time-varying constraints over the estimation horizon $H_e$ are also possible, mathematically defined as:

\[\begin{alignat*}{3} \mathbf{X̂_{min} - C_{x̂_{min}}} ϵ ≤&&\ \mathbf{X̂} &≤ \mathbf{X̂_{max} + C_{x̂_{max}}} ϵ \\ \mathbf{Ŵ_{min} - C_{ŵ_{min}}} ϵ ≤&&\ \mathbf{Ŵ} &≤ \mathbf{Ŵ_{max} + C_{ŵ_{max}}} ϵ \\ \mathbf{V̂_{min} - C_{v̂_{min}}} ϵ ≤&&\ \mathbf{V̂} &≤ \mathbf{V̂_{max} + C_{v̂_{max}}} ϵ \end{alignat*}\]

For this, use the same keyword arguments as above but with a first capital letter:

  • X̂min / X̂max / C_x̂min / C_x̂max : $\mathbf{X̂}$ constraints (nx̂*(He+1),).
  • Ŵmin / Ŵmax / C_ŵmin / C_ŵmax : $\mathbf{Ŵ}$ constraints (nx̂*He,).
  • V̂min / V̂max / C_v̂min / C_v̂max : $\mathbf{V̂}$ constraints (nym*He,).
source
setconstraint!(mpc::PredictiveController; <keyword arguments>) -> mpc

Set the constraint parameters of the PredictiveController mpc.

The predictive controllers support both soft and hard constraints, defined by:

\[\begin{alignat*}{3} \mathbf{u_{min} - c_{u_{min}}} ϵ ≤&&\ \mathbf{u}(k+j) &≤ \mathbf{u_{max} + c_{u_{max}}} ϵ &&\qquad j = 0, 1 ,..., H_p - 1 \\ \mathbf{Δu_{min} - c_{Δu_{min}}} ϵ ≤&&\ \mathbf{Δu}(k+j) &≤ \mathbf{Δu_{max} + c_{Δu_{max}}} ϵ &&\qquad j = 0, 1 ,..., H_c - 1 \\ \mathbf{y_{min} - c_{y_{min}}} ϵ ≤&&\ \mathbf{ŷ}(k+j) &≤ \mathbf{y_{max} + c_{y_{max}}} ϵ &&\qquad j = 1, 2 ,..., H_p \\ \mathbf{x̂_{min} - c_{x̂_{min}}} ϵ ≤&&\ \mathbf{x̂}_i(k+j) &≤ \mathbf{x̂_{max} + c_{x̂_{max}}} ϵ &&\qquad j = H_p \end{alignat*}\]

and also $ϵ ≥ 0$. The last line is the terminal constraints applied on the states at the end of the horizon (see Extended Help). See MovingHorizonEstimator constraints for details on bounds and softness parameters $\mathbf{c}$. The output and terminal constraints are all soft by default. See Extended Help for time-varying constraints.

Arguments

Info

The keyword arguments Δumin, Δumax, c_Δumin, c_Δumax, x̂min, x̂max, c_x̂min, c_x̂max and their capital letter versions have non-Unicode alternatives e.g. Deltaumin, xhatmax and C_Deltaumin

The default constraints are mentioned here for clarity but omitting a keyword argument will not re-assign to its default value (defaults are set at construction only).

  • mpc::PredictiveController : predictive controller to set constraints
  • umin=fill(-Inf,nu) / umax=fill(+Inf,nu) : manipulated input bound $\mathbf{u_{min/max}}$
  • Δumin=fill(-Inf,nu) / Δumax=fill(+Inf,nu) : manipulated input increment bound $\mathbf{Δu_{min/max}}$
  • ymin=fill(-Inf,ny) / ymax=fill(+Inf,ny) : predicted output bound $\mathbf{y_{min/max}}$
  • x̂min=fill(-Inf,nx̂) / x̂max=fill(+Inf,nx̂) : terminal constraint bound $\mathbf{x̂_{min/max}}$
  • c_umin=fill(0.0,nu) / c_umax=fill(0.0,nu) : umin / umax softness weight $\mathbf{c_{u_{min/max}}}$
  • c_Δumin=fill(0.0,nu) / c_Δumax=fill(0.0,nu) : Δumin / Δumax softness weight $\mathbf{c_{Δu_{min/max}}}$
  • c_ymin=fill(1.0,ny) / c_ymax=fill(1.0,ny) : ymin / ymax softness weight $\mathbf{c_{y_{min/max}}}$
  • c_x̂min=fill(1.0,nx̂) / c_x̂max=fill(1.0,nx̂) : x̂min / x̂max softness weight $\mathbf{c_{x̂_{min/max}}}$
  • all the keyword arguments above but with a first capital letter, except for the terminal constraints, e.g. Ymax or C_Δumin: for time-varying constraints (see Extended Help)

Examples

julia> mpc = LinMPC(setop!(LinModel(tf(3, [30, 1]), 4), uop=[50], yop=[25]));

julia> mpc = setconstraint!(mpc, umin=[0], umax=[100], Δumin=[-10], Δumax=[+10])
LinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, SteadyKalmanFilter estimator and:
 10 prediction steps Hp
  2 control steps Hc
  1 slack variable ϵ (control constraints)
  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

Extended Help

Terminal constraints provide closed-loop stability guarantees on the nominal plant model. They can render an unfeasible problem however. In practice, a sufficiently large prediction horizon $H_p$ without terminal constraints is typically enough for stability. If mpc.estim.direct==true, the estimator computes the states at $i = k$ (the current time step), otherwise at $i = k - 1$. Note that terminal constraints are applied on the augmented state vector $\mathbf{x̂}$ (see SteadyKalmanFilter for details on augmentation).

For variable constraints, the bounds can be modified after calling moveinput!, that is, at runtime, but not the softness parameters $\mathbf{c}$. It is not possible to modify ±Inf bounds at runtime.

Tip

To keep a variable unconstrained while maintaining the ability to add a constraint later at runtime, set the bound to an absolute value sufficiently large when you create the controller (but different than ±Inf).

It is also possible to specify time-varying constraints over $H_p$ and $H_c$ horizons. In such a case, they are defined by:

\[\begin{alignat*}{3} \mathbf{U_{min} - C_{u_{min}}} ϵ ≤&&\ \mathbf{U} &≤ \mathbf{U_{max} + C_{u_{max}}} ϵ \\ \mathbf{ΔU_{min} - C_{Δu_{min}}} ϵ ≤&&\ \mathbf{ΔU} &≤ \mathbf{ΔU_{max} + C_{Δu_{max}}} ϵ \\ \mathbf{Y_{min} - C_{y_{min}}} ϵ ≤&&\ \mathbf{Ŷ} &≤ \mathbf{Y_{max} + C_{y_{max}}} ϵ \end{alignat*}\]

For this, use the same keyword arguments as above but with a first capital letter:

  • Umin / Umax / C_umin / C_umax : $\mathbf{U}$ constraints (nu*Hp,).
  • ΔUmin / ΔUmax / C_Δumin / C_Δumax : $\mathbf{ΔU}$ constraints (nu*Hc,).
  • Ymin / Ymax / C_ymin / C_ymax : $\mathbf{Ŷ}$ constraints (ny*Hp,).
source

Evaluate Output y

ModelPredictiveControl.evaloutputFunction
evaloutput(model::SimModel, d=[]) -> y

Evaluate SimModel outputs y from model.x0 states and measured disturbances d.

It returns model output at the current time step $\mathbf{y}(k)$. Calling a SimModel object calls this evaloutput method.

Examples

julia> model = setop!(LinModel(tf(2, [10, 1]), 5.0), yop=[20]);

julia> y = evaloutput(model)
1-element Vector{Float64}:
 20.0
source
evaloutput(estim::StateEstimator, d=[]) -> ŷ

Evaluate StateEstimator outputs from estim.x̂0 states and disturbances d.

It returns estim output at the current time step $\mathbf{ŷ}(k)$. Calling a StateEstimator object calls this evaloutput method.

Examples

julia> kf = SteadyKalmanFilter(setop!(LinModel(tf(2, [10, 1]), 5), yop=[20]));

julia> ŷ = evaloutput(kf)
1-element Vector{Float64}:
 20.0
source

Change State x

Prepare State x

ModelPredictiveControl.preparestate!Function
preparestate!(model::SimModel, _ , _ ) -> x

Do nothing for SimModel and return the current model state $\mathbf{x}(k)$.

source
preparestate!(estim::StateEstimator, ym, d=estim.model.dop) -> x̂

Prepare estim.x̂0 estimate with meas. outputs ym and dist. d for the current time step.

This function should be called at the beginning of each discrete time step. Its behavior depends if estim is a StateEstimator in the current/filter (1.) or delayed/predictor (2.) formulation:

  1. If estim.direct is true, it removes the operating points with remove_op!, calls correct_estimate!, and returns the corrected state estimate $\mathbf{x̂}_k(k)$.
  2. Else, it does nothing and returns the current best estimate $\mathbf{x̂}_{k-1}(k)$.

Examples

julia> estim2 = SteadyKalmanFilter(LinModel(ss(0.1, 0.5, 1, 0, 4)), nint_ym=0, direct=true);

julia> x̂ = round.(preparestate!(estim2, [1]), digits=3)
1-element Vector{Float64}:
 0.01

julia> estim1 = SteadyKalmanFilter(LinModel(ss(0.1, 0.5, 1, 0, 4)), nint_ym=0, direct=false);

julia> x̂ = preparestate!(estim1, [1])
1-element Vector{Float64}:
 0.0
source
preparestate!(mpc::PredictiveController, ym, d=[]) -> x̂

Call preparestate! on mpc.estim StateEstimator.

source

Update State x

ModelPredictiveControl.updatestate!Function
updatestate!(model::SimModel, u, d=[]) -> xnext

Update model.x0 states with current inputs u and measured disturbances d.

The method computes and returns the model state for the next time step $\mathbf{x}(k+1)$.

Examples

julia> model = LinModel(ss(1.0, 1.0, 1.0, 0, 1.0));

julia> x = updatestate!(model, [1])
1-element Vector{Float64}:
 1.0
source
updatestate!(estim::StateEstimator, u, ym, d=[]) -> x̂next

Update estim.x̂0 estimate with current inputs u, measured outputs ym and dist. d.

This function should be called at the end of each discrete time step. It removes the operating points with remove_op!, calls update_estimate! and returns the state estimate for the next time step $\mathbf{x̂}_k(k+1)$. The method preparestate! should be called prior to this one to correct the estimate when applicable (if estim.direct == true). Note that the MovingHorizonEstimator with the default direct=true option is not able to estimate $\mathbf{x̂}_k(k+1)$, the returned value is therefore the current corrected state $\mathbf{x̂}_k(k)$.

Examples

julia> kf = SteadyKalmanFilter(LinModel(ss(0.1, 0.5, 1, 0, 4.0))); u = [1]; ym = [0];

julia> preparestate!(kf, ym);

julia> x̂ = updatestate!(kf, u, ym) # x̂[2] is the integrator state (nint_ym argument)
2-element Vector{Float64}:
 0.5
 0.0
source
updatestate!(mpc::PredictiveController, u, ym, d=[]) -> x̂next

Call updatestate! on mpc.estim StateEstimator.

source

Init State x

ModelPredictiveControl.initstate!Function
initstate!(model::SimModel, u, d=[]) -> x

Init model.x0 with manipulated inputs u and measured disturbances d steady-state.

The method tries to initialize the model state $\mathbf{x}$ at steady-state. It removes the operating points on u and d and calls steadystate!:

  • If model is a LinModel, the method computes the steady-state of current inputs u and measured disturbances d.
  • Else, model.x0 is left unchanged. Use setstate! to manually modify it.

Examples

julia> model = LinModel(tf(6, [10, 1]), 2.0);

julia> u = [1]; x = initstate!(model, u); y = round.(evaloutput(model), digits=3)
1-element Vector{Float64}:
 6.0
 
julia> x ≈ updatestate!(model, u)
true
source
initstate!(estim::StateEstimator, u, ym, d=[]) -> x̂

Init estim.x̂0 states from current inputs u, measured outputs ym and disturbances d.

The method tries to find a good steady-state for the initial estimate $\mathbf{x̂}$. It removes the operating points with remove_op! and call init_estimate!:

  • If estim.model is a LinModel, it finds the steady-state of the augmented model using u and d arguments, and uses the ym argument to enforce that $\mathbf{ŷ^m}(0) = \mathbf{y^m}(0)$. For control applications, this solution produces a bumpless manual to automatic transfer. See init_estimate! for details.
  • Else, estim.x̂0 is left unchanged. Use setstate! to manually modify it.

If applicable, it also sets the error covariance estim.P̂ to estim.P̂_0.

Examples

julia> estim = SteadyKalmanFilter(LinModel(tf(3, [10, 1]), 0.5), nint_ym=[2]);

julia> u = [1]; y = [3 - 0.1]; x̂ = round.(initstate!(estim, u, y), digits=3)
3-element Vector{Float64}:
  5.0
  0.0
 -0.1

julia> preparestate!(estim, y); 

julia> x̂ ≈ updatestate!(estim, u, y)
true

julia> evaloutput(estim) ≈ y
true
source
initstate!(mpc::PredictiveController, u, ym, d=[]) -> x̂

Init the states of mpc.estim StateEstimator and warm start mpc.ΔŨ at zero.

source

Set State x

ModelPredictiveControl.setstate!Function
setstate!(model::SimModel, x) -> model

Set model.x0 to x - model.xop from the argument x.

source
setstate!(estim::StateEstimator, x̂) -> estim

Set estim.x̂0 to x̂ - estim.x̂op from the argument .

source
setstate!(mpc::PredictiveController, x̂) -> mpc

Set mpc.estim.x̂0 to x̂ - estim.x̂op from the argument .

source

Set Model and Weights

ModelPredictiveControl.setmodel!Function
setmodel!(estim::StateEstimator, model=estim.model; <keyword arguments>) -> estim

Set model and covariance matrices of estim StateEstimator.

Allows model adaptation of estimators based on LinModel at runtime. Modification of NonLinModel state-space functions is not supported. New covariance matrices can be specified with the keyword arguments (see SteadyKalmanFilter documentation for the nomenclature). Not supported by Luenberger and SteadyKalmanFilter, use the time-varying KalmanFilter instead. The MovingHorizonEstimator model is kept constant over the estimation horizon $H_e$. The matrix dimensions and sample time must stay the same. Note that the observability and controllability of the new augmented model is not verified (see Extended Help for more info).

Arguments

Info

Keyword arguments with emphasis are non-Unicode alternatives.

  • estim::StateEstimator : estimator to set model and covariances.
  • model=estim.model : new plant model (not supported by NonLinModel).
  • Q̂=nothing or Qhat : new augmented model $\mathbf{Q̂}$ covariance matrix.
  • R̂=nothing or Rhat : new augmented model $\mathbf{R̂}$ covariance matrix.

Examples

julia> kf = KalmanFilter(LinModel(ss(0.1, 0.5, 1, 0, 4.0)), σQ=[√4.0], σQint_ym=[√0.25]);

julia> kf.model.A[], kf.Q̂[1, 1], kf.Q̂[2, 2] 
(0.1, 4.0, 0.25)

julia> setmodel!(kf, LinModel(ss(0.42, 0.5, 1, 0, 4.0)), Q̂=[1 0;0 0.5]);

julia> kf.model.A[], kf.Q̂[1, 1], kf.Q̂[2, 2] 
(0.42, 1.0, 0.5)

Extended Help

Extended Help

Using the default model augmentation computed by the default_nint method, switching from a non-integrating plant model to an integrating one will produce an augmented model that is not observable. Moving the unmeasured disturbances at the model input (nint_u parameter) can fix this issue.

source
setmodel!(mpc::PredictiveController, model=mpc.estim.model; <keyword arguments>) -> mpc

Set model and objective function weights of mpc PredictiveController.

Allows model adaptation of controllers based on LinModel at runtime. Modification of NonLinModel state-space functions is not supported. New weight matrices in the objective function can be specified with the keyword arguments (see LinMPC for the nomenclature). If Cwt ≠ Inf, the augmented move suppression weight is $\mathbf{Ñ}_{H_c} = \mathrm{diag}(\mathbf{N}_{H_c}, C)$, else $\mathbf{Ñ}_{H_c} = \mathbf{N}_{H_c}$. The StateEstimator mpc.estim cannot be a Luenberger observer or a SteadyKalmanFilter (the default estimator). Construct the mpc object with a time-varying KalmanFilter instead. Note that the model is constant over the prediction horizon $H_p$.

Arguments

Info

Keyword arguments with emphasis are non-Unicode alternatives.

  • mpc::PredictiveController : controller to set model and weights.
  • model=mpc.estim.model : new plant model (not supported by NonLinModel).
  • Mwt=nothing : new main diagonal in $\mathbf{M}$ weight matrix (vector).
  • Nwt=nothing : new main diagonal in $\mathbf{N}$ weight matrix (vector).
  • Lwt=nothing : new main diagonal in $\mathbf{L}$ weight matrix (vector).
  • M_Hp=nothing : new $\mathbf{M}_{H_p}$ weight matrix.
  • Ñ_Hc=nothing or Ntilde_Hc : new $\mathbf{Ñ}_{H_c}$ weight matrix (see def. above).
  • L_Hp=nothing : new $\mathbf{L}_{H_p}$ weight matrix.
  • additional keyword arguments are passed to setmodel!(mpc.estim).

Examples

julia> mpc = LinMPC(KalmanFilter(LinModel(ss(0.1, 0.5, 1, 0, 4.0)), σR=[√25]), Hp=1, Hc=1);

julia> mpc.estim.model.A[1], mpc.estim.R̂[1], mpc.M_Hp[1], mpc.Ñ_Hc[1]
(0.1, 25.0, 1.0, 0.1)

julia> setmodel!(mpc, LinModel(ss(0.42, 0.5, 1, 0, 4.0)); R̂=[9], M_Hp=[10], Nwt=[0.666]);

julia> mpc.estim.model.A[1], mpc.estim.R̂[1], mpc.M_Hp[1], mpc.Ñ_Hc[1]
(0.42, 9.0, 10.0, 0.666)
source

Get Additional Information

ModelPredictiveControl.getinfoFunction
getinfo(estim::MovingHorizonEstimator) -> info

Get additional info on estim MovingHorizonEstimator optimum for troubleshooting.

If estim.direct==true, the function should be called after calling preparestate! Otherwise, call it after updatestate!. It returns the dictionary info with the following fields:

Info

Fields with emphasis are non-Unicode alternatives.

  • :Ŵ or :What : optimal estimated process noise over $N_k$, $\mathbf{Ŵ}$
  • or :epsilon : optimal slack variable, $ϵ$
  • :X̂ or :Xhat : optimal estimated states over $N_k+1$, $\mathbf{X̂}$
  • :x̂ or :xhat : optimal estimated state for the next time step, $\mathbf{x̂}_k(k+1)$
  • :V̂ or :Vhat : optimal estimated sensor noise over $N_k$, $\mathbf{V̂}$
  • :P̄ or :Pbar : estimation error covariance at arrival, $\mathbf{P̄}$
  • :x̄ or :xbar : optimal estimation error at arrival, $\mathbf{x̄}$
  • :Ŷ or :Yhat : optimal estimated outputs over $N_k$, $\mathbf{Ŷ}$
  • :Ŷm or :Yhatm : optimal estimated measured outputs over $N_k$, $\mathbf{Ŷ^m}$
  • :x̂arr or :xhatarr : optimal estimated state at arrival, $\mathbf{x̂}_k(k-N_k+p)$
  • :J : objective value optimum, $J$
  • :Ym : measured outputs over $N_k$, $\mathbf{Y^m}$
  • :U : manipulated inputs over $N_k$, $\mathbf{U}$
  • :D : measured disturbances over $N_k$, $\mathbf{D}$
  • :sol : solution summary of the optimizer for printing

Examples

julia> model = LinModel(ss(1.0, 1.0, 1.0, 0, 5.0));

julia> estim = MovingHorizonEstimator(model, He=1, nint_ym=0, direct=false);

julia> updatestate!(estim, [0], [1]);

julia> round.(getinfo(estim)[:Ŷ], digits=3)
1-element Vector{Float64}:
 0.5
source
getinfo(mpc::PredictiveController) -> info

Get additional info about mpc PredictiveController optimum for troubleshooting.

The function should be called after calling moveinput!. It returns the dictionary info with the following fields:

Info

Fields with emphasis are non-Unicode alternatives.

  • :ΔU or :DeltaU : optimal manipulated input increments over $H_c$, $\mathbf{ΔU}$
  • or :epsilon : optimal slack variable, $ϵ$
  • :D̂ or :Dhat : predicted measured disturbances over $H_p$, $\mathbf{D̂}$
  • :ŷ or :yhat : current estimated output, $\mathbf{ŷ}(k)$
  • :Ŷ or :Yhat : optimal predicted outputs over $H_p$, $\mathbf{Ŷ}$
  • :Ŷs or :Yhats : predicted stochastic output over $H_p$ of InternalModel, $\mathbf{Ŷ_s}$
  • :R̂y or :Rhaty : predicted output setpoint over $H_p$, $\mathbf{R̂_y}$
  • :R̂u or :Rhatu : predicted manipulated input setpoint over $H_p$, $\mathbf{R̂_u}$
  • :x̂end or :xhatend : optimal terminal states, $\mathbf{x̂}_{k-1}(k+H_p)$
  • :J : objective value optimum, $J$
  • :U : optimal manipulated inputs over $H_p$, $\mathbf{U}$
  • :u : current optimal manipulated input, $\mathbf{u}(k)$
  • :d : current measured disturbance, $\mathbf{d}(k)$

For LinMPC and NonLinMPC, the field :sol also contains the optimizer solution summary that can be printed. Lastly, the optimal economic cost :JE is also available for NonLinMPC.

Examples

julia> mpc = LinMPC(LinModel(tf(5, [2, 1]), 3), Nwt=[0], Hp=1, Hc=1);

julia> u = moveinput!(mpc, [10]);

julia> round.(getinfo(mpc)[:Ŷ], digits=3)
1-element Vector{Float64}:
 10.0
source

Real-Time Simulate and Control

Disclaimer

These utilities are for soft real-time applications. They are not suitable for hard real-time environnement like safety-critical processes.

Save current time t

ModelPredictiveControl.savetime!Function
savetime!(model::SimModel) -> t

Set model.t to time() and return the value.

Used in conjunction with periodsleep for simple soft real-time simulations. Call this function before any other in the simulation loop.

source
savetime!(estim::StateEstimator) -> t

Call savetime!(estim.model) and return the time t.

source
savetime!(mpc::PredictiveController) -> t

Call savetime!(mpc.estim.model) and return the time t.

source

Period Sleep

ModelPredictiveControl.periodsleepFunction
periodsleep(model::SimModel, busywait=false) -> nothing

Sleep for model.Ts s minus the time elapsed since the last call to savetime!.

It calls sleep if busywait is false. Else, a simple while loop implements busy-waiting. As a rule-of-thumb, busy-waiting should be used if model.Ts < 0.1 s, since the accuracy of sleep is around 1 ms. Can be used to implement simple soft real-time simulations, see the example below.

Warning

The allocations in Julia are garbage-collected (GC) automatically. This can affect the timing. In such cases, you can temporarily stop the GC with GC.enable(false), and restart it at a convenient time e.g.: just before calling periodsleep.

Examples

julia> model = LinModel(tf(2, [0.3, 1]), 0.1);

julia> function sim_realtime!(model)
           t_0 = time()
           for i=1:3
               t = savetime!(model)      # first function called
               println(round(t - t_0, digits=3))
               updatestate!(model, [1])
               periodsleep(model, true)  # last function called
           end
       end;

julia> sim_realtime!(model)
0.0
0.1
0.2
source
periodsleep(estim::StateEstimator) -> nothing

Call periodsleep(estim.model).

source
periodsleep(mpc::PredictiveController) -> nothing

Call periodsleep(mpc.estim.model).

source