Functions: Generic Functions
This page contains the documentation of functions that are generic to SimModel, StateEstimator and PredictiveController types.
Set Constraint
ModelPredictiveControl.setconstraint! — Functionsetconstraint!(estim::MovingHorizonEstimator; <keyword arguments>) -> estimSet 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+1) &≤ \mathbf{x̂_{max} + c_{x̂_{max}}} ϵ &&\qquad j = N_k, N_k - 1, ... , 0 \\ \mathbf{ŵ_{min} - c_{ŵ_{min}}} ϵ ≤&&\ \mathbf{ŵ}(k-j+1) &≤ \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 model augmentation and time-varying constraints.
Arguments
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). The same applies for PredictiveController.
estim::MovingHorizonEstimator: moving horizon estimator to set constraintsx̂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̂maxsoftness weight $\mathbf{c_{x̂_{min/max}}}$c_ŵmin=fill(0.0,nx̂)/c_ŵmax=fill(0.0,nx̂):ŵmin/ŵmaxsoftness weight $\mathbf{c_{ŵ_{min/max}}}$c_v̂min=fill(0.0,nym)/c_v̂max=fill(0.0,nym):v̂min/v̂maxsoftness weight $\mathbf{c_{v̂_{min/max}}}$- all the keyword arguments above but with a first capital letter, e.g.
X̂maxorC_ŵ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 dExtended Help
Extended Help
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,).
setconstraint!(mpc::PredictiveController; <keyword arguments>) -> mpcSet 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̂}_{k-1}(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
mpc::PredictiveController: predictive controller to set constraintsumin=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/umaxsoftness weight $\mathbf{c_{u_{min/max}}}$c_Δumin=fill(0.0,nu)/c_Δumax=fill(0.0,nu):Δumin/Δumaxsoftness weight $\mathbf{c_{Δu_{min/max}}}$c_ymin=fill(1.0,ny)/c_ymax=fill(1.0,ny):ymin/ymaxsoftness weight $\mathbf{c_{y_{min/max}}}$c_x̂min=fill(1.0,nx̂)/c_x̂max=fill(1.0,nx̂):x̂min/x̂maxsoftness weight $\mathbf{c_{x̂_{min/max}}}$- all the keyword arguments above but with a first capital letter, except for the terminal constraints, e.g.
YmaxorC_Δ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 dExtended 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. 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.
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,).
Evaluate Output y
ModelPredictiveControl.evaloutput — Functionevaloutput(model::SimModel, d=[]) -> yEvaluate SimModel outputs y from model.x0 states and measured disturbances d.
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.0evaloutput(estim::StateEstimator, d=[]) -> ŷEvaluate StateEstimator outputs ŷ from estim.x̂0 states and disturbances d.
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.0Update State x
ModelPredictiveControl.updatestate! — Functionupdatestate!(model::SimModel, u, d=[]) -> xUpdate model.x0 states with current inputs u and measured disturbances d.
Examples
julia> model = LinModel(ss(1.0, 1.0, 1.0, 0, 1.0));
julia> x = updatestate!(model, [1])
1-element Vector{Float64}:
1.0updatestate!(estim::StateEstimator, u, ym, d=[]) -> x̂Update estim.x̂0 estimate with current inputs u, measured outputs ym and dist. d.
The method removes the operating points with remove_op! and call update_estimate!.
Examples
julia> kf = SteadyKalmanFilter(LinModel(ss(0.1, 0.5, 1, 0, 4.0)));
julia> x̂ = updatestate!(kf, [1], [0]) # x̂[2] is the integrator state (nint_ym argument)
2-element Vector{Float64}:
0.5
0.0updatestate!(mpc::PredictiveController, u, ym, d=[]) -> x̂Call updatestate! on mpc.estim StateEstimator.
Init State x
ModelPredictiveControl.initstate! — Functioninitstate!(model::SimModel, u, d=[]) -> xInit model.x0 with manipulated inputs u and measured disturbances d steady-state.
It removes the operating points on u and d and calls steadystate!:
- If
modelis aLinModel, the method computes the steady-state of current inputsuand measured disturbancesd. - Else,
model.x0is left unchanged. Usesetstate!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)
trueinitstate!(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̂}(0)$. It removes the operating points with remove_op! and call init_estimate!:
- If
estim.modelis aLinModel, it finds the steady-state of the augmented model usinguanddarguments, and uses theymargument to enforce that $\mathbf{ŷ^m}(0) = \mathbf{y^m}(0)$. For control applications, this solution produces a bumpless manual to automatic transfer. Seeinit_estimate!for details. - Else,
estim.x̂0is left unchanged. Usesetstate!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> x̂ ≈ updatestate!(estim, u, y)
true
julia> evaloutput(estim) ≈ y
trueinitstate!(mpc::PredictiveController, u, ym, d=[]) -> x̂Init the states of mpc.estim StateEstimator and warm start mpc.ΔŨ at zero.
Set State x
ModelPredictiveControl.setstate! — Functionsetstate!(model::SimModel, x) -> modelSet model.x0 to x - model.xop from the argument x.
setstate!(estim::StateEstimator, x̂) -> estimSet estim.x̂0 to x̂ - estim.x̂op from the argument x̂.
setstate!(mpc::PredictiveController, x̂) -> mpcSet the estimate at mpc.estim.x̂.
Set Plant Model
ModelPredictiveControl.setmodel! — Functionsetmodel!(estim::StateEstimator, model::LinModel) -> estimSet model and operating points of estim StateEstimator to model values.
Allows model adaptation of estimators based on LinModel at runtime (NonLinModel is not supported). Not supported by Luenberger and SteadyKalmanFilter, use the time-varying KalmanFilter instead. 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 details).
Examples
julia> kf = KalmanFilter(LinModel(ss(0.1, 0.5, 1, 0, 4.0)));
julia> kf.model.A
1×1 Matrix{Float64}:
0.1
julia> setmodel!(kf, LinModel(ss(0.42, 0.5, 1, 0, 4.0))); kf.model.A
1×1 Matrix{Float64}:
0.42Extended 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.
setmodel!(mpc::PredictiveController, model::LinModel) -> mpcSet model and operating points of mpc PredictiveController to model values.
Allows model adaptation of controllers based on LinModel at runtime (NonLinModel is not supported). 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$.
Examples
julia> kf = KalmanFilter(LinModel(ss(0.1, 0.5, 1, 0, 4.0)));
julia> mpc = LinMPC(kf); mpc.estim.model.A
1×1 Matrix{Float64}:
0.1
julia> setmodel!(mpc, LinModel(ss(0.42, 0.5, 1, 0, 4.0))); mpc.estim.model.A
1×1 Matrix{Float64}:
0.42Quick Simulation
Simulate
ModelPredictiveControl.sim! — Functionsim!(plant::SimModel, N::Int, u=plant.uop.+1, d=plant.dop; x_0=plant.xop) -> resOpen-loop simulation of plant for N time steps, default to unit bump test on all inputs.
The manipulated inputs $\mathbf{u}$ and measured disturbances $\mathbf{d}$ are held constant at u and d values, respectively. The plant initial state $\mathbf{x}(0)$ is specified by x_0 keyword arguments. The function returns SimResult instances that can be visualized by calling plot from Plots.jl on them (see Examples below). Note that the method mutates plant internal states.
Examples
julia> plant = NonLinModel((x,u,d)->0.1x+u+d, (x,_)->2x, 10.0, 1, 1, 1, 1, solver=nothing);
julia> res = sim!(plant, 15, [0], [0], x_0=[1])
Simulation results of NonLinModel with 15 time steps.
julia> using Plots; plot(res, plotu=false, plotd=false, plotx=true)
sim!(
estim::StateEstimator,
N::Int,
u = estim.model.uop .+ 1,
d = estim.model.dop;
<keyword arguments>
) -> resClosed-loop simulation of estim estimator for N steps, default to input bumps.
See Arguments for the available options. The noises are provided as standard deviations σ vectors. The simulated sensor and process noises of plant are specified by y_noise and x_noise arguments, respectively.
Arguments
estim::StateEstimator: state estimator to simulateN::Int: simulation length in time stepsu = estim.model.uop .+ 1: manipulated input $\mathbf{u}$ valued = estim.model.dop: plant measured disturbance $\mathbf{d}$ valueplant::SimModel = estim.model: simulated plant modelu_step = zeros(plant.nu): step load disturbance on plant inputs $\mathbf{u}$u_noise = zeros(plant.nu): gaussian load disturbance on plant inputs $\mathbf{u}$y_step = zeros(plant.ny): step disturbance on plant outputs $\mathbf{y}$y_noise = zeros(plant.ny): additive gaussian noise on plant outputs $\mathbf{y}$d_step = zeros(plant.nd): step on measured disturbances $\mathbf{d}$d_noise = zeros(plant.nd): additive gaussian noise on measured dist. $\mathbf{d}$x_noise = zeros(plant.nx): additive gaussian noise on plant states $\mathbf{x}$x_0 = plant.xop: plant initial state $\mathbf{x}(0)$x̂_0 = nothing: initial estimate $\mathbf{x̂}(0)$,initstate!is used ifnothinglastu = plant.uop: last plant input $\mathbf{u}$ for $\mathbf{x̂}$ initialization
Examples
julia> model = LinModel(tf(3, [30, 1]), 0.5);
julia> estim = KalmanFilter(model, σR=[0.5], σQ=[0.25], σQint_ym=[0.01], σPint_ym_0=[0.1]);
julia> res = sim!(estim, 50, [0], y_noise=[0.5], x_noise=[0.25], x_0=[-10], x̂_0=[0, 0])
Simulation results of KalmanFilter with 50 time steps.
julia> using Plots; plot(res, plotŷ=true, plotu=false, plotxwithx̂=true)
sim!(
mpc::PredictiveController,
N::Int,
ry = mpc.estim.model.yop .+ 1,
d = mpc.estim.model.dop,
ru = mpc.estim.model.uop;
<keyword arguments>
) -> resClosed-loop simulation of mpc controller for N steps, default to output setpoint bumps.
The output and manipulated input setpoints are held constant at ry and ru, respectively. The keyword arguments are identical to sim!(::StateEstimator, ::Int).
Examples
julia> model = LinModel([tf(3, [30, 1]); tf(2, [5, 1])], 4);
julia> mpc = setconstraint!(LinMPC(model, Mwt=[0, 1], Nwt=[0.01], Hp=30), ymin=[0, -Inf]);
julia> res = sim!(mpc, 25, [0, 0], y_noise=[0.1], y_step=[-10, 0])
Simulation results of LinMPC with 25 time steps.
julia> using Plots; plot(res, plotry=true, plotŷ=true, plotymin=true, plotu=true)
Simulation Results
ModelPredictiveControl.SimResult — TypeSimResult(
obj::Union{SimModel, StateEstimator, PredictiveController},
U_data,
Y_data,
D_data = [];
X_data = nothing,
X̂_data = nothing,
Ry_data = nothing,
Ru_data = nothing,
Ŷ_data = nothing
)Manually construct a SimResult to quickly plot obj simulations.
Except for obj, all the arguments should be matrices of N columns, where N is the number of time steps. SimResult objects allow to quickly plot simulation results. Simply call plot from Plots.jl on them.
Examples
julia> plant = LinModel(tf(1, [1, 1]), 1.0); N = 5; U_data = fill(1.0, 1, N);
julia> Y_data = reduce(hcat, (updatestate!(plant, U_data[:, i]); plant()) for i=1:N)
1×5 Matrix{Float64}:
0.632121 0.864665 0.950213 0.981684 0.993262
julia> res = SimResult(plant, U_data, Y_data)
Simulation results of LinModel with 5 time steps.
julia> using Plots; plot(res)
Get Additional Information
ModelPredictiveControl.getinfo — Functiongetinfo(estim::MovingHorizonEstimator) -> infoGet additional info on estim MovingHorizonEstimator optimum for troubleshooting.
The function should be called after calling updatestate!. It returns the dictionary info with the following fields:
:Ŵ: optimal estimated process noise over $N_k$, $\mathbf{Ŵ}$:x̂arr: optimal estimated state at arrival, $\mathbf{x̂}_k(k-N_k+1)$:ϵ: optimal slack variable, $ϵ$:J: objective value optimum, $J$:X̂: optimal estimated states over $N_k+1$, $\mathbf{X̂}$:x̂: optimal estimated state for the next time step, $\mathbf{x̂}_k(k+1)$:V̂: optimal estimated sensor noise over $N_k$, $\mathbf{V̂}$:P̄: estimation error covariance at arrival, $\mathbf{P̄}$:x̄: optimal estimation error at arrival, $\mathbf{x̄}$:Ŷ: optimal estimated outputs over $N_k$, $\mathbf{Ŷ}$:Ŷm: optimal estimated measured outputs over $N_k$, $\mathbf{Ŷ^m}$: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> estim = MovingHorizonEstimator(LinModel(ss(1.0, 1.0, 1.0, 0, 1)), He=1, nint_ym=0);
julia> updatestate!(estim, [0], [1]);
julia> round.(getinfo(estim)[:Ŷ], digits=3)
1-element Vector{Float64}:
0.5getinfo(mpc::PredictiveController) -> infoGet 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:
:ΔU: optimal manipulated input increments over $H_c$, $\mathbf{ΔU}$:ϵ: optimal slack variable, $ϵ$: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)$:D̂: predicted measured disturbances over $H_p$, $\mathbf{D̂}$:ŷ: current estimated output, $\mathbf{ŷ}(k)$:Ŷ: optimal predicted outputs over $H_p$, $\mathbf{Ŷ}$:x̂end: optimal terminal states, $\mathbf{x̂}_{k-1}(k+H_p)$:Ŷs: predicted stochastic output over $H_p$ ofInternalModel, $\mathbf{Ŷ_s}$:R̂y: predicted output setpoint over $H_p$, $\mathbf{R̂_y}$:R̂u: predicted manipulated input setpoint over $H_p$, $\mathbf{R̂_u}$
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