The objective is to provide a simple and clear framework to quickly design model predictive controllers (MPCs) in Julia, while preserving the flexibility for advanced real-time optimization. Modern MPCs based on closed-loop state estimators are the main focus of the package, but classical approaches that rely on internal models are also possible. The JuMP.jl interface allows the user to test different solvers easily if the performance of the default settings is not satisfactory.
The documentation is divided in two parts:
Manual — This section includes step-by-step guides to design predictive controllers on multiple case studies.
Functions — Documentation of methods and types exported by the package. The "Internals" section provides implementation details of functions that are not exported.
where predicted outputs $\mathbf{Ŷ}$, stochastic outputs $\mathbf{Ŷ_s}$, and measured disturbances $\mathbf{D̂}$ are from $k + 1$ to $k + H_p$. Input increments $\mathbf{ΔU}$ are from $k$ to $k + H_c - 1$. The vector $\mathbf{x̂}_{k-1}(k)$ is the state estimated at the last control period. The stochastic outputs $\mathbf{Ŷ_s = 0}$ if estim is not a InternalModel. Operating points on $\mathbf{u}$, $\mathbf{d}$ and $\mathbf{y}$ are omitted in above equations.
Extended Help
Using the augmented matrices $\mathbf{Â, B̂_u, Ĉ, B̂_d, D̂_d}$ in estim and the equation $\mathbf{W}_j = \mathbf{Ĉ} ( ∑_{i=0}^j \mathbf{Â}^i ) \mathbf{B̂_u}$, the prediction matrices are computed by :
init_quadprog(model::LinModel, Ẽ, S_Hp, M_Hp, N_Hc, L_Hp) -> P̃, q̃, p
Init the quadratic programming optimization matrix P̃ and q̃.
The matrices appear in the quadratic general form :
\[ J = \min_{\mathbf{ΔŨ}} \frac{1}{2}\mathbf{(ΔŨ)'P̃(ΔŨ)} + \mathbf{q̃'(ΔŨ)} + p \]
$\mathbf{P̃}$ is constant if the model and weights are linear and time invariant (LTI). The vector $\mathbf{q̃}$ and scalar $p$ need recalculation each control period $k$ (see initpred! method). $p$ does not impact the minima position. It is thus useless at optimization but required to evaluate the minimal $J$ value.
Current stochastic outputs $\mathbf{ŷ_s}(k)$ comprises the measured outputs $\mathbf{ŷ_s^m}(k) = \mathbf{y^m}(k) - \mathbf{ŷ_d^m}(k)$ and unmeasured $\mathbf{ŷ_s^u}(k) = \mathbf{0}$. See [2].
Augment manipulated inputs constraints with slack variable ϵ for softening.
Denoting the input increments augmented with the slack variable $\mathbf{ΔŨ} = [\begin{smallmatrix} \mathbf{ΔU} \\ ϵ \end{smallmatrix}]$, it returns the augmented conversion matrix $\mathbf{S̃}_{H_p}$, similar to the one described at init_ΔUtoU. It also returns the $\mathbf{A}$ matrices for the inequality constraints:
Augment input increments constraints with slack variable ϵ for softening.
Denoting the input increments augmented with the slack variable $\mathbf{ΔŨ} = [\begin{smallmatrix} \mathbf{ΔU} \\ ϵ \end{smallmatrix}]$, it returns the augmented input increment weights $\mathbf{Ñ}_{H_c}$ (that incorporate $C$). It also returns the augmented constraints $\mathbf{ΔŨ_{min}}$ and $\mathbf{ΔŨ_{max}}$ and the $\mathbf{A}$ matrices for the inequality constraints:
Augment linear output prediction constraints with slack variable ϵ for softening.
Denoting the input increments augmented with the slack variable $\mathbf{ΔŨ} = [\begin{smallmatrix} \mathbf{ΔU} \\ ϵ \end{smallmatrix}]$, it returns the $\mathbf{Ẽ}$ matrix that appears in the linear model prediction equation $\mathbf{Ŷ = Ẽ ΔŨ + F}$, and the $\mathbf{A}$ matrices for the inequality constraints:
1Maciejowski, J. 2000, "Predictive control : with constraints", 1st ed., Prentice Hall, ISBN 978-0201398236.
2Desbiens, A., D. Hodouin & É. Plamondon. 2000, "Global predictive control : a unified control structure for decoupling setpoint tracking, feedforward compensation and disturbance rejection dynamics", IEE Proceedings - Control Theory and Applications, vol. 147, no 4, https://doi.org/10.1049/ip-cta:20000443, p. 465–475, ISSN 1350-2379.
Settings
This document was generated with Documenter.jl version 0.27.25 on Thursday 14 September 2023. Using Julia version 1.9.3.
Init stochastic model matrices from integrator specifications for state estimation.
The arguments nint_u and nint_ym specify how many integrators are added to each manipulated input and measured outputs. The function returns the state-space matrices As, Cs_u and Cs_y of the stochastic model:
where $\mathbf{e}(k)$ is an unknown zero mean white noise and $\mathbf{A_s} = \mathrm{diag}(\mathbf{A_{s_{u}}, A_{s_{ym}}})$. The estimations does not use $\mathbf{B_s}$, it is thus ignored. The function init_integrators builds the state-space matrices.
init_integrators(nint, ny, varname::String) -> A, C, nint
Calc A, C state-space matrices from integrator specifications nint.
This function is used to initialize the stochastic part of the augmented model for the design of state estimators. The vector nint provides how many integrators (in series) should be incorporated for each output. The argument should have ny element, except for nint=0 which is an alias for no integrator at all. The specific case of one integrator per output results in A = I and C = I. The estimation does not use the B matrix, it is thus ignored. This function is called twice :
for the unmeasured disturbances at manipulated inputs $\mathbf{u}$
for the unmeasured disturbances at measured outputs $\mathbf{y^m}$
Augment LinModel state-space matrices with the stochastic ones As and Cs.
If $\mathbf{x}$ are model.x states, and $\mathbf{x_s}$, the states defined at init_integrators, we define an augmented state vector $\mathbf{x̂} = [ \begin{smallmatrix} \mathbf{x} \\ \mathbf{x_s} \end{smallmatrix} ]$. The method returns the augmented matrices Â, B̂u, Ĉ, B̂d and D̂d:
With $n_\mathbf{x̂}$ elements in the state vector $\mathbf{x̂}$ and $n_σ = 2 n_\mathbf{x̂} + 1$ sigma points, the scaling factor applied on standard deviation matrices $\sqrt{\mathbf{P̂}}$ is:
\[ γ = α \sqrt{ n_\mathbf{x̂} + κ }\]
The weight vector $(n_σ × 1)$ for the mean and the weight matrix $(n_σ × n_σ)$ for the covariance are respectively:
where $\mathbf{e}(k)$ is conceptual and unknown zero mean white noise. Its optimal estimation is $\mathbf{ê=0}$, the expected value. Thus, the Âs and B̂s matrices that optimally update the stochastic estimate $\mathbf{x̂_s}$ are:
with current stochastic outputs estimation $\mathbf{ŷ_s}(k)$, composed of the measured $\mathbf{ŷ_s^m}(k) = \mathbf{y^m}(k) - \mathbf{ŷ_d^m}(k)$ and unmeasured $\mathbf{ŷ_s^u = 0}$ outputs. See [1].
All these methods assume that the operating points are already removed in u, ym and d arguments. Strickly speaking, the arguments should be called u0, ym0 and d0, following setop! notation. The 0 is dropped to simplify the notation.
based on the process model described in SteadyKalmanFilter. The notation $\mathbf{x̂}_{k-1}(k)$ refers to the state for the current time $k$ estimated at the last control period $k-1$. See [2] for details.
It implements the unscented Kalman Filter in its predictor (observer) form, based on the generalized unscented transform[3]. See init_ukf for the definition of the constants $\mathbf{m̂, Ŝ}$ and $γ$.
Denoting $\mathbf{x̂}_{k-1}(k)$ as the state for the current time $k$ estimated at the last period $k-1$, $\mathbf{0}$, a null vector, $n_σ = 2 n_\mathbf{x̂} + 1$, the number of sigma points, and $\mathbf{X̂}_{k-1}^j(k)$, the vector at the $j$th column of $\mathbf{X̂}_{k-1}(k)$, the estimator updates the states with:
by using the lower triangular factor of cholesky to compute $\sqrt{\mathbf{P̂}_{k-1}(k)}$ and $\sqrt{\mathbf{P̂}_{k}(k)}$. The matrices $\mathbf{P̂, Q̂, R̂}$ are the covariance of the estimation error, process noise and sensor noise, respectively.
init_estimate!(estim::StateEstimator, model::LinModel, u, ym, d)
Init estim.x̂ estimate with the steady-state solution if model is a LinModel.
Using u, ym and d arguments, the steady-state problem combined to the equality constraint $\mathbf{ŷ^m} = \mathbf{y^m}$ engenders the following system to solve:
1Desbiens, A., D. Hodouin & É. Plamondon. 2000, "Global predictive control : a unified control structure for decoupling setpoint tracking, feedforward compensation and disturbance rejection dynamics", IEE Proceedings - Control Theory and Applications, vol. 147, no 4, https://doi.org/10.1049/ip-cta:20000443, p. 465–475, ISSN 1350-2379.
2Boyd S., "Lecture 8 : The Kalman Filter" (Winter 2008-09) [course slides], EE363: Linear Dynamical Systems, https://web.stanford.edu/class/ee363/lectures/kf.pdf.
3Simon, D. 2006, "Chapter 14: The unscented Kalman filter" in "Optimal State Estimation: Kalman, H∞, and Nonlinear Approaches", John Wiley & Sons, p. 433–459, https://doi.org/10.1002/0470045345.ch14, ISBN9780470045343.
Settings
This document was generated with Documenter.jl version 0.27.25 on Thursday 14 September 2023. Using Julia version 1.9.3.
To install the ModelPredictiveControl package, run this command in the Julia REPL:
using Pkg; Pkg.activate(); Pkg.add("ModelPredictiveControl")
Doing so will install the package to default Julia environnement, that is, accessible anywhere. To facilitate sharing of code and reproducibility of results, it is recommended to install packages in a project environnement. To generate a new project named MPCproject with this package in the current working directory, write this in the REPL:
using Pkg; Pkg.generate("MPCproject"); Pkg.activate("."); Pkg.add("ModelPredictiveControl")
Note that that the construction of linear models typically requires ss or tf functions, it is thus advised to load the package with:
using ModelPredictiveControl, ControlSystemsBase
Settings
This document was generated with Documenter.jl version 0.27.25 on Thursday 14 September 2023. Using Julia version 1.9.3.
The example considers a continuously stirred-tank reactor (CSTR) with a cold and hot water inlet as a plant. The water flows out of an opening at the bottom of the tank. The manipulated inputs are the cold $u_c$ and hot $u_h$ water flow rates, and the measured outputs are the liquid level $y_L$ and temperature $y_T$:
A linear model predictive controller (MPC) will control both the water level $y_L$ and temperature $y_T$ in the tank, at a sampling time of 4 s. The tank level should also never fall below 45:
\[y_L ≥ 45\]
We design our LinMPC controllers by including the linear level constraint with setconstraint! (±Inf values should be used when there is no bound):
LinMPC controller with a sample time Ts = 2.0 s, OSQP optimizer, SteadyKalmanFilter estimator and:
+ 15 prediction steps Hp
+ 2 control steps Hc
+ 2 manipulated inputs u (0 integrators)
+ 4 states x̂
+ 2 measured outputs ym (2 integrators)
+ 0 unmeasured outputs yu
+ 0 measured disturbances d
in which Hp and Hc keyword arguments are respectively the predictive and control horizons, and Mwt and Nwt, the output setpoint tracking and move suppression weights. By default, LinMPC controllers use OSQP to solve the problem, soft constraints on output predictions $\mathbf{ŷ}$ to ensure feasibility, and a SteadyKalmanFilter to estimate the plant states. An attentive reader will also notice that the Kalman filter estimates two additional states compared to the plant model. These are the integrators for the unmeasured plant disturbances, and they are automatically added to the model outputs by default if feasible (see SteadyKalmanFilter for details).
Before closing the loop, we call initstate! with the actual plant inputs and measurements to ensure a bumpless transfer. Since model simulates our plant here, its output will initialize the states. LinModel objects are callable for this purpose (an alias for evaloutput):
u, y = model.uop, model() # or equivalently : y = evaloutput(model)
+initstate!(mpc, u, y)
We can then close the loop and test mpc performance on the simulator by imposing step changes on output setpoints $\mathbf{r_y}$ and on a load disturbance $u_l$:
function test_mpc(mpc, model)
+ N = 200
+ ry, ul = [50, 30], 0
+ u_data = zeros(model.nu, N)
+ y_data = zeros(model.ny, N)
+ ry_data = zeros(model.ny, N)
+ for k = 0:N-1
+ k == 50 && (ry = [50, 35])
+ k == 100 && (ry = [54, 30])
+ k == 150 && (ul = -20)
+ y = model() # simulated measurements
+ u = mpc(ry) # or equivalently : u = moveinput!(mpc, ry)
+ u_data[:,k+1] = u
+ y_data[:,k+1] = y
+ ry_data[:,k+1] = ry
+ updatestate!(mpc, u, y) # update mpc state estimate
+ updatestate!(model, u + [0; ul]) # update simulator with the load disturbance
+ end
+ return u_data, y_data, ry_data
+end
+u_data, y_data, ry_data = test_mpc(mpc, model)
+t_data = Ts*(0:(size(y_data,2)-1))
The LinMPC objects are also callable as an alternative syntax for moveinput!. Calling updatestate! on the mpc object updates its internal state for the NEXT control period (this is by design, see Functions: State Estimators for justifications). That is why the call is done at the end of the for loop. The same logic applies for model.
Lastly, we plot the closed-loop test with the Plots package:
For some situations, when LinMPC matrices are small/medium and dense, DAQP optimizer may be more efficient. To install it, run:
using Pkg; Pkg.add("DAQP")
Also, compared to the default setting, adding the integrating states at the model inputs may improve the closed-loop performance. Load disturbances are indeed very frequent in many real-life control problems. Constructing a LinMPC with DAQP and input integrators:
Suppose that the load disturbance $u_l$ of the last section is in fact caused by a separate hot water pipe that discharges into the tank. Measuring this flow rate allows us to incorporate feedforward compensation in the controller. The new plant model is:
In this example, the goal is to control the angular position $θ$ of a pendulum attached to a motor. Knowing that the manipulated input is the motor torque $τ$, the I/O vectors are:
in which $g$ is the gravitational acceleration, $L$, the pendulum length, $K$, the friction coefficient at the pivot point, and $m$, the mass attached at the end of the pendulum. Here, the explicit Euler method discretizes the system to construct a NonLinModel:
UnscentedKalmanFilter estimator with a sample time Ts = 0.1 s, NonLinModel and:
+ 1 manipulated inputs u (0 integrators)
+ 3 states x̂
+ 1 measured outputs ym (1 integrators)
+ 0 unmeasured outputs yu
+ 0 measured disturbances d
The standard deviation of the angular velocity $ω$ is higher here (σQ second value) since $\dot{ω}(t)$ equation includes an uncertain parameter: the friction coefficient $K$. The estimator tuning is tested on a plant simulated with a different $K$:
The estimate $x̂_3$ is the integrator state that compensates for static errors (nint_ym and σQint_ym parameters of UnscentedKalmanFilter). The Kalman filter performance seems sufficient for control. As the motor torque is limited to -1.5 to 1.5 N m, we incorporate the input constraints in a NonLinMPC:
NonLinMPC controller with a sample time Ts = 0.1 s, Ipopt optimizer, UnscentedKalmanFilter estimator and:
+ 20 prediction steps Hp
+ 4 control steps Hc
+ 1 manipulated inputs u (0 integrators)
+ 3 states x̂
+ 1 measured outputs ym (1 integrators)
+ 0 unmeasured outputs yu
+ 0 measured disturbances d
We test mpc performance on plant by imposing an angular setpoint of 180° (inverted position):
res = sim!(mpc, 60, [180.0], plant=plant, x0=zeros(plant.nx), x̂0=zeros(mpc.estim.nx̂))
+plot(res)
+
+
The controller seems robust enough to variations on $K$ coefficient. Starting from this inverted position, the closed-loop response to a step disturbances of 10° is also satisfactory:
Evaluate InternalModel outputs ŷ from estim.x̂d states and measured outputs ym.
InternalModel estimator needs current measured outputs $\mathbf{y^m}(k)$ to estimate its outputs $\mathbf{ŷ}(k)$, since the strategy imposes that $\mathbf{ŷ^m}(k) = \mathbf{y^m}(k)$ is always true.
initstate!(estim::StateEstimator, u, ym, d=Float64[]) -> x̂
Init estim.x̂ states from current inputs u, measured outputs ym and disturbances d.
The method tries to find a good stead-state for the initial esitmate $\mathbf{x̂}(0)$. 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} = \mathbf{y^m}$. For control applications, this solution produces a bumpless manual to automatic transfer. See init_estimate! for details.
Else, estim.x̂ is left unchanged. Use setstate! to manually modify it.
If applicable, it also sets the error covariance estim.P̂ to $\mathbf{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
+true
sim!(plant::SimModel, N::Int, u=plant.uop.+1, d=plant.dop; x0=zeros(plant.nx)) -> res
Open-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 x0 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.
sim!(
+ estim::StateEstimator,
+ N::Int,
+ u = estim.model.uop .+ 1,
+ d = estim.model.dop;
+ <keyword arguments>
+) -> res
Closed-loop simulation of estim estimator for N time 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 simulate.
N::Int : simulation length in time steps.
u = estim.model.uop .+ 1 : manipulated input $\mathbf{u}$ value.
d = estim.model.dop : plant measured disturbance $\mathbf{d}$ value.
All the predictive controllers in this module rely on a state estimator to compute the predictions. The default LinMPC estimator is a SteadyKalmanFilter, and NonLinMPC with nonlinear models, an UnscentedKalmanFilter. For simpler and more classical designs, an InternalModel structure is also available, that assumes by default that the current model mismatch estimation is constant in the future (same approach as dynamic matrix control, DMC).
Info
The nomenclature use capital letters for time series (and matrices) and hats for the predictions (and estimations, for state estimators).
To be precise, at the $k$th control period, the vectors that encompass the future measured disturbances $\mathbf{d̂}$, model outputs $\mathbf{ŷ}$ and setpoints $\mathbf{r̂_y}$ over the prediction horizon $H_p$ are defined as:
assuming constant input setpoints at $\mathbf{r_u}$. Defining the manipulated input increment as $\mathbf{Δu}(k+j) = \mathbf{u}(k+j) - \mathbf{u}(k+j-1)$, the control horizon $H_c$ enforces that $\mathbf{Δu}(k+j) = \mathbf{0}$ for $j ≥ H_c$. For this reason, the vector that collects them is truncated up to $k+H_c-1$:
The $\mathbf{ΔU}$ vector includes the manipulated input increments $\mathbf{Δu}(k+j) = \mathbf{u}(k+j) - \mathbf{u}(k+j-1)$ from $j=0$ to $H_c-1$, the $\mathbf{Ŷ}$ vector, the output predictions $\mathbf{ŷ}(k+j)$ from $j=1$ to $H_p$, and the $\mathbf{U}$ vector, the manipulated inputs $\mathbf{u}(k+j)$ from $j=0$ to $H_p-1$. The manipulated input setpoint predictions $\mathbf{R̂_u}$ are constant at $\mathbf{r_u}$. See Extended Help for a detailed nomenclature.
This method uses the default state estimator, a SteadyKalmanFilter with default arguments.
Arguments
model::LinModel : model used for controller predictions and state estimations.
Hp=10+nk: prediction horizon $H_p$, nk is the number of delays in model.
Hc=2 : control horizon $H_c$.
Mwt=fill(1.0,model.ny) : main diagonal of $\mathbf{M}$ weight matrix (vector).
Nwt=fill(0.1,model.nu) : main diagonal of $\mathbf{N}$ weight matrix (vector).
Lwt=fill(0.0,model.nu) : main diagonal of $\mathbf{L}$ weight matrix (vector).
Cwt=1e5 : slack variable weight $C$ (scalar), use Cwt=Inf for hard constraints only.
optim=JuMP.Model(OSQP.MathOptInterfaceOSQP.Optimizer) : quadratic optimizer used in the predictive controller, provided as a JuMP.Model (default to OSQP.jl optimizer).
Examples
julia> model = LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 4);
+
+julia> mpc = LinMPC(model, Mwt=[0, 1], Nwt=[0.5], Hp=30, Hc=1)
+LinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, SteadyKalmanFilter estimator and:
+ 30 prediction steps Hp
+ 1 control steps Hc
+ 1 manipulated inputs u (0 integrators)
+ 4 states x̂
+ 2 measured outputs ym (2 integrators)
+ 0 unmeasured outputs yu
+ 0 measured disturbances d
Extended Help
Manipulated inputs setpoints $\mathbf{r_u}$ are not common but they can be interesting for over-actuated systems, when nu > ny (e.g. prioritize solutions with lower economical costs). The default Lwt value implies that this feature is disabled by default.
See LinMPC for the variable definitions. This controller does not support constraints but the computational costs are extremely low (array division), therefore suitable for applications that require small sample times. This method uses the default state estimator, a SteadyKalmanFilter with default arguments.
Arguments
model::LinModel : model used for controller predictions and state estimations.
Hp=10+nk: prediction horizon $H_p$, nk is the number of delays in model.
Hc=2 : control horizon $H_c$.
Mwt=fill(1.0,model.ny) : main diagonal of $\mathbf{M}$ weight matrix (vector).
Nwt=fill(0.1,model.nu) : main diagonal of $\mathbf{N}$ weight matrix (vector).
Lwt=fill(0.0,model.nu) : main diagonal of $\mathbf{L}$ weight matrix (vector).
See LinMPC for the variable definitions. The custom economic function $J_E$ can penalizes solutions with high economic costs. Setting all the weights to 0 except $E$ creates a pure economic model predictive controller (EMPC). The arguments of $J_E$ are the manipulated inputs, the predicted outputs and measured disturbances from $k$ to $k+H_p$ inclusively:
since $H_c ≤ H_p$ implies that $\mathbf{u}(k+H_p) = \mathbf{u}(k+H_p-1)$. The vector $\mathbf{D̂}$ includes the predicted measured disturbance over $H_p$.
Tip
Replace any of the 3 arguments with _ if not needed (see JE default value below).
optim=JuMP.Model(Ipopt.Optimizer) : nonlinear optimizer used in the predictive controller, provided as a JuMP.Model (default to Ipopt.jl optimizer).
Examples
julia> model = NonLinModel((x,u,_)->0.5x+u, (x,_)->2x, 10.0, 1, 1, 1);
+
+julia> mpc = NonLinMPC(model, Hp=20, Hc=1, Cwt=1e6)
+NonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, UnscentedKalmanFilter estimator and:
+ 20 prediction steps Hp
+ 1 control steps Hc
+ 1 manipulated inputs u (0 integrators)
+ 2 states x̂
+ 1 measured outputs ym (1 integrators)
+ 0 unmeasured outputs yu
+ 0 measured disturbances d
Extended Help
NonLinMPC controllers based on LinModel compute the predictions with matrix algebra instead of a for loop. This feature can accelerate the optimization and is not available in any other package, to my knowledge.
The optimizations rely on JuMP.jl automatic differentiation (AD) to compute the objective and constraint derivatives. Optimizers generally benefit from exact derivatives like AD. However, the NonLinModelf and h functions must be compatible with this feature. See Automatic differentiation for common mistakes when writing these functions.
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. The output constraints $\mathbf{y_{min}}$ and $\mathbf{y_{max}}$ are soft by default.
Arguments
Info
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).
moveinput!(
+ mpc::PredictiveController,
+ ry = mpc.estim.model.yop,
+ d = Float64[];
+ R̂y = repeat(ry, mpc.Hp),
+ D̂ = repeat(d, mpc.Hp),
+ ym = nothing
+)
Compute the optimal manipulated input value u for the current control period.
Solve the optimization problem of mpcPredictiveController and return the results $\mathbf{u}(k)$. Following the receding horizon principle, the algorithm discards the optimal future manipulated inputs $\mathbf{u}(k+1), \mathbf{u}(k+2), ...$ The arguments ry and d are current output setpoints $\mathbf{r_y}(k)$ and measured disturbances $\mathbf{d}(k)$.
The keyword arguments R̂y and D̂ are the predicted output setpoints $\mathbf{R̂_y}$ and measured disturbances $\mathbf{D̂}$. They are assumed constant in the future by default, that is $\mathbf{r̂_y}(k+j) = \mathbf{r_y}(k)$ and $\mathbf{d̂}(k+j) = \mathbf{d}(k)$ for $j=1$ to $H_p$. Current measured output ym is only required if mpc.estim is a InternalModel.
The SimModel types represents discrete state-space models that can be used to construct StateEstimators and PredictiveControllers, or as plant simulators by calling evaloutput and updatestate! methods on SimModel instances (to test estimator/controller designs). For time simulations, the states x are stored inside SimModel instances. Use setstate! method to manually modify them.
with the state $\mathbf{x}$ and output $\mathbf{y}$ vectors. The $\mathbf{z}$ vector comprises the manipulated inputs $\mathbf{u}$ and measured disturbances $\mathbf{d}$, in any order. i_u provides the indices of $\mathbf{z}$ that are manipulated, and i_d, the measured disturbances. See Extended Help if sys is continuous-time, or discrete-time with Ts ≠ sys.Ts.
julia> model = LinModel(ss(0.4, 0.2, 0.3, 0, 0.1))
+Discrete-time linear model with a sample time Ts = 0.1 s and:
+ 1 manipulated inputs u
+ 1 states x
+ 1 outputs y
+ 0 measured disturbances d
Extended Help
State-space matrices are similar if sys is continuous (replace $\mathbf{x}(k+1)$ with $\mathbf{ẋ}(t)$ and $k$ with $t$ on the LHS). In such a case, it's discretized with c2d and :zoh for manipulated inputs, and :tustin, for measured disturbances. Lastly, if sys is discrete and the provided argument Ts ≠ sys.Ts, the system is resampled by using the aforementioned discretization methods.
Note that the constructor transforms the system to its minimal realization using minreal for controllability/observability. As a consequence, the final state-space representation may be different from the one provided in sys. It is also converted into a more practical form ($\mathbf{D_u=0}$ because of the zero-order hold):
Convert to minimal realization state-space when sys is a transfer function.
sys is equal to $\frac{\mathbf{y}(s)}{\mathbf{z}(s)}$ for continuous-time, and $\frac{\mathbf{y}(z)}{\mathbf{z}(z)}$, for discrete-time.
Examples
julia> model = LinModel([tf(3, [30, 1]) tf(-2, [5, 1])], 0.5, i_d=[2])
+Discrete-time linear model with a sample time Ts = 0.5 s and:
+ 1 manipulated inputs u
+ 2 states x
+ 1 outputs y
+ 1 measured disturbances d
Discretize with zero-order hold when sys is a continuous system with delays.
The delays must be multiples of the sample time Ts.
Examples
julia> model = LinModel(tf(4, [10, 1])*delay(2), 0.5)
+Discrete-time linear model with a sample time Ts = 0.5 s and:
+ 1 manipulated inputs u
+ 5 states x
+ 1 outputs y
+ 0 measured disturbances d
Construct the model from the discrete state-space matrices A, Bu, C, Bd, Dd directly.
This syntax do not modify the state-space representation provided in argument (minreal is not called). Care must be taken to ensure that the model is controllable and observable.
Ts is the sampling time in second. nu, nx, ny and nd are the respective number of manipulated inputs, states, outputs and measured disturbances.
Tip
Replace the d argument with _ if nd = 0 (see Examples below).
Nonlinear continuous-time state-space functions are not supported for now. In such a case, manually call a differential equation solver in f (see Manual).
Warning
f and h must be pure Julia functions to use the model in NonLinMPC, ExtendedKalmanFilter and MovingHorizonEstimator.
julia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1)
+Discrete-time nonlinear model with a sample time Ts = 10.0 s and:
+ 1 manipulated inputs u
+ 1 states x
+ 1 outputs y
+ 0 measured disturbances d
julia> model = setop!(LinModel(tf(3, [10, 1]), 2.0), uop=[50], yop=[20])
+Discrete-time linear model with a sample time Ts = 2.0 s and:
+ 1 manipulated inputs u
+ 1 states x
+ 1 outputs y
+ 0 measured disturbances d
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).
Info
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 nint_u=0 and nint_ym=0 disable it.
The estimators are all implemented in the predictor form (a.k.a. observer form), that is, they all estimates at each discrete time $k$ the states of the next period $\mathbf{x̂}_k(k+1)$[1]. In contrast, the filter form that estimates $\mathbf{x̂}_k(k)$ 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).
Info
All the estimators support measured $\mathbf{y^m}$ and unmeasured $\mathbf{y^u}$ model outputs, where $\mathbf{y}$ refers to all of them.
with sensor $\mathbf{v}(k)$ and process $\mathbf{w}(k)$ noises as uncorrelated zero mean white noise vectors, with a respective covariance of $\mathbf{R̂}$ and $\mathbf{Q̂}$. The arguments are in standard deviations σ, i.e. same units than outputs and states. The matrices $\mathbf{Â, B̂_u, B̂_d, Ĉ, D̂_d}$ 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 $\mathbf{Q̂ = \text{diag}(Q, Q_{int_u}, Q_{int_{ym}})}$ and $\mathbf{R̂ = R}$. The matrices $\mathbf{Ĉ^m, D̂_d^m}$ are the rows of $\mathbf{Ĉ, D̂_d}$ that correspond to measured outputs $\mathbf{y^m}$ (and unmeasured ones, for $\mathbf{Ĉ^u, D̂_d^u}$).
Arguments
model::LinModel : (deterministic) model for the estimations.
i_ym=1:model.ny : model output indices that are measured $\mathbf{y^m}$, the rest are unmeasured $\mathbf{y^u}$.
σQ=fill(1/model.nx,model.nx) : main diagonal of the process noise covariance $\mathbf{Q}$ of model, specified as a standard deviation vector.
σR=fill(1,length(i_ym)) : main diagonal of the sensor noise covariance $\mathbf{R}$ of model 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), use nint_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 $\mathbf{Q_{int_u}}$ (composed of integrators).
nint_ym=default_nint(model,i_ym,nint_u) : same than nint_u but for the unmeasured disturbances at the measured outputs, use nint_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 $\mathbf{Q_{int_{ym}}}$ (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 integrators)
+ 3 states x̂
+ 1 measured outputs ym (1 integrators)
+ 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.
Tip
Increasing σQint_u and σQint_ym values increases the integral action "gain".
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.
Construct a time-varying Kalman Filter with the LinModelmodel.
The process model is identical to SteadyKalmanFilter. The matrix $\mathbf{P̂}_k(k+1)$ is the estimation error covariance of model states augmented with the stochastic ones (specified by nint_ym). Three keyword arguments modify its initial value with $\mathbf{P̂}_{-1}(0) = \mathrm{diag}\{ \mathbf{P}(0), \mathbf{P_{int_{u}}}(0), \mathbf{P_{int_{ym}}}(0) \}$.
Arguments
model::LinModel : (deterministic) model for the estimations.
σP0=fill(1/model.nx,model.nx) : main diagonal of the initial estimate covariance $\mathbf{P}(0)$, specified as a standard deviation vector.
σP0int_u=fill(1,sum(nint_u)) : same than σP0 but for the unmeasured disturbances at manipulated inputs $\mathbf{P_{int_u}}(0)$ (composed of integrators).
σP0int_ym=fill(1,sum(nint_ym)) : same than σP0 but for the unmeasured disturbances at measured outputs $\mathbf{P_{int_{ym}}}(0)$ (composed of integrators).
Construct a Luenberger observer with the LinModelmodel.
i_ym provides the model output indices that are measured $\mathbf{y^m}$, the rest are unmeasured $\mathbf{y^u}$. 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_ym) elements specifying the observer poles/eigenvalues (near $z=0.5$ 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 integrators)
+ 4 states x̂
+ 2 measured outputs ym (2 integrators)
+ 0 unmeasured outputs yu
+ 0 measured disturbances d
See SteadyKalmanFilter for details on $\mathbf{v}(k), \mathbf{w}(k)$ noises and $\mathbf{R̂}, \mathbf{Q̂}$ covariances. The functions $\mathbf{f̂, ĥ}$ 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 $\mathbf{ĥ^m}$ function represents the measured outputs of $\mathbf{ĥ}$ function (and unmeasured ones, for $\mathbf{ĥ^u}$).
Arguments
model::SimModel : (deterministic) model for the estimations.
α=1e-3 : alpha parameter, spread of the state distribution $(0 ≤ α ≤ 1)$.
β=2 : beta parameter, skewness and kurtosis of the states distribution $(β ≥ 0)$.
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 integrators)
+ 3 states x̂
+ 1 measured outputs ym (2 integrators)
+ 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.
Construct an extended Kalman Filter with the SimModelmodel.
Both LinModel and NonLinModel are supported. The process model is identical to UnscentedKalmanFilter. The Jacobians of the augmented model $\mathbf{f̂, ĥ}$ are computed with ForwardDiff.jl automatic differentiation.
Warning
See Extended Help if you get an error like: MethodError: no method matching (::var"##")(::Vector{ForwardDiff.Dual}).
Arguments
model::SimModel : (deterministic) model for the estimations.
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 integrators)
+ 2 states x̂
+ 1 measured outputs ym (1 integrators)
+ 0 unmeasured outputs yu
+ 0 measured disturbances d
Extended Help
Automatic differentiation (AD) allows exact Jacobians. The NonLinModelf and h functions must be compatible with this feature though. See Automatic differentiation for common mistakes when writing these functions.
Construct an internal model estimator based on model (LinModel or NonLinModel).
i_ym provides the model output indices that are measured $\mathbf{y^m}$, the rest are unmeasured $\mathbf{y^u}$. model evaluates the deterministic predictions $\mathbf{ŷ_d}$, and stoch_ym, the stochastic predictions of the measured outputs $\mathbf{ŷ_s^m}$ (the unmeasured ones being $\mathbf{ŷ_s^u=0}$). The predicted outputs sum both values : $\mathbf{ŷ = ŷ_d + ŷ_s}$.
Warning
InternalModel estimator does not work if model is integrating or unstable. The constructor verifies these aspects for LinModel but not for NonLinModel. Uses any other state estimator in such cases.
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 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 $\mathbf{y^m}$. Its input is a hypothetical zero mean white noise vector. stoch_ym supposes 1 integrator per measured outputs by default, assuming that the current stochastic estimate $\mathbf{ŷ_s^m}(k) = \mathbf{y^m}(k) - \mathbf{ŷ_d^m}(k)$ is constant in the future. This is the dynamic matrix control (DMC) strategy, which is simple but sometimes too aggressive. Additional poles and zeros in stoch_ym can mitigate this.
Get default integrator quantity per measured outputs nint_ym for LinModel.
The measured output $\mathbf{y^m}$ indices are specified by i_ym argument. By default, one integrator is added on each measured outputs. If $\mathbf{Â, Ĉ}$ matrices of the augmented model become unobservable, the integrator is removed. This approach works well for stable, integrating and unstable model (see Examples).
This document was generated with Documenter.jl version 0.27.25 on Thursday 14 September 2023. Using Julia version 1.9.3.
diff --git a/v0.8.3/search_index.js b/v0.8.3/search_index.js
new file mode 100644
index 000000000..0a4c8a8b9
--- /dev/null
+++ b/v0.8.3/search_index.js
@@ -0,0 +1,3 @@
+var documenterSearchIndex = {"docs":
+[{"location":"manual/installation/#Manual:-Installation","page":"Installation","title":"Manual: Installation","text":"","category":"section"},{"location":"manual/installation/","page":"Installation","title":"Installation","text":"To install the ModelPredictiveControl package, run this command in the Julia REPL:","category":"page"},{"location":"manual/installation/","page":"Installation","title":"Installation","text":"using Pkg; Pkg.activate(); Pkg.add(\"ModelPredictiveControl\")","category":"page"},{"location":"manual/installation/","page":"Installation","title":"Installation","text":"Doing so will install the package to default Julia environnement, that is, accessible anywhere. To facilitate sharing of code and reproducibility of results, it is recommended to install packages in a project environnement. To generate a new project named MPCproject with this package in the current working directory, write this in the REPL:","category":"page"},{"location":"manual/installation/","page":"Installation","title":"Installation","text":"using Pkg; Pkg.generate(\"MPCproject\"); Pkg.activate(\".\"); Pkg.add(\"ModelPredictiveControl\")","category":"page"},{"location":"manual/installation/","page":"Installation","title":"Installation","text":"Note that that the construction of linear models typically requires ss or tf functions, it is thus advised to load the package with:","category":"page"},{"location":"manual/installation/","page":"Installation","title":"Installation","text":"using ModelPredictiveControl, ControlSystemsBase","category":"page"},{"location":"internals/predictive_control/#Functions:-PredictiveController-Internals","page":"Predictive Controllers","title":"Functions: PredictiveController Internals","text":"","category":"section"},{"location":"internals/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"Pages = [\"predictive_control.md\"]","category":"page"},{"location":"internals/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"The prediction methodology of this module is mainly based on Maciejowski textbook [1].","category":"page"},{"location":"internals/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"[1]: Maciejowski, J. 2000, \"Predictive control : with constraints\", 1st ed., Prentice Hall, ISBN 978-0201398236.","category":"page"},{"location":"internals/predictive_control/#Controller-Construction","page":"Predictive Controllers","title":"Controller Construction","text":"","category":"section"},{"location":"internals/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"ModelPredictiveControl.init_predmat\nModelPredictiveControl.init_ΔUtoU\nModelPredictiveControl.init_quadprog\nModelPredictiveControl.init_stochpred\nModelPredictiveControl.init_linconstraint","category":"page"},{"location":"internals/predictive_control/#ModelPredictiveControl.init_predmat","page":"Predictive Controllers","title":"ModelPredictiveControl.init_predmat","text":"init_predmat(estim::StateEstimator, ::LinModel, Hp, Hc) -> E, G, J, K, Q\n\nConstruct the prediction matrices for LinModel model.\n\nThe linear model predictions are evaluated by :\n\nbeginaligned\n mathbfY = mathbfE ΔU + mathbfG d(k) + mathbfJ D + mathbfK x_k-1(k) \n + mathbfQ u(k-1) + mathbfY_s \n = mathbfE ΔU + mathbfF\nendaligned\n\nwhere predicted outputs mathbfY, stochastic outputs mathbfY_s, and measured disturbances mathbfD are from k + 1 to k + H_p. Input increments mathbfΔU are from k to k + H_c - 1. The vector mathbfx_k-1(k) is the state estimated at the last control period. The stochastic outputs mathbfY_s = 0 if estim is not a InternalModel. Operating points on mathbfu, mathbfd and mathbfy are omitted in above equations.\n\nExtended Help\n\nUsing the augmented matrices mathbfA B_u C B_d D_d in estim and the equation mathbfW_j = mathbfC ( _i=0^j mathbfA^i ) mathbfB_u, the prediction matrices are computed by :\n\nbeginaligned\nmathbfE = beginbmatrix\nmathbfW_0 mathbf0 cdots mathbf0 \nmathbfW_1 mathbfW_0 cdots mathbf0 \nvdots vdots ddots vdots \nmathbfW_H_p-1 mathbfW_H_p-2 cdots mathbfW_H_p-H_c+1\nendbmatrix\n\nmathbfG = beginbmatrix\nmathbfCmathbfA^0 mathbfB_d \nmathbfCmathbfA^1 mathbfB_d \nvdots \nmathbfCmathbfA^H_p-1 mathbfB_d\nendbmatrix\n\nmathbfJ = beginbmatrix\nmathbfD_d mathbf0 cdots mathbf0 \nmathbfCmathbfA^0 mathbfB_d mathbfD_d cdots mathbf0 \nvdots vdots ddots vdots \nmathbfCmathbfA^H_p-2 mathbfB_d mathbfCmathbfA^H_p-3 mathbfB_d cdots mathbfD_d\nendbmatrix\n\nmathbfK = beginbmatrix\nmathbfCmathbfA^1 \nmathbfCmathbfA^2 \nvdots \nmathbfCmathbfA^H_p\nendbmatrix\n\nmathbfQ = beginbmatrix\nmathbfW_0 \nmathbfW_1 \nvdots \nmathbfW_H_p-1\nendbmatrix\nendaligned\n\n\n\n\n\nReturn empty matrices if model is not a LinModel\n\n\n\n\n\n","category":"function"},{"location":"internals/predictive_control/#ModelPredictiveControl.init_ΔUtoU","page":"Predictive Controllers","title":"ModelPredictiveControl.init_ΔUtoU","text":"init_ΔUtoU(nu, Hp, Hc, C, c_Umin, c_Umax) -> S_Hp, T_Hp, S_Hc, T_Hc\n\nInit manipulated input increments to inputs conversion matrices.\n\nThe conversion from the input increments mathbfΔU to manipulated inputs over H_p and H_c are calculated by:\n\nbeginaligned\nmathbfU = \n mathbfU_H_p = mathbfS_H_p mathbfΔU + mathbfT_H_p mathbfu(k-1) \n mathbfU_H_c = mathbfS_H_c mathbfΔU + mathbfT_H_c mathbfu(k-1)\nendaligned\n\n\n\n\n\n","category":"function"},{"location":"internals/predictive_control/#ModelPredictiveControl.init_quadprog","page":"Predictive Controllers","title":"ModelPredictiveControl.init_quadprog","text":"init_quadprog(model::LinModel, Ẽ, S_Hp, M_Hp, N_Hc, L_Hp) -> P̃, q̃, p\n\nInit the quadratic programming optimization matrix P̃ and q̃.\n\nThe matrices appear in the quadratic general form :\n\n J = min_mathbfΔU frac12mathbf(ΔU)P(ΔU) + mathbfq(ΔU) + p \n\nmathbfP is constant if the model and weights are linear and time invariant (LTI). The vector mathbfq and scalar p need recalculation each control period k (see initpred! method). p does not impact the minima position. It is thus useless at optimization but required to evaluate the minimal J value.\n\n\n\n\n\nReturn empty matrices if model is not a LinModel.\n\n\n\n\n\n","category":"function"},{"location":"internals/predictive_control/#ModelPredictiveControl.init_stochpred","page":"Predictive Controllers","title":"ModelPredictiveControl.init_stochpred","text":"init_stochpred(estim::InternalModel, Hp) -> Ks, Ps\n\nInit the stochastic prediction matrices for InternalModel.\n\nKs and Ps matrices are defined as:\n\n mathbfY_s = mathbfK_s x_s(k) + mathbfP_s y_s(k)\n\nCurrent stochastic outputs mathbfy_s(k) comprises the measured outputs mathbfy_s^m(k) = mathbfy^m(k) - mathbfy_d^m(k) and unmeasured mathbfy_s^u(k) = mathbf0. See [2].\n\n[2]: Desbiens, A., D. Hodouin & É. Plamondon. 2000, \"Global predictive control : a unified control structure for decoupling setpoint tracking, feedforward compensation and disturbance rejection dynamics\", IEE Proceedings - Control Theory and Applications, vol. 147, no 4, https://doi.org/10.1049/ip-cta:20000443, p. 465–475, ISSN 1350-2379.\n\n\n\n\n\nReturn empty matrices if estim is not a InternalModel.\n\n\n\n\n\n","category":"function"},{"location":"internals/predictive_control/#ModelPredictiveControl.init_linconstraint","page":"Predictive Controllers","title":"ModelPredictiveControl.init_linconstraint","text":"init_linconstraint(model::LinModel, \n A_Umin, A_Umax, A_ΔŨmin, A_ΔŨmax, A_Ymin, A_Ymax,\n i_Umin, i_Umax, i_ΔŨmin, i_ΔŨmax, i_Ymin, i_Ymax\n) -> A, i_b, b\n\nInit A, b and i_b for the linear inequality constraints (mathbfA ΔU b).\n\ni_b is a BitVector including the indices of mathbfb that are finite numbers.\n\n\n\n\n\nInit values without predicted output constraints if model is not a LinModel.\n\n\n\n\n\n","category":"function"},{"location":"internals/predictive_control/#Constraint-Relaxation","page":"Predictive Controllers","title":"Constraint Relaxation","text":"","category":"section"},{"location":"internals/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"ModelPredictiveControl.relaxU\nModelPredictiveControl.relaxΔU\nModelPredictiveControl.relaxŶ","category":"page"},{"location":"internals/predictive_control/#ModelPredictiveControl.relaxU","page":"Predictive Controllers","title":"ModelPredictiveControl.relaxU","text":"relaxU(C, c_Umin, c_Umax, S_Hp, S_Hc) -> A_Umin, A_Umax, S̃_Hp\n\nAugment manipulated inputs constraints with slack variable ϵ for softening.\n\nDenoting the input increments augmented with the slack variable mathbfΔU = beginsmallmatrix mathbfΔU ϵ endsmallmatrix, it returns the augmented conversion matrix mathbfS_H_p, similar to the one described at init_ΔUtoU. It also returns the mathbfA matrices for the inequality constraints:\n\nbeginbmatrix \n mathbfA_U_min \n mathbfA_U_max \nendbmatrix mathbfΔU \nbeginbmatrix\n - mathbfU_min + mathbfT_H_c mathbfu(k-1) \n + mathbfU_max - mathbfT_H_c mathbfu(k-1)\nendbmatrix\n\n\n\n\n\n","category":"function"},{"location":"internals/predictive_control/#ModelPredictiveControl.relaxΔU","page":"Predictive Controllers","title":"ModelPredictiveControl.relaxΔU","text":"relaxΔU(C, c_ΔUmin, c_ΔUmax, ΔUmin, ΔUmax, N_Hc) -> A_ΔŨmin, A_ΔŨmax, ΔŨmin, ΔŨmax, Ñ_Hc\n\nAugment input increments constraints with slack variable ϵ for softening.\n\nDenoting the input increments augmented with the slack variable mathbfΔU = beginsmallmatrix mathbfΔU ϵ endsmallmatrix, it returns the augmented input increment weights mathbfN_H_c (that incorporate C). It also returns the augmented constraints mathbfΔU_min and mathbfΔU_max and the mathbfA matrices for the inequality constraints:\n\nbeginbmatrix \n mathbfA_ΔU_min \n mathbfA_ΔU_max\nendbmatrix mathbfΔU \nbeginbmatrix\n - mathbfΔU_min \n + mathbfΔU_max\nendbmatrix\n\n\n\n\n\n","category":"function"},{"location":"internals/predictive_control/#ModelPredictiveControl.relaxŶ","page":"Predictive Controllers","title":"ModelPredictiveControl.relaxŶ","text":"relaxŶ(::LinModel, C, c_Ymin, c_Ymax, E) -> A_Ymin, A_Ymax, Ẽ\n\nAugment linear output prediction constraints with slack variable ϵ for softening.\n\nDenoting the input increments augmented with the slack variable mathbfΔU = beginsmallmatrix mathbfΔU ϵ endsmallmatrix, it returns the mathbfE matrix that appears in the linear model prediction equation mathbfY = E ΔU + F, and the mathbfA matrices for the inequality constraints:\n\nbeginbmatrix \n mathbfA_Y_min \n mathbfA_Y_max\nendbmatrix mathbfΔU \nbeginbmatrix\n - mathbfY_min + mathbfF \n + mathbfY_max - mathbfF \nendbmatrix\n\n\n\n\n\nReturn empty matrices if model is not a LinModel\n\n\n\n\n\n","category":"function"},{"location":"internals/predictive_control/#Predictions","page":"Predictive Controllers","title":"Predictions","text":"","category":"section"},{"location":"internals/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"ModelPredictiveControl.initpred!","category":"page"},{"location":"internals/predictive_control/#ModelPredictiveControl.initpred!","page":"Predictive Controllers","title":"ModelPredictiveControl.initpred!","text":"initpred!(mpc, model::LinModel, d, D̂, R̂y)\n\nInit linear model prediction matrices F, q̃ and p.\n\nSee init_predmat and init_quadprog for the definition of the matrices.\n\n\n\n\n\ninitpred!(mpc::PredictiveController, model::SimModel, d, D̂, R̂y)\n\nInit d0 and D̂0 matrices when model is not a LinModel.\n\nd0 and D̂0 are the measured disturbances and its predictions without the operating points mathbfd_op.\n\n\n\n\n\n","category":"function"},{"location":"internals/predictive_control/#Constraints","page":"Predictive Controllers","title":"Constraints","text":"","category":"section"},{"location":"internals/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"ModelPredictiveControl.linconstraint!","category":"page"},{"location":"internals/predictive_control/#ModelPredictiveControl.linconstraint!","page":"Predictive Controllers","title":"ModelPredictiveControl.linconstraint!","text":"linconstraint!(mpc::PredictiveController, model::LinModel)\n\nSet b vector for the linear model inequality constraints (mathbfA ΔU b).\n\n\n\n\n\nSet b excluding predicted output constraints when model is not a LinModel.\n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#Functions:-StateEstimator-Internals","page":"State Estimators","title":"Functions: StateEstimator Internals","text":"","category":"section"},{"location":"internals/state_estim/","page":"State Estimators","title":"State Estimators","text":"Pages = [\"state_estim.md\"]","category":"page"},{"location":"internals/state_estim/#Estimator-Construction","page":"State Estimators","title":"Estimator Construction","text":"","category":"section"},{"location":"internals/state_estim/","page":"State Estimators","title":"State Estimators","text":"ModelPredictiveControl.init_estimstoch\nModelPredictiveControl.init_integrators\nModelPredictiveControl.augment_model\nModelPredictiveControl.init_ukf\nModelPredictiveControl.init_internalmodel","category":"page"},{"location":"internals/state_estim/#ModelPredictiveControl.init_estimstoch","page":"State Estimators","title":"ModelPredictiveControl.init_estimstoch","text":"init_estimstoch(model, i_ym, nint_u, nint_ym) -> As, Cs_u, Cs_y, nxs, nint_u, nint_ym\n\nInit stochastic model matrices from integrator specifications for state estimation.\n\nThe arguments nint_u and nint_ym specify how many integrators are added to each manipulated input and measured outputs. The function returns the state-space matrices As, Cs_u and Cs_y of the stochastic model:\n\nbeginaligned\nmathbfx_s(k+1) = mathbfA_s x_s(k) + mathbfB_s e(k) \nmathbfy_s_u(k) = mathbfC_s_u x_s(k) \nmathbfy_s_ym(k) = mathbfC_s_ym x_s(k) \nendaligned\n\nwhere mathbfe(k) is an unknown zero mean white noise and mathbfA_s = mathrmdiag(mathbfA_s_u A_s_ym). The estimations does not use mathbfB_s, it is thus ignored. The function init_integrators builds the state-space matrices.\n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#ModelPredictiveControl.init_integrators","page":"State Estimators","title":"ModelPredictiveControl.init_integrators","text":"init_integrators(nint, ny, varname::String) -> A, C, nint\n\nCalc A, C state-space matrices from integrator specifications nint.\n\nThis function is used to initialize the stochastic part of the augmented model for the design of state estimators. The vector nint provides how many integrators (in series) should be incorporated for each output. The argument should have ny element, except for nint=0 which is an alias for no integrator at all. The specific case of one integrator per output results in A = I and C = I. The estimation does not use the B matrix, it is thus ignored. This function is called twice :\n\nfor the unmeasured disturbances at manipulated inputs mathbfu\nfor the unmeasured disturbances at measured outputs mathbfy^m\n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#ModelPredictiveControl.augment_model","page":"State Estimators","title":"ModelPredictiveControl.augment_model","text":"augment_model(model::LinModel, As, Cs; verify_obsv=true) -> Â, B̂u, Ĉ, B̂d, D̂d\n\nAugment LinModel state-space matrices with the stochastic ones As and Cs.\n\nIf mathbfx are model.x states, and mathbfx_s, the states defined at init_integrators, we define an augmented state vector mathbfx = beginsmallmatrix mathbfx mathbfx_s endsmallmatrix . The method returns the augmented matrices Â, B̂u, Ĉ, B̂d and D̂d:\n\nbeginaligned\n mathbfx(k+1) = mathbfA x(k) + mathbfB_u u(k) + mathbfB_d d(k) \n mathbfy(k) = mathbfC x(k) + mathbfD_d d(k)\nendaligned\n\nAn error is thrown if the augmented model is not observable and verify_obsv == true.\n\n\n\n\n\nReturn empty matrices if model is not a LinModel.\n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#ModelPredictiveControl.init_ukf","page":"State Estimators","title":"ModelPredictiveControl.init_ukf","text":"init_ukf(nx̂, α, β, κ) -> nσ, γ, m̂, Ŝ\n\nCompute the UnscentedKalmanFilter constants from α β and κ.\n\nWith n_mathbfx elements in the state vector mathbfx and n_σ = 2 n_mathbfx + 1 sigma points, the scaling factor applied on standard deviation matrices sqrtmathbfP is:\n\n γ = α sqrt n_mathbfx + κ \n\nThe weight vector (n_σ 1) for the mean and the weight matrix (n_σ n_σ) for the covariance are respectively:\n\nbeginaligned\n mathbfm = beginbmatrix 1 - tfracn_mathbfxγ^2 tfrac12γ^2 tfrac12γ^2 cdots tfrac12γ^2 endbmatrix \n mathbfS = mathrmdiagbig( 2 - α^2 + β - tfracn_mathbfxγ^2 tfrac12γ^2 tfrac12γ^2 cdots tfrac12γ^2 big)\nendaligned\n\nSee update_estimate!(::UnscentedKalmanFilter) for other details.\n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#ModelPredictiveControl.init_internalmodel","page":"State Estimators","title":"ModelPredictiveControl.init_internalmodel","text":"init_internalmodel(As, Bs, Cs, Ds) -> Âs, B̂s\n\nCalc stochastic model update matrices Âs and B̂s for InternalModel estimator.\n\nAs, Bs, Cs and Ds are the stochastic model matrices :\n\nbeginaligned\n mathbfx_s(k+1) = mathbfA_s x_s(k) + mathbfB_s e(k) \n mathbfy_s(k) = mathbfC_s x_s(k) + mathbfD_s e(k)\nendaligned\n\nwhere mathbfe(k) is conceptual and unknown zero mean white noise. Its optimal estimation is mathbfe=0, the expected value. Thus, the Âs and B̂s matrices that optimally update the stochastic estimate mathbfx_s are:\n\nbeginaligned\n mathbfx_s(k+1) \n = mathbf(A_s - B_s D_s^-1 C_s) x_s(k) + mathbf(B_s D_s^-1) y_s(k) \n = mathbfA_s x_s(k) + mathbfB_s y_s(k)\nendaligned\n\nwith current stochastic outputs estimation mathbfy_s(k), composed of the measured mathbfy_s^m(k) = mathbfy^m(k) - mathbfy_d^m(k) and unmeasured mathbfy_s^u = 0 outputs. See [1].\n\n[1]: Desbiens, A., D. Hodouin & É. Plamondon. 2000, \"Global predictive control : a unified control structure for decoupling setpoint tracking, feedforward compensation and disturbance rejection dynamics\", IEE Proceedings - Control Theory and Applications, vol. 147, no 4, https://doi.org/10.1049/ip-cta:20000443, p. 465–475, ISSN 1350-2379.\n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#Augmented-Model","page":"State Estimators","title":"Augmented Model","text":"","category":"section"},{"location":"internals/state_estim/","page":"State Estimators","title":"State Estimators","text":"ModelPredictiveControl.f̂\nModelPredictiveControl.ĥ","category":"page"},{"location":"internals/state_estim/#ModelPredictiveControl.f̂","page":"State Estimators","title":"ModelPredictiveControl.f̂","text":"f̂(estim::StateEstimator, x̂, u, d)\n\nState function mathbff of the augmented model.\n\nBy introducing an augmented state vector mathbfx like in augment_model, the function returns the next state of the augmented model, defined as:\n\nbeginaligned\n mathbfx(k+1) = mathbffBig(mathbfx(k) mathbfu(k) mathbfd(k)Big) \n mathbfy(k) = mathbfhBig(mathbfx(k) mathbfd(k)Big) \nendaligned\n\n\n\n\n\nf̂(estim::InternalModel, x̂, u, d)\n\nState function mathbff of the [InternalModel].\n\nIt calls f(estim.model, x̂, u ,d) since this estimator does not augment the state vector.\n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#ModelPredictiveControl.ĥ","page":"State Estimators","title":"ModelPredictiveControl.ĥ","text":"ĥ(estim::StateEstimator, x̂, d)\n\nOutput function mathbfh of the augmented model, see f̂ for details.\n\n\n\n\n\nĥ(estim::InternalModel, x̂, d)\n\nOutput function mathbfh of the [InternalModel], it calls h(estim.model, x̂, d).\n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#Remove-Operating-Points","page":"State Estimators","title":"Remove Operating Points","text":"","category":"section"},{"location":"internals/state_estim/","page":"State Estimators","title":"State Estimators","text":"ModelPredictiveControl.remove_op!","category":"page"},{"location":"internals/state_estim/#ModelPredictiveControl.remove_op!","page":"State Estimators","title":"ModelPredictiveControl.remove_op!","text":"remove_op!(estim::StateEstimator, u, d, ym) -> u0, d0, ym0\n\nRemove operating points on inputs u, measured outputs ym and disturbances d.\n\nAlso store current inputs without operating points u0 in estim.lastu0. This field is used for PredictiveController computations.\n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#Update-Estimate","page":"State Estimators","title":"Update Estimate","text":"","category":"section"},{"location":"internals/state_estim/","page":"State Estimators","title":"State Estimators","text":"info: Info\nAll these methods assume that the operating points are already removed in u, ym and d arguments. Strickly speaking, the arguments should be called u0, ym0 and d0, following setop! notation. The 0 is dropped to simplify the notation.","category":"page"},{"location":"internals/state_estim/","page":"State Estimators","title":"State Estimators","text":"ModelPredictiveControl.update_estimate!","category":"page"},{"location":"internals/state_estim/#ModelPredictiveControl.update_estimate!","page":"State Estimators","title":"ModelPredictiveControl.update_estimate!","text":"update_estimate!(estim::SteadyKalmanFilter, u, ym, d)\n\nUpdate estim.x̂ estimate with current inputs u, measured outputs ym and dist. d.\n\nThe SteadyKalmanFilter updates it with the precomputed Kalman gain mathbfK:\n\nmathbfx_k(k+1) = mathbfA x_k-1(k) + mathbfB_u u(k) + mathbfB_d d(k) \n + mathbfKmathbfy^m(k) - mathbfC^m x_k-1(k) - mathbfD_d^m d(k)\n\n\n\n\n\nupdate_estimate!(estim::KalmanFilter, u, ym, d)\n\nUpdate KalmanFilter state estim.x̂ and estimation error covariance estim.P̂.\n\nIt implements the time-varying Kalman Filter in its predictor (observer) form :\n\nbeginaligned\n mathbfM(k) = mathbfP_k-1(k)mathbfC^m\n mathbfC^m P_k-1(k)mathbfC^m + mathbfR^-1 \n mathbfK(k) = mathbfA M(k) \n mathbfy^m(k) = mathbfC^m x_k-1(k) + mathbfD_d^m d(k) \n mathbfx_k(k+1) = mathbfA x_k-1(k) + mathbfB_u u(k) + mathbfB_d d(k)\n + mathbfK(k)mathbfy^m(k) - mathbfy^m(k) \n mathbfP_k(k+1) = mathbfAmathbfP_k-1(k)\n - mathbfM(k)mathbfC^m P_k-1(k)mathbfA + mathbfQ\nendaligned\n\nbased on the process model described in SteadyKalmanFilter. The notation mathbfx_k-1(k) refers to the state for the current time k estimated at the last control period k-1. See [2] for details.\n\n[2]: Boyd S., \"Lecture 8 : The Kalman Filter\" (Winter 2008-09) [course slides], EE363: Linear Dynamical Systems, https://web.stanford.edu/class/ee363/lectures/kf.pdf.\n\n\n\n\n\nupdate_estimate!(estim::UnscentedKalmanFilter, u, ym, d)\n\nUpdate UnscentedKalmanFilter state estim.x̂ and covariance estimate estim.P̂.\n\nIt implements the unscented Kalman Filter in its predictor (observer) form, based on the generalized unscented transform[3]. See init_ukf for the definition of the constants mathbfm S and γ. \n\nDenoting mathbfx_k-1(k) as the state for the current time k estimated at the last period k-1, mathbf0, a null vector, n_σ = 2 n_mathbfx + 1, the number of sigma points, and mathbfX_k-1^j(k), the vector at the jth column of mathbfX_k-1(k), the estimator updates the states with:\n\nbeginaligned\n mathbfX_k-1(k) = biggbeginmatrix mathbfx_k-1(k) mathbfx_k-1(k) cdots mathbfx_k-1(k) endmatrixbigg + biggbeginmatrix mathbf0 γ sqrtmathbfP_k-1(k) -γ sqrtmathbfP_k-1(k) endmatrixbigg \n mathbfY^m(k) = biggbeginmatrix mathbfh^mBig( mathbfX_k-1^1(k) Big) mathbfh^mBig( mathbfX_k-1^2(k) Big) cdots mathbfh^mBig( mathbfX_k-1^n_σ(k) Big) endmatrixbigg \n mathbfy^m(k) = mathbfY^m(k) mathbfm \n mathbfX_k-1(k) = beginbmatrix mathbfX_k-1^1(k) - mathbfx_k-1(k) mathbfX_k-1^2(k) - mathbfx_k-1(k) cdots mathbfX_k-1^n_σ(k) - mathbfx_k-1(k) endbmatrix \n mathbfY^m(k) = beginbmatrix mathbfY^m^1(k) - mathbfy^m(k) mathbfY^m^2(k) - mathbfy^m(k) cdots mathbfY^m^n_σ(k) - mathbfy^m(k) endbmatrix \n mathbfM(k) = mathbfY^m(k) mathbfS mathbfY^m(k) + mathbfR \n mathbfK(k) = mathbfX_k-1(k) mathbfS mathbfY^m(k) bigmathbfM(k)big^-1 \n mathbfx_k(k) = mathbfx_k-1(k) + mathbfK(k) big mathbfy^m(k) - mathbfy^m(k) big \n mathbfP_k(k) = mathbfP_k-1(k) - mathbfK(k) mathbfM(k) mathbfK(k) \n mathbfX_k(k) = biggbeginmatrix mathbfx_k(k) mathbfx_k(k) cdots mathbfx_k(k) endmatrixbigg + biggbeginmatrix mathbf0 gamma sqrtmathbfP_k(k) - gamma sqrtmathbfP_k(k) endmatrixbigg \n mathbfX_k(k+1) = biggbeginmatrix mathbffBig( mathbfX_k^1(k) mathbfu(k) mathbfd(k) Big) mathbffBig( mathbfX_k^2(k) mathbfu(k) mathbfd(k) Big) cdots mathbffBig( mathbfX_k^n_σ(k) mathbfu(k) mathbfd(k) Big) endmatrixbigg \n mathbfx_k(k+1) = mathbfX_k(k+1)mathbfm \n mathbfX_k(k+1) = beginbmatrix mathbfX_k^1(k+1) - mathbfx_k(k+1) mathbfX_k^2(k+1) - mathbfx_k(k+1) cdots mathbfX_k^n_σ(k+1) - mathbfx_k(k+1) endbmatrix \n mathbfP_k(k+1) = mathbfX_k(k+1) mathbfS mathbfX_k(k+1) + mathbfQ\nendaligned \n\nby using the lower triangular factor of cholesky to compute sqrtmathbfP_k-1(k) and sqrtmathbfP_k(k). The matrices mathbfP Q R are the covariance of the estimation error, process noise and sensor noise, respectively.\n\n[3]: Simon, D. 2006, \"Chapter 14: The unscented Kalman filter\" in \"Optimal State Estimation: Kalman, H∞, and Nonlinear Approaches\", John Wiley & Sons, p. 433–459, https://doi.org/10.1002/0470045345.ch14, ISBN9780470045343.\n\n\n\n\n\nupdate_estimate!(estim::ExtendedKalmanFilter, u, ym, d=Float64[])\n\nUpdate ExtendedKalmanFilter state estim.x̂ and covariance estim.P̂.\n\nThe equations are similar to update_estimate!(::KalmanFilter) but with the substitutions mathbfA = F(k) and mathbfC^m = H^m(k):\n\nbeginaligned\n mathbfM(k) = mathbfP_k-1(k)mathbfH^m(k)\n mathbfH^m(k)mathbfP_k-1(k)mathbfH^m(k) + mathbfR^-1 \n mathbfK(k) = mathbfF(k) mathbfM(k) \n mathbfy^m(k) = mathbfh^mBig( mathbfx_k-1(k) mathbfd(k) Big) \n mathbfx_k(k+1) = mathbffBig( mathbfx_k-1(k) mathbfu(k) mathbfd(k) Big)\n + mathbfK(k)mathbfy^m(k) - mathbfy^m(k) \n mathbfP_k(k+1) = mathbfF(k)mathbfP_k-1(k)\n - mathbfM(k)mathbfH^m(k)mathbfP_k-1(k)mathbfF(k) \n + mathbfQ\nendaligned\n\nForwardDiff.jacobian automatically computes the Jacobians:\n\nbeginaligned\n mathbfF(k) = left fracmathbff(mathbfx mathbfu mathbfd)mathbfx right_mathbfx = x_k-1(k) mathbfu = u(k) mathbfd = d(k) \n mathbfH(k) = left fracmathbfh(mathbfx mathbfd)mathbfx right_mathbfx = x_k-1(k) mathbfd = d(k)\nendaligned\n\nThe matrix mathbfH^m is the rows of mathbfH that are measured outputs.\n\n\n\n\n\nupdate_estimate!(estim::Luenberger, u, ym, d=Float64[])\n\nSame than update_estimate!(::SteadyKalmanFilter) but using Luenberger.\n\n\n\n\n\nupdate_estimate!(estim::InternalModel, u, ym, d=Float64[]) -> x̂d\n\nUpdate estim.x̂ \\ x̂d \\ x̂s with current inputs u, measured outputs ym and dist. d.\n\nThe InternalModel updates the deterministic x̂d and stochastic x̂s estimates with:\n\nbeginaligned\n mathbfx_d(k+1) = mathbffBig( mathbfx_d(k) mathbfu(k) mathbfd(k) Big) \n mathbfx_s(k+1) = mathbfA_s x_s(k) + mathbfB_s y_s(k)\nendaligned\n\nThis estimator does not augment the state vector, thus mathbfx = x_d. See init_internalmodel for details. \n\n\n\n\n\n","category":"function"},{"location":"internals/state_estim/#Init-Estimate","page":"State Estimators","title":"Init Estimate","text":"","category":"section"},{"location":"internals/state_estim/","page":"State Estimators","title":"State Estimators","text":"info: Info\nSame as above: the arguments should be called u0, ym0 and d0, strickly speaking.","category":"page"},{"location":"internals/state_estim/","page":"State Estimators","title":"State Estimators","text":"ModelPredictiveControl.init_estimate!","category":"page"},{"location":"internals/state_estim/#ModelPredictiveControl.init_estimate!","page":"State Estimators","title":"ModelPredictiveControl.init_estimate!","text":"init_estimate!(estim::StateEstimator, model::LinModel, u, ym, d)\n\nInit estim.x̂ estimate with the steady-state solution if model is a LinModel.\n\nUsing u, ym and d arguments, the steady-state problem combined to the equality constraint mathbfy^m = mathbfy^m engenders the following system to solve:\n\nbeginbmatrix\n mathbfI - mathbfA \n mathbfC^m\nendbmatrix mathbfx =\nbeginbmatrix\n mathbfB_u u + mathbfB_d d \n mathbfy^m - mathbfD_d^m d\nendbmatrix\n\nin which mathbfC^m D_d^m are the rows of estim.Ĉ, estim.D̂d that correspond to measured outputs mathbfy^m.\n\n\n\n\n\nLeft estim.x̂ estimate unchanged if model is not a LinModel.\n\n\n\n\n\n","category":"function"},{"location":"manual/nonlinmpc/#man_nonlin","page":"Nonlinear Design","title":"Manual: Nonlinear Design","text":"","category":"section"},{"location":"manual/nonlinmpc/#Nonlinear-Model","page":"Nonlinear Design","title":"Nonlinear Model","text":"","category":"section"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"In this example, the goal is to control the angular position θ of a pendulum attached to a motor. Knowing that the manipulated input is the motor torque τ, the I/O vectors are:","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"beginaligned\n mathbfu = beginbmatrix τ endbmatrix \n mathbfy = beginbmatrix θ endbmatrix\nendaligned","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"The plant model is nonlinear:","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"beginaligned\n dotθ(t) = ω(t) \n dotω(t) = -fracgLsinbig( θ(t) big) - fracKm ω(t) + frac1m L^2 τ(t)\nendaligned","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"in which g is the gravitational acceleration, L, the pendulum length, K, the friction coefficient at the pivot point, and m, the mass attached at the end of the pendulum. Here, the explicit Euler method discretizes the system to construct a NonLinModel:","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"using ModelPredictiveControl\nfunction pendulum(par, x, u)\n g, L, K, m = par # [m/s²], [m], [kg/s], [kg]\n θ, ω = x[1], x[2] # [rad], [rad/s]\n τ = u[1] # [N m]\n dθ = ω\n dω = -g/L*sin(θ) - K/m*ω + τ/m/L^2\n return [dθ, dω]\nend\nTs = 0.1 # [s]\npar = (9.8, 0.4, 1.2, 0.3)\nf(x, u, _ ) = x + Ts*pendulum(par, x, u) # Euler method\nh(x, _ ) = [180/π*x[1]] # [°]\nnu, nx, ny = 1, 2, 1\nmodel = NonLinModel(f, h, Ts, nu, nx, ny)","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"The output function mathbfh converts the θ angle to degrees. It is good practice to first simulate model using sim! as a quick sanity check:","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"using Plots\nu = [0.5]\nplot(sim!(model, 60, u), plotu=false)","category":"page"},{"location":"manual/nonlinmpc/#Nonlinear-Model-Predictive-Controller","page":"Nonlinear Design","title":"Nonlinear Model Predictive Controller","text":"","category":"section"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"An UnscentedKalmanFilter estimates the plant state :","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"estim = UnscentedKalmanFilter(model, σQ=[0.1, 0.5], σR=[0.5], nint_ym=[1], σQint_ym=[5.0])","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"The standard deviation of the angular velocity ω is higher here (σQ second value) since dotω(t) equation includes an uncertain parameter: the friction coefficient K. The estimator tuning is tested on a plant simulated with a different K:","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"par_plant = (par[1], par[2], par[3] + 0.25, par[4])\nf_plant(x, u, _) = x + Ts*pendulum(par_plant, x, u)\nplant = NonLinModel(f_plant, h, Ts, nu, nx, ny)\nres = sim!(estim, 60, [0.5], plant=plant, y_noise=[0.5])\nplot(res, plotu=false, plotxwithx̂=true)","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"The estimate x_3 is the integrator state that compensates for static errors (nint_ym and σQint_ym parameters of UnscentedKalmanFilter). The Kalman filter performance seems sufficient for control. As the motor torque is limited to -1.5 to 1.5 N m, we incorporate the input constraints in a NonLinMPC:","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"mpc = NonLinMPC(estim, Hp=20, Hc=4, Mwt=[0.5], Nwt=[2.5], Cwt=Inf)\nmpc = setconstraint!(mpc, umin=[-1.5], umax=[+1.5])","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"We test mpc performance on plant by imposing an angular setpoint of 180° (inverted position):","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"res = sim!(mpc, 60, [180.0], plant=plant, x0=zeros(plant.nx), x̂0=zeros(mpc.estim.nx̂))\nplot(res)","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"The controller seems robust enough to variations on K coefficient. Starting from this inverted position, the closed-loop response to a step disturbances of 10° is also satisfactory:","category":"page"},{"location":"manual/nonlinmpc/","page":"Nonlinear Design","title":"Nonlinear Design","text":"res = sim!(mpc, 60, [180.0], plant=plant, x0=[π, 0], x̂0=[π, 0, 0], y_step=[10])\nplot(res)","category":"page"},{"location":"public/state_estim/#Functions:-State-Estimators","page":"State Estimators","title":"Functions: State Estimators","text":"","category":"section"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"Pages = [\"state_estim.md\"]","category":"page"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"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).","category":"page"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"info: Info\nIf 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 nint_u=0 and nint_ym=0 disable it.","category":"page"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"The estimators are all implemented in the predictor form (a.k.a. observer form), that is, they all estimates at each discrete time k the states of the next period mathbfx_k(k+1)[1]. In contrast, the filter form that estimates mathbfx_k(k) is sometimes slightly more accurate.","category":"page"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"[1]: also denoted mathbfx_k+1k elsewhere.","category":"page"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"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).","category":"page"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"info: Info\nAll the estimators support measured mathbfy^m and unmeasured mathbfy^u model outputs, where mathbfy refers to all of them.","category":"page"},{"location":"public/state_estim/#StateEstimator","page":"State Estimators","title":"StateEstimator","text":"","category":"section"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"StateEstimator","category":"page"},{"location":"public/state_estim/#ModelPredictiveControl.StateEstimator","page":"State Estimators","title":"ModelPredictiveControl.StateEstimator","text":"Abstract supertype of all state estimators.\n\n\n\n(estim::StateEstimator)(d=Float64[])\n\nFunctor allowing callable StateEstimator object as an alias for evaloutput.\n\nExamples\n\njulia> kf = KalmanFilter(setop!(LinModel(tf(3, [10, 1]), 2), yop=[20]));\n\njulia> ŷ = kf() \n1-element Vector{Float64}:\n 20.0\n\n\n\n\n\n","category":"type"},{"location":"public/state_estim/#SteadyKalmanFilter","page":"State Estimators","title":"SteadyKalmanFilter","text":"","category":"section"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"SteadyKalmanFilter","category":"page"},{"location":"public/state_estim/#ModelPredictiveControl.SteadyKalmanFilter","page":"State Estimators","title":"ModelPredictiveControl.SteadyKalmanFilter","text":"SteadyKalmanFilter(model::LinModel; )\n\nConstruct a steady-state Kalman Filter with the LinModel model.\n\nThe steady-state (or asymptotic) Kalman filter is based on the process model :\n\nbeginaligned\n mathbfx(k+1) = \n mathbfA x(k) + mathbfB_u u(k) + mathbfB_d d(k) + mathbfw(k) \n mathbfy^m(k) = mathbfC^m x(k) + mathbfD_d^m d(k) + mathbfv(k) \n mathbfy^u(k) = mathbfC^u x(k) + mathbfD_d^u d(k)\nendaligned\n\nwith sensor mathbfv(k) and process mathbfw(k) noises as uncorrelated zero mean white noise vectors, with a respective covariance of mathbfR and mathbfQ. The arguments are in standard deviations σ, i.e. same units than outputs and states. The matrices mathbfA B_u B_d C D_d 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 mathbfQ = textdiag(Q Q_int_u Q_int_ym) and mathbfR = R. The matrices mathbfC^m D_d^m are the rows of mathbfC D_d that correspond to measured outputs mathbfy^m (and unmeasured ones, for mathbfC^u D_d^u).\n\nArguments\n\nmodel::LinModel : (deterministic) model for the estimations.\ni_ym=1:model.ny : model output indices that are measured mathbfy^m, the rest are unmeasured mathbfy^u.\nσQ=fill(1/model.nx,model.nx) : main diagonal of the process noise covariance mathbfQ of model, specified as a standard deviation vector.\nσR=fill(1,length(i_ym)) : main diagonal of the sensor noise covariance mathbfR of model measured outputs, specified as a standard deviation vector.\nnint_u=0: integrator quantity for the stochastic model of the unmeasured disturbances at the manipulated inputs (vector), use nint_u=0 for no integrator (see Extended Help).\nσQint_u=fill(1,sum(nint_u)): same than σQ but for the unmeasured disturbances at manipulated inputs mathbfQ_int_u (composed of integrators).\nnint_ym=default_nint(model,i_ym,nint_u) : same than nint_u but for the unmeasured disturbances at the measured outputs, use nint_ym=0 for no integrator (see Extended Help).\nσQint_ym=fill(1,sum(nint_ym)) : same than σQ for the unmeasured disturbances at measured outputs mathbfQ_int_ym (composed of integrators).\n\nExamples\n\njulia> model = LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 0.5);\n\njulia> estim = SteadyKalmanFilter(model, i_ym=[2], σR=[1], σQint_ym=[0.01])\nSteadyKalmanFilter estimator with a sample time Ts = 0.5 s, LinModel and:\n 1 manipulated inputs u (0 integrators)\n 3 states x̂\n 1 measured outputs ym (1 integrators)\n 1 unmeasured outputs yu\n 0 measured disturbances d\n\nExtended Help\n\nThe 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:\n\nUse 0 integrator if the model output is already integrating (else it will be unobservable)\nUse 1 integrator if the disturbances on the output are typically \"step-like\"\nUse 2 integrators if the disturbances on the output are typically \"ramp-like\" \n\nThe function init_estimstoch builds the stochastic model for estimation.\n\ntip: Tip\nIncreasing σQint_u and σQint_ym values increases the integral action \"gain\".\n\nThe 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.\n\n\n\n\n\nSteadyKalmanFilter(model, i_ym, nint_u, nint_ym, Q̂, R̂)\n\nConstruct the estimator from the augmented covariance matrices Q̂ and R̂.\n\nThis syntax allows nonzero off-diagonal elements in mathbfQ R.\n\n\n\n\n\n","category":"type"},{"location":"public/state_estim/#KalmanFilter","page":"State Estimators","title":"KalmanFilter","text":"","category":"section"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"KalmanFilter","category":"page"},{"location":"public/state_estim/#ModelPredictiveControl.KalmanFilter","page":"State Estimators","title":"ModelPredictiveControl.KalmanFilter","text":"KalmanFilter(model::LinModel; )\n\nConstruct a time-varying Kalman Filter with the LinModel model.\n\nThe process model is identical to SteadyKalmanFilter. The matrix mathbfP_k(k+1) is the estimation error covariance of model states augmented with the stochastic ones (specified by nint_ym). Three keyword arguments modify its initial value with mathbfP_-1(0) = mathrmdiag mathbfP(0) mathbfP_int_u(0) mathbfP_int_ym(0) .\n\nArguments\n\nmodel::LinModel : (deterministic) model for the estimations.\nσP0=fill(1/model.nx,model.nx) : main diagonal of the initial estimate covariance mathbfP(0), specified as a standard deviation vector.\nσP0int_u=fill(1,sum(nint_u)) : same than σP0 but for the unmeasured disturbances at manipulated inputs mathbfP_int_u(0) (composed of integrators).\nσP0int_ym=fill(1,sum(nint_ym)) : same than σP0 but for the unmeasured disturbances at measured outputs mathbfP_int_ym(0) (composed of integrators).\n of SteadyKalmanFilter constructor.\n\nExamples\n\njulia> model = LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 0.5);\n\njulia> estim = KalmanFilter(model, i_ym=[2], σR=[1], σP0=[100, 100], σQint_ym=[0.01])\nKalmanFilter estimator with a sample time Ts = 0.5 s, LinModel and:\n 1 manipulated inputs u (0 integrators)\n 3 states x̂\n 1 measured outputs ym (1 integrators)\n 1 unmeasured outputs yu\n 0 measured disturbances d\n\n\n\n\n\nKalmanFilter(model, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂)\n\nConstruct the estimator from the augmented covariance matrices P̂0, Q̂ and R̂.\n\nThis syntax allows nonzero off-diagonal elements in mathbfP_-1(0) mathbfQ R.\n\n\n\n\n\n","category":"type"},{"location":"public/state_estim/#Luenberger","page":"State Estimators","title":"Luenberger","text":"","category":"section"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"Luenberger","category":"page"},{"location":"public/state_estim/#ModelPredictiveControl.Luenberger","page":"State Estimators","title":"ModelPredictiveControl.Luenberger","text":"Luenberger(\n model::LinModel; \n i_ym = 1:model.ny, \n nint_u = 0,\n nint_ym = default_nint(model, i_ym),\n p̂ = 1e-3*(1:(model.nx + sum(nint_u) + sum(nint_ym))) .+ 0.5\n)\n\nConstruct a Luenberger observer with the LinModel model.\n\ni_ym provides the model output indices that are measured mathbfy^m, the rest are unmeasured mathbfy^u. 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_ym) elements specifying the observer poles/eigenvalues (near z=05 by default). The method computes the observer gain K̂ with place.\n\nExamples\n\njulia> model = LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 0.5);\n\njulia> estim = Luenberger(model, nint_ym=[1, 1], p̂=[0.61, 0.62, 0.63, 0.64])\nLuenberger estimator with a sample time Ts = 0.5 s, LinModel and:\n 1 manipulated inputs u (0 integrators)\n 4 states x̂\n 2 measured outputs ym (2 integrators)\n 0 unmeasured outputs yu\n 0 measured disturbances d\n\n\n\n\n\n","category":"type"},{"location":"public/state_estim/#UnscentedKalmanFilter","page":"State Estimators","title":"UnscentedKalmanFilter","text":"","category":"section"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"UnscentedKalmanFilter","category":"page"},{"location":"public/state_estim/#ModelPredictiveControl.UnscentedKalmanFilter","page":"State Estimators","title":"ModelPredictiveControl.UnscentedKalmanFilter","text":"UnscentedKalmanFilter(model::SimModel; )\n\nConstruct an unscented Kalman Filter with the SimModel model.\n\nBoth LinModel and NonLinModel are supported. The unscented Kalman filter is based on the process model :\n\nbeginaligned\n mathbfx(k+1) = mathbffBig(mathbfx(k) mathbfu(k) mathbfd(k)Big) \n + mathbfw(k) \n mathbfy^m(k) = mathbfh^mBig(mathbfx(k) mathbfd(k)Big) + mathbfv(k) \n mathbfy^u(k) = mathbfh^uBig(mathbfx(k) mathbfd(k)Big) \nendaligned\n\nSee SteadyKalmanFilter for details on mathbfv(k) mathbfw(k) noises and mathbfR mathbfQ covariances. The functions mathbff h 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 mathbfh^m function represents the measured outputs of mathbfh function (and unmeasured ones, for mathbfh^u).\n\nArguments\n\nmodel::SimModel : (deterministic) model for the estimations.\nα=1e-3 : alpha parameter, spread of the state distribution (0 α 1).\nβ=2 : beta parameter, skewness and kurtosis of the states distribution (β 0).\nκ=0 : kappa parameter, another spread parameter (0 κ 3).\n of SteadyKalmanFilter constructor.\n of KalmanFilter constructor.\n\nExamples\n\njulia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1);\n\njulia> estim = UnscentedKalmanFilter(model, σR=[1], nint_ym=[2], σP0int_ym=[1, 1])\nUnscentedKalmanFilter estimator with a sample time Ts = 10.0 s, NonLinModel and:\n 1 manipulated inputs u (0 integrators)\n 3 states x̂\n 1 measured outputs ym (2 integrators)\n 0 unmeasured outputs yu\n 0 measured disturbances d\n\nExtended Help\n\nThe 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.\n\n\n\n\n\nUnscentedKalmanFilter{M<:SimModel}(model::M, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂, α, β, κ)\n\nConstruct the estimator from the augmented covariance matrices P̂0, Q̂ and R̂.\n\nThis syntax allows nonzero off-diagonal elements in mathbfP_-1(0) mathbfQ R.\n\n\n\n\n\n","category":"type"},{"location":"public/state_estim/#ExtendedKalmanFilter","page":"State Estimators","title":"ExtendedKalmanFilter","text":"","category":"section"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"ExtendedKalmanFilter","category":"page"},{"location":"public/state_estim/#ModelPredictiveControl.ExtendedKalmanFilter","page":"State Estimators","title":"ModelPredictiveControl.ExtendedKalmanFilter","text":"ExtendedKalmanFilter(model::SimModel; )\n\nConstruct an extended Kalman Filter with the SimModel model.\n\nBoth LinModel and NonLinModel are supported. The process model is identical to UnscentedKalmanFilter. The Jacobians of the augmented model mathbff h are computed with ForwardDiff.jl automatic differentiation.\n\nwarning: Warning\nSee Extended Help if you get an error like: MethodError: no method matching (::var\"##\")(::Vector{ForwardDiff.Dual}).\n\nArguments\n\nmodel::SimModel : (deterministic) model for the estimations.\n of SteadyKalmanFilter constructor.\n of KalmanFilter constructor.\n\nExamples\n\njulia> model = NonLinModel((x,u,_)->0.2x+u, (x,_)->-3x, 5.0, 1, 1, 1);\n\njulia> estim = ExtendedKalmanFilter(model, σQ=[2], σQint_ym=[2], σP0=[0.1], σP0int_ym=[0.1])\nExtendedKalmanFilter estimator with a sample time Ts = 5.0 s, NonLinModel and:\n 1 manipulated inputs u (0 integrators)\n 2 states x̂\n 1 measured outputs ym (1 integrators)\n 0 unmeasured outputs yu\n 0 measured disturbances d\n\nExtended Help\n\nAutomatic differentiation (AD) allows exact Jacobians. The NonLinModel f and h functions must be compatible with this feature though. See Automatic differentiation for common mistakes when writing these functions.\n\n\n\n\n\nExtendedKalmanFilter{M<:SimModel}(model::M, i_ym, nint_u, nint_ym, P̂0, Q̂, R̂)\n\nConstruct the estimator from the augmented covariance matrices P̂0, Q̂ and R̂.\n\nThis syntax allows nonzero off-diagonal elements in mathbfP_-1(0) mathbfQ R.\n\n\n\n\n\n","category":"type"},{"location":"public/state_estim/#InternalModel","page":"State Estimators","title":"InternalModel","text":"","category":"section"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"InternalModel","category":"page"},{"location":"public/state_estim/#ModelPredictiveControl.InternalModel","page":"State Estimators","title":"ModelPredictiveControl.InternalModel","text":"InternalModel(model::SimModel; i_ym=1:model.ny, stoch_ym=ss(1,1,1,1,model.Ts).*I)\n\nConstruct an internal model estimator based on model (LinModel or NonLinModel).\n\ni_ym provides the model output indices that are measured mathbfy^m, the rest are unmeasured mathbfy^u. model evaluates the deterministic predictions mathbfy_d, and stoch_ym, the stochastic predictions of the measured outputs mathbfy_s^m (the unmeasured ones being mathbfy_s^u=0). The predicted outputs sum both values : mathbfy = y_d + y_s.\n\nwarning: Warning\nInternalModel estimator does not work if model is integrating or unstable. The constructor verifies these aspects for LinModel but not for NonLinModel. Uses any other state estimator in such cases.\n\nExamples\n\njulia> estim = InternalModel(LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 0.5), i_ym=[2])\nInternalModel estimator with a sample time Ts = 0.5 s, LinModel and:\n 1 manipulated inputs u\n 2 states x̂\n 1 measured outputs ym\n 1 unmeasured outputs yu\n 0 measured disturbances d\n\nExtended Help\n\nstoch_ym is a TransferFunction or StateSpace object that models disturbances on mathbfy^m. Its input is a hypothetical zero mean white noise vector. stoch_ym supposes 1 integrator per measured outputs by default, assuming that the current stochastic estimate mathbfy_s^m(k) = mathbfy^m(k) - mathbfy_d^m(k) is constant in the future. This is the dynamic matrix control (DMC) strategy, which is simple but sometimes too aggressive. Additional poles and zeros in stoch_ym can mitigate this.\n\n\n\n\n\n","category":"type"},{"location":"public/state_estim/#Default-model-augmentation","page":"State Estimators","title":"Default model augmentation","text":"","category":"section"},{"location":"public/state_estim/","page":"State Estimators","title":"State Estimators","text":"default_nint","category":"page"},{"location":"public/state_estim/#ModelPredictiveControl.default_nint","page":"State Estimators","title":"ModelPredictiveControl.default_nint","text":"default_nint(model::LinModel, i_ym=1:model.ny, nint_u=0)\n\nGet default integrator quantity per measured outputs nint_ym for LinModel.\n\nThe measured output mathbfy^m indices are specified by i_ym argument. By default, one integrator is added on each measured outputs. If mathbfA C matrices of the augmented model become unobservable, the integrator is removed. This approach works well for stable, integrating and unstable model (see Examples).\n\nExamples\n\njulia> model = LinModel(append(tf(3, [10, 1]), tf(2, [1, 0]), tf(4,[-5, 1])), 1.0);\n\njulia> nint_ym = default_nint(model)\n3-element Vector{Int64}:\n 1\n 0\n 1\n\n\n\n\n\ndefault_nint(model::SimModel, i_ym=1:model.ny, nint_u=0)\n\nOne integrator on each measured output by default if model is not a LinModel.\n\n\n\n\n\n","category":"function"},{"location":"func_index/#Index","page":"Index","title":"Index","text":"","category":"section"},{"location":"func_index/","page":"Index","title":"Index","text":"","category":"page"},{"location":"manual/linmpc/#man_lin","page":"Linear Design","title":"Manual: Linear Design","text":"","category":"section"},{"location":"manual/linmpc/#Linear-Model","page":"Linear Design","title":"Linear Model","text":"","category":"section"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"The example considers a continuously stirred-tank reactor (CSTR) with a cold and hot water inlet as a plant. The water flows out of an opening at the bottom of the tank. The manipulated inputs are the cold u_c and hot u_h water flow rates, and the measured outputs are the liquid level y_L and temperature y_T:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"beginaligned\n mathbfu = beginbmatrix u_c u_h endbmatrix \n mathbfy = beginbmatrix y_L y_T endbmatrix\nendaligned","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"At the steady-state operating points:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"beginaligned\n mathbfu_op = beginbmatrix 20 20 endbmatrix \n mathbfy_op = beginbmatrix 50 30 endbmatrix \nendaligned","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"the following linear model accurately describes the plant dynamics:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"beginbmatrix\n y_L(s) y_T(s)\nendbmatrix = \nbeginbmatrix\n frac19018s + 1 frac19018s + 1 3pt\n frac-0748s + 1 frac0748s + 1\nendbmatrix\nbeginbmatrix\n u_c(s) u_h(s)\nendbmatrix","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"We first need to construct a LinModel objet with setop! to handle the operating points:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"using ModelPredictiveControl, ControlSystemsBase\nsys = [ tf(1.90, [18, 1]) tf(1.90, [18, 1]);\n tf(-0.74,[8, 1]) tf(0.74, [8, 1]) ]\nTs = 2.0\nmodel = setop!(LinModel(sys, Ts), uop=[20, 20], yop=[50, 30])","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"The model object will be used for two purposes : to construct our controller, and as a plant simulator to test the design.","category":"page"},{"location":"manual/linmpc/#Linear-Model-Predictive-Controller","page":"Linear Design","title":"Linear Model Predictive Controller","text":"","category":"section"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"A linear model predictive controller (MPC) will control both the water level y_L and temperature y_T in the tank, at a sampling time of 4 s. The tank level should also never fall below 45:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"y_L 45","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"We design our LinMPC controllers by including the linear level constraint with setconstraint! (±Inf values should be used when there is no bound):","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"mpc = LinMPC(model, Hp=15, Hc=2, Mwt=[1, 1], Nwt=[0.1, 0.1])\nmpc = setconstraint!(mpc, ymin=[45, -Inf])","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"in which Hp and Hc keyword arguments are respectively the predictive and control horizons, and Mwt and Nwt, the output setpoint tracking and move suppression weights. By default, LinMPC controllers use OSQP to solve the problem, soft constraints on output predictions mathbfy to ensure feasibility, and a SteadyKalmanFilter to estimate the plant states. An attentive reader will also notice that the Kalman filter estimates two additional states compared to the plant model. These are the integrators for the unmeasured plant disturbances, and they are automatically added to the model outputs by default if feasible (see SteadyKalmanFilter for details).","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"Before closing the loop, we call initstate! with the actual plant inputs and measurements to ensure a bumpless transfer. Since model simulates our plant here, its output will initialize the states. LinModel objects are callable for this purpose (an alias for evaloutput):","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"u, y = model.uop, model() # or equivalently : y = evaloutput(model)\ninitstate!(mpc, u, y)\nnothing # hide","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"We can then close the loop and test mpc performance on the simulator by imposing step changes on output setpoints mathbfr_y and on a load disturbance u_l:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"function test_mpc(mpc, model)\n N = 200\n ry, ul = [50, 30], 0\n u_data = zeros(model.nu, N)\n y_data = zeros(model.ny, N)\n ry_data = zeros(model.ny, N)\n for k = 0:N-1\n k == 50 && (ry = [50, 35])\n k == 100 && (ry = [54, 30])\n k == 150 && (ul = -20)\n y = model() # simulated measurements\n u = mpc(ry) # or equivalently : u = moveinput!(mpc, ry)\n u_data[:,k+1] = u\n y_data[:,k+1] = y\n ry_data[:,k+1] = ry \n updatestate!(mpc, u, y) # update mpc state estimate\n updatestate!(model, u + [0; ul]) # update simulator with the load disturbance\n end\n return u_data, y_data, ry_data\nend\nu_data, y_data, ry_data = test_mpc(mpc, model)\nt_data = Ts*(0:(size(y_data,2)-1))\nnothing # hide","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"The LinMPC objects are also callable as an alternative syntax for moveinput!. Calling updatestate! on the mpc object updates its internal state for the NEXT control period (this is by design, see Functions: State Estimators for justifications). That is why the call is done at the end of the for loop. The same logic applies for model.","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"Lastly, we plot the closed-loop test with the Plots package:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"using Plots\nfunction plot_data(t_data, u_data, y_data, ry_data)\n p1 = plot(t_data, y_data[1,:], label=\"meas.\"); ylabel!(\"level\")\n plot!(t_data, ry_data[1,:], label=\"setpoint\", linestyle=:dash, linetype=:steppost)\n plot!(t_data, fill(45,size(t_data)), label=\"min\", linestyle=:dot, linewidth=1.5)\n p2 = plot(t_data, y_data[2,:], label=\"meas.\", legend=:topleft); ylabel!(\"temp.\")\n plot!(t_data, ry_data[2,:],label=\"setpoint\", linestyle=:dash, linetype=:steppost)\n p3 = plot(t_data,u_data[1,:],label=\"cold\", linetype=:steppost); ylabel!(\"flow rate\")\n plot!(t_data,u_data[2,:],label=\"hot\", linetype=:steppost); xlabel!(\"time (s)\")\n return plot(p1, p2, p3, layout=(3,1), fmt=:svg)\nend\nplot_data(t_data, u_data, y_data, ry_data)","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"For some situations, when LinMPC matrices are small/medium and dense, DAQP optimizer may be more efficient. To install it, run:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"using Pkg; Pkg.add(\"DAQP\")","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"Also, compared to the default setting, adding the integrating states at the model inputs may improve the closed-loop performance. Load disturbances are indeed very frequent in many real-life control problems. Constructing a LinMPC with DAQP and input integrators:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"using JuMP, DAQP\ndaqp = Model(DAQP.Optimizer)\nestim = SteadyKalmanFilter(model, nint_u=[1, 1], nint_ym=[0, 0])\nmpc2 = LinMPC(estim, Hp=15, Hc=2, Mwt=[1, 1], Nwt=[0.1, 0.1], optim=daqp)\nmpc2 = setconstraint!(mpc2, ymin=[45, -Inf])","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"leads to similar computational times, but it does accelerate the rejection of the load disturbance and eliminates the level constraint violation:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"setstate!(model, zeros(model.nx))\nu, y = model.uop, model()\ninitstate!(mpc2, u, y)\nu_data, y_data, ry_data = test_mpc(mpc2, model)\nplot_data(t_data, u_data, y_data, ry_data)","category":"page"},{"location":"manual/linmpc/#Adding-Feedforward-Compensation","page":"Linear Design","title":"Adding Feedforward Compensation","text":"","category":"section"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"Suppose that the load disturbance u_l of the last section is in fact caused by a separate hot water pipe that discharges into the tank. Measuring this flow rate allows us to incorporate feedforward compensation in the controller. The new plant model is:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"beginbmatrix\n y_L(s) y_T(s)\nendbmatrix = \nbeginbmatrix\n frac19018s + 1 frac19018s + 1 frac19018s + 1 3pt\n frac-0748s + 1 frac0748s + 1 frac0748s + 1\nendbmatrix\nbeginbmatrix\n u_c(s) u_h(s) u_l(s)\nendbmatrix","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"We need to construct a new LinModel that includes the measured disturbance mathbfd = u_l and the operating point mathbfd_op = 20:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"sys_ff = [sys sys[1:2, 2]]\nmodel_ff = setop!(LinModel(sys_ff, Ts, i_d=[3]), uop=[20, 20], yop=[50, 30], dop=[20])","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"A LinMPC controller is constructed on this model:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"mpc_ff = LinMPC(model_ff, Hp=15, Hc=2, Mwt=[1, 1], Nwt=[0.1, 0.1])\nmpc_ff = setconstraint!(mpc_ff, ymin=[45, -Inf])","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"A new test function that feeds the measured disturbance mathbfd to the controller is also required:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"function test_mpc_ff(mpc_ff, model)\n N = 200\n ry, ul = [50, 30], 0\n dop = mpc_ff.estim.model.dop\n u_data = zeros(model.nu, N)\n y_data = zeros(model.ny, N)\n ry_data = zeros(model.ny, N)\n for k = 0:N-1\n k == 50 && (ry = [50, 35])\n k == 100 && (ry = [54, 30])\n k == 150 && (ul = -20)\n d = ul .+ dop # simulated measured disturbance\n y = model() # simulated measurements\n u = mpc_ff(ry, d) # also feed the measured disturbance d to the controller\n u_data[:,k+1] = u\n y_data[:,k+1] = y\n ry_data[:,k+1] = ry \n updatestate!(mpc_ff, u, y, d) # update estimate with the measured disturbance d\n updatestate!(model, u + [0; ul]) # update simulator\n end\n return u_data, y_data, ry_data\nend\nnothing # hide","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"The new feedforward compensation is able to almost perfectly reject the load disturbance:","category":"page"},{"location":"manual/linmpc/","page":"Linear Design","title":"Linear Design","text":"setstate!(model, zeros(model.nx))\nu, y, d = model.uop, model(), mpc_ff.estim.model.dop\ninitstate!(mpc_ff, u, y, d)\nu_data, y_data, ry_data = test_mpc_ff(mpc_ff, model)\nplot_data(t_data, u_data, y_data, ry_data)","category":"page"},{"location":"public/sim_model/#func_sim_model","page":"Plant Models","title":"Functions: Plant Models","text":"","category":"section"},{"location":"public/sim_model/","page":"Plant Models","title":"Plant Models","text":"Pages = [\"sim_model.md\"]","category":"page"},{"location":"public/sim_model/","page":"Plant Models","title":"Plant Models","text":"The SimModel types represents discrete state-space models that can be used to construct StateEstimators and PredictiveControllers, or as plant simulators by calling evaloutput and updatestate! methods on SimModel instances (to test estimator/controller designs). For time simulations, the states x are stored inside SimModel instances. Use setstate! method to manually modify them.","category":"page"},{"location":"public/sim_model/#SimModel","page":"Plant Models","title":"SimModel","text":"","category":"section"},{"location":"public/sim_model/","page":"Plant Models","title":"Plant Models","text":"SimModel","category":"page"},{"location":"public/sim_model/#ModelPredictiveControl.SimModel","page":"Plant Models","title":"ModelPredictiveControl.SimModel","text":"Abstract supertype of LinModel and NonLinModel types.\n\n\n\n(model::SimModel)(d=Float64[])\n\nFunctor allowing callable SimModel object as an alias for evaloutput.\n\nExamples\n\njulia> model = NonLinModel((x,u,_)->-x + u, (x,_)->x .+ 20, 10.0, 1, 1, 1);\n\njulia> y = model()\n1-element Vector{Float64}:\n 20.0\n\n\n\n\n\n","category":"type"},{"location":"public/sim_model/#LinModel","page":"Plant Models","title":"LinModel","text":"","category":"section"},{"location":"public/sim_model/","page":"Plant Models","title":"Plant Models","text":"LinModel","category":"page"},{"location":"public/sim_model/#ModelPredictiveControl.LinModel","page":"Plant Models","title":"ModelPredictiveControl.LinModel","text":"LinModel(sys::StateSpace[, Ts]; i_u=1:size(sys,2), i_d=Int[])\n\nConstruct a linear model from state-space model sys with sampling time Ts in second.\n\nTs can be omitted when sys is discrete-time. Its state-space matrices are:\n\nbeginaligned\n mathbfx(k+1) = mathbfA x(k) + mathbfB z(k) \n mathbfy(k) = mathbfC x(k) + mathbfD z(k)\nendaligned\n\nwith the state mathbfx and output mathbfy vectors. The mathbfz vector comprises the manipulated inputs mathbfu and measured disturbances mathbfd, in any order. i_u provides the indices of mathbfz that are manipulated, and i_d, the measured disturbances. See Extended Help if sys is continuous-time, or discrete-time with Ts ≠ sys.Ts.\n\nSee also ss, tf.\n\nExamples\n\njulia> model = LinModel(ss(0.4, 0.2, 0.3, 0, 0.1))\nDiscrete-time linear model with a sample time Ts = 0.1 s and:\n 1 manipulated inputs u\n 1 states x\n 1 outputs y\n 0 measured disturbances d\n\nExtended Help\n\nState-space matrices are similar if sys is continuous (replace mathbfx(k+1) with mathbfx(t) and k with t on the LHS). In such a case, it's discretized with c2d and :zoh for manipulated inputs, and :tustin, for measured disturbances. Lastly, if sys is discrete and the provided argument Ts ≠ sys.Ts, the system is resampled by using the aforementioned discretization methods.\n\nNote that the constructor transforms the system to its minimal realization using minreal for controllability/observability. As a consequence, the final state-space representation may be different from the one provided in sys. It is also converted into a more practical form (mathbfD_u=0 because of the zero-order hold):\n\nbeginaligned\n mathbfx(k+1) = mathbfA x(k) + mathbfB_u u(k) + mathbfB_d d(k) \n mathbfy(k) = mathbfC x(k) + mathbfD_d d(k)\nendaligned\n\nUse the syntax LinModel(A,Bu,C,Bd,Dd,Ts,nu,nx,ny,nd) to force a specific state- space representation.\n\n\n\n\n\nLinModel(sys::TransferFunction[, Ts]; i_u=1:size(sys,2), i_d=Int[])\n\nConvert to minimal realization state-space when sys is a transfer function.\n\nsys is equal to fracmathbfy(s)mathbfz(s) for continuous-time, and fracmathbfy(z)mathbfz(z), for discrete-time.\n\nExamples\n\njulia> model = LinModel([tf(3, [30, 1]) tf(-2, [5, 1])], 0.5, i_d=[2])\nDiscrete-time linear model with a sample time Ts = 0.5 s and:\n 1 manipulated inputs u\n 2 states x\n 1 outputs y\n 1 measured disturbances d\n\n\n\n\n\nLinModel(sys::DelayLtiSystem, Ts; i_u=1:size(sys,2), i_d=Int[])\n\nDiscretize with zero-order hold when sys is a continuous system with delays.\n\nThe delays must be multiples of the sample time Ts.\n\nExamples\n\njulia> model = LinModel(tf(4, [10, 1])*delay(2), 0.5)\nDiscrete-time linear model with a sample time Ts = 0.5 s and:\n 1 manipulated inputs u\n 5 states x\n 1 outputs y\n 0 measured disturbances d\n\n\n\n\n\nLinModel(A, Bu, C, Bd, Dd, Ts, nu, nx, ny, nd)\n\nConstruct the model from the discrete state-space matrices A, Bu, C, Bd, Dd directly.\n\nThis syntax do not modify the state-space representation provided in argument (minreal is not called). Care must be taken to ensure that the model is controllable and observable.\n\n\n\n\n\n","category":"type"},{"location":"public/sim_model/#NonLinModel","page":"Plant Models","title":"NonLinModel","text":"","category":"section"},{"location":"public/sim_model/","page":"Plant Models","title":"Plant Models","text":"NonLinModel","category":"page"},{"location":"public/sim_model/#ModelPredictiveControl.NonLinModel","page":"Plant Models","title":"ModelPredictiveControl.NonLinModel","text":"NonLinModel(f::Function, h::Function, Ts, nu, nx, ny, nd=0)\n\nConstruct a nonlinear model from discrete-time state-space functions f and h.\n\nThe state update mathbff and output mathbfh functions are defined as :\n\n beginaligned\n mathbfx(k+1) = mathbffBig( mathbfx(k) mathbfu(k) mathbfd(k) Big) \n mathbfy(k) = mathbfhBig( mathbfx(k) mathbfd(k) Big)\n endaligned\n\nTs is the sampling time in second. nu, nx, ny and nd are the respective number of manipulated inputs, states, outputs and measured disturbances. \n\ntip: Tip\nReplace the d argument with _ if nd = 0 (see Examples below).\n\nNonlinear continuous-time state-space functions are not supported for now. In such a case, manually call a differential equation solver in f (see Manual).\n\nwarning: Warning\nf and h must be pure Julia functions to use the model in NonLinMPC, ExtendedKalmanFilter and MovingHorizonEstimator.\n\nSee also LinModel.\n\nExamples\n\njulia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1)\nDiscrete-time nonlinear model with a sample time Ts = 10.0 s and:\n 1 manipulated inputs u\n 1 states x\n 1 outputs y\n 0 measured disturbances d\n\n\n\n\n\n","category":"type"},{"location":"public/sim_model/#Set-Operating-Points","page":"Plant Models","title":"Set Operating Points","text":"","category":"section"},{"location":"public/sim_model/","page":"Plant Models","title":"Plant Models","text":"setop!","category":"page"},{"location":"public/sim_model/#ModelPredictiveControl.setop!","page":"Plant Models","title":"ModelPredictiveControl.setop!","text":"setop!(model::SimModel; uop=nothing, yop=nothing, dop=nothing)\n\nSet model inputs uop, outputs yop and measured disturbances dop operating points.\n\nThe state-space model with operating points (a.k.a. nominal values) is:\n\nbeginaligned\n mathbfx(k+1) = mathbfA x(k) + mathbfB_u u_0(k) + mathbfB_d d_0(k) \n mathbfy_0(k) = mathbfC x(k) + mathbfD_d d_0(k)\nendaligned\n\nin which the uop, yop and dop vectors evaluate:\n\nbeginaligned\n mathbfu_0(k) = mathbfu(k) - mathbfu_op \n mathbfy_0(k) = mathbfy(k) - mathbfy_op \n mathbfd_0(k) = mathbfd(k) - mathbfd_op \nendaligned\n\nThe structure is similar if model is a NonLinModel:\n\nbeginaligned\n mathbfx(k+1) = mathbffBig(mathbfx(k) mathbfu_0(k) mathbfd_0(k)Big)\n mathbfy_0(k) = mathbfhBig(mathbfx(k) mathbfd_0(k)Big)\nendaligned\n\nExamples\n\njulia> model = setop!(LinModel(tf(3, [10, 1]), 2.0), uop=[50], yop=[20])\nDiscrete-time linear model with a sample time Ts = 2.0 s and:\n 1 manipulated inputs u\n 1 states x\n 1 outputs y\n 0 measured disturbances d\n\n\n\n\n\n","category":"function"},{"location":"public/predictive_control/#Functions:-Predictive-Controllers","page":"Predictive Controllers","title":"Functions: Predictive Controllers","text":"","category":"section"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"Pages = [\"predictive_control.md\"]","category":"page"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"All the predictive controllers in this module rely on a state estimator to compute the predictions. The default LinMPC estimator is a SteadyKalmanFilter, and NonLinMPC with nonlinear models, an UnscentedKalmanFilter. For simpler and more classical designs, an InternalModel structure is also available, that assumes by default that the current model mismatch estimation is constant in the future (same approach as dynamic matrix control, DMC).","category":"page"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"info: Info\nThe nomenclature use capital letters for time series (and matrices) and hats for the predictions (and estimations, for state estimators).","category":"page"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"To be precise, at the kth control period, the vectors that encompass the future measured disturbances mathbfd, model outputs mathbfy and setpoints mathbfr_y over the prediction horizon H_p are defined as:","category":"page"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":" mathbfD = beginbmatrix\n mathbfd(k+1) mathbfd(k+2) vdots mathbfd(k+H_p)\n endbmatrix quad\n mathbfY = beginbmatrix\n mathbfy(k+1) mathbfy(k+2) vdots mathbfy(k+H_p)\n endbmatrix quad textand quad\n mathbfR_y = beginbmatrix\n mathbfr_y(k+1) mathbfr_y(k+2) vdots mathbfr_y(k+H_p)\n endbmatrix","category":"page"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"The vectors for the manipulated input mathbfu are shifted by one time step:","category":"page"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":" mathbfU = beginbmatrix\n mathbfu(k+0) mathbfu(k+1) vdots mathbfu(k+H_p-1)\n endbmatrix quad textand quad\n mathbfR_u = beginbmatrix\n mathbfr_u mathbfr_u vdots mathbfr_u\n endbmatrix","category":"page"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"assuming constant input setpoints at mathbfr_u. Defining the manipulated input increment as mathbfΔu(k+j) = mathbfu(k+j) - mathbfu(k+j-1), the control horizon H_c enforces that mathbfΔu(k+j) = mathbf0 for j H_c. For this reason, the vector that collects them is truncated up to k+H_c-1:","category":"page"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":" mathbfΔU =\n beginbmatrix\n mathbfΔu(k+0) mathbfΔu(k+1) vdots mathbfΔu(k+H_c-1)\n endbmatrix","category":"page"},{"location":"public/predictive_control/#PredictiveController","page":"Predictive Controllers","title":"PredictiveController","text":"","category":"section"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"PredictiveController","category":"page"},{"location":"public/predictive_control/#ModelPredictiveControl.PredictiveController","page":"Predictive Controllers","title":"ModelPredictiveControl.PredictiveController","text":"Abstract supertype of all predictive controllers.\n\n\n\n(mpc::PredictiveController)(ry, d=Float64[]; kwargs...)\n\nFunctor allowing callable PredictiveController object as an alias for moveinput!.\n\nExamples\n\njulia> mpc = LinMPC(LinModel(tf(5, [2, 1]), 3), Nwt=[0], Hp=1000, Hc=1);\n\njulia> u = mpc([5]); round.(u, digits=3)\n1-element Vector{Float64}:\n 1.0\n\n\n\n\n\n","category":"type"},{"location":"public/predictive_control/#LinMPC","page":"Predictive Controllers","title":"LinMPC","text":"","category":"section"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"LinMPC","category":"page"},{"location":"public/predictive_control/#ModelPredictiveControl.LinMPC","page":"Predictive Controllers","title":"ModelPredictiveControl.LinMPC","text":"LinMPC(model::LinModel; )\n\nConstruct a linear predictive controller based on LinModel model.\n\nThe controller minimizes the following objective function at each discrete time k:\n\nmin_mathbfΔU ϵ mathbf(R_y - Y) mathbfM_H_p mathbf(R_y - Y) \n + mathbf(ΔU) mathbfN_H_c mathbf(ΔU) \n + mathbf(R_u - U) mathbfL_H_p mathbf(R_u - U) \n + C ϵ^2\n\nin which the weight matrices are repeated H_p or H_c times:\n\nbeginaligned\n mathbfM_H_p = textdiagmathbf(MMM) \n mathbfN_H_c = textdiagmathbf(NNN) \n mathbfL_H_p = textdiagmathbf(LLL) \nendaligned\n\nThe mathbfΔU vector includes the manipulated input increments mathbfΔu(k+j) = mathbfu(k+j) - mathbfu(k+j-1) from j=0 to H_c-1, the mathbfY vector, the output predictions mathbfy(k+j) from j=1 to H_p, and the mathbfU vector, the manipulated inputs mathbfu(k+j) from j=0 to H_p-1. The manipulated input setpoint predictions mathbfR_u are constant at mathbfr_u. See Extended Help for a detailed nomenclature.\n\nThis method uses the default state estimator, a SteadyKalmanFilter with default arguments.\n\nArguments\n\nmodel::LinModel : model used for controller predictions and state estimations.\nHp=10+nk: prediction horizon H_p, nk is the number of delays in model.\nHc=2 : control horizon H_c.\nMwt=fill(1.0,model.ny) : main diagonal of mathbfM weight matrix (vector).\nNwt=fill(0.1,model.nu) : main diagonal of mathbfN weight matrix (vector).\nLwt=fill(0.0,model.nu) : main diagonal of mathbfL weight matrix (vector).\nCwt=1e5 : slack variable weight C (scalar), use Cwt=Inf for hard constraints only.\nru=model.uop : manipulated input setpoints mathbfr_u (vector).\noptim=JuMP.Model(OSQP.MathOptInterfaceOSQP.Optimizer) : quadratic optimizer used in the predictive controller, provided as a JuMP.Model (default to OSQP.jl optimizer).\n\nExamples\n\njulia> model = LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 4);\n\njulia> mpc = LinMPC(model, Mwt=[0, 1], Nwt=[0.5], Hp=30, Hc=1)\nLinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, SteadyKalmanFilter estimator and:\n 30 prediction steps Hp\n 1 control steps Hc\n 1 manipulated inputs u (0 integrators)\n 4 states x̂\n 2 measured outputs ym (2 integrators)\n 0 unmeasured outputs yu\n 0 measured disturbances d\n\nExtended Help\n\nManipulated inputs setpoints mathbfr_u are not common but they can be interesting for over-actuated systems, when nu > ny (e.g. prioritize solutions with lower economical costs). The default Lwt value implies that this feature is disabled by default.\n\nThe objective function follows this nomenclature:\n\nVARIABLE DESCRIPTION SIZE\nH_p prediction horizon (integer) ()\nH_c control horizon (integer) ()\nmathbfΔU manipulated input increments over H_c (nu*Hc,)\nmathbfY predicted outputs over H_p (ny*Hp,)\nmathbfU manipulated inputs over H_p (nu*Hp,)\nmathbfR_y predicted output setpoints over H_p (ny*Hp,)\nmathbfR_u predicted manipulated input setpoints over H_p (nu*Hp,)\nmathbfM output setpoint tracking weights (ny*Hp, ny*Hp)\nmathbfN manipulated input increment weights (nu*Hc, nu*Hc)\nmathbfL manipulated input setpoint tracking weights (nu*Hp, nu*Hp)\nC slack variable weight ()\nϵ slack variable for constraint softening ()\n\n\n\n\n\nLinMPC(estim::StateEstimator; )\n\nUse custom state estimator estim to construct LinMPC.\n\nestim.model must be a LinModel. Else, a NonLinMPC is required. \n\nExamples\n\njulia> estim = KalmanFilter(LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 4), i_ym=[2]);\n\njulia> mpc = LinMPC(estim, Mwt=[0, 1], Nwt=[0.5], Hp=30, Hc=1)\nLinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, KalmanFilter estimator and:\n 30 prediction steps Hp\n 1 control steps Hc\n 1 manipulated inputs u (0 integrators)\n 3 states x̂\n 1 measured outputs ym (1 integrators)\n 1 unmeasured outputs yu\n 0 measured disturbances d\n\n\n\n\n\n","category":"type"},{"location":"public/predictive_control/#ExplicitMPC","page":"Predictive Controllers","title":"ExplicitMPC","text":"","category":"section"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"ExplicitMPC","category":"page"},{"location":"public/predictive_control/#ModelPredictiveControl.ExplicitMPC","page":"Predictive Controllers","title":"ModelPredictiveControl.ExplicitMPC","text":"ExplicitMPC(model::LinModel; )\n\nConstruct an explicit linear predictive controller based on LinModel model.\n\nThe controller minimizes the following objective function at each discrete time k:\n\nmin_mathbfΔU mathbf(R_y - Y) mathbfM_H_p mathbf(R_y - Y) \n + mathbf(ΔU) mathbfN_H_c mathbf(ΔU) \n + mathbf(R_u - U) mathbfL_H_p mathbf(R_u - U) \n\nSee LinMPC for the variable definitions. This controller does not support constraints but the computational costs are extremely low (array division), therefore suitable for applications that require small sample times. This method uses the default state estimator, a SteadyKalmanFilter with default arguments.\n\nArguments\n\nmodel::LinModel : model used for controller predictions and state estimations.\nHp=10+nk: prediction horizon H_p, nk is the number of delays in model.\nHc=2 : control horizon H_c.\nMwt=fill(1.0,model.ny) : main diagonal of mathbfM weight matrix (vector).\nNwt=fill(0.1,model.nu) : main diagonal of mathbfN weight matrix (vector).\nLwt=fill(0.0,model.nu) : main diagonal of mathbfL weight matrix (vector).\nru=model.uop : manipulated input setpoints mathbfr_u (vector).\n\nExamples\n\njulia> model = LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 4);\n\njulia> mpc = ExplicitMPC(model, Mwt=[0, 1], Nwt=[0.5], Hp=30, Hc=1)\nExplicitMPC controller with a sample time Ts = 4.0 s, SteadyKalmanFilter estimator and:\n 30 prediction steps Hp\n 1 control steps Hc\n 1 manipulated inputs u (0 integrators)\n 4 states x̂\n 2 measured outputs ym (2 integrators)\n 0 unmeasured outputs yu\n 0 measured disturbances d\n\n\n\n\n\nExplicitMPC(estim::StateEstimator; )\n\nUse custom state estimator estim to construct ExplicitMPC.\n\nestim.model must be a LinModel. Else, a NonLinMPC is required. \n\nExamples\n\njulia> estim = KalmanFilter(LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 4), i_ym=[2]);\n\njulia> mpc = ExplicitMPC(estim, Mwt=[0, 1], Nwt=[0.5], Hp=30, Hc=1)\nExplicitMPC controller with a sample time Ts = 4.0 s, KalmanFilter estimator and:\n 30 prediction steps Hp\n 1 control steps Hc\n 1 manipulated inputs u (0 integrators)\n 3 states x̂\n 1 measured outputs ym (1 integrators)\n 1 unmeasured outputs yu\n 0 measured disturbances d\n\n\n\n\n\n","category":"type"},{"location":"public/predictive_control/#NonLinMPC","page":"Predictive Controllers","title":"NonLinMPC","text":"","category":"section"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"NonLinMPC","category":"page"},{"location":"public/predictive_control/#ModelPredictiveControl.NonLinMPC","page":"Predictive Controllers","title":"ModelPredictiveControl.NonLinMPC","text":"NonLinMPC(model::SimModel; )\n\nConstruct a nonlinear predictive controller based on SimModel model.\n\nBoth NonLinModel and LinModel are supported (see Extended Help). The controller minimizes the following objective function at each discrete time k:\n\nmin_mathbfΔU ϵ mathbf(R_y - Y) mathbfM_H_p mathbf(R_y - Y) \n + mathbf(ΔU) mathbfN_H_c mathbf(ΔU) \n + mathbf(R_u - U) mathbfL_H_p mathbf(R_u - U) \n + C ϵ^2 + E J_E(mathbfU_E mathbfY_E mathbfD_E)\n\nSee LinMPC for the variable definitions. The custom economic function J_E can penalizes solutions with high economic costs. Setting all the weights to 0 except E creates a pure economic model predictive controller (EMPC). The arguments of J_E are the manipulated inputs, the predicted outputs and measured disturbances from k to k+H_p inclusively:\n\n mathbfU_E = beginbmatrix mathbfU mathbfu(k+H_p-1) endbmatrix text qquad\n mathbfY_E = beginbmatrix mathbfy(k) mathbfY endbmatrix text qquad\n mathbfD_E = beginbmatrix mathbfd(k) mathbfD endbmatrix\n\nsince H_c H_p implies that mathbfu(k+H_p) = mathbfu(k+H_p-1). The vector mathbfD includes the predicted measured disturbance over H_p.\n\ntip: Tip\nReplace any of the 3 arguments with _ if not needed (see JE default value below).\n\nThis method uses the default state estimator :\n\nif model is a LinModel, a SteadyKalmanFilter with default arguments;\nelse, an UnscentedKalmanFilter with default arguments. \n\nwarning: Warning\nSee Extended Help if you get an error like: MethodError: no method matching Float64(::ForwardDiff.Dual).\n\nArguments\n\nmodel::SimModel : model used for controller predictions and state estimations.\nHp=10: prediction horizon H_p.\nHc=2 : control horizon H_c.\nMwt=fill(1.0,model.ny) : main diagonal of mathbfM weight matrix (vector).\nNwt=fill(0.1,model.nu) : main diagonal of mathbfN weight matrix (vector).\nLwt=fill(0.0,model.nu) : main diagonal of mathbfL weight matrix (vector).\nCwt=1e5 : slack variable weight C (scalar), use Cwt=Inf for hard constraints only.\nEwt=0.0 : economic costs weight E (scalar). \nJE=(_,_,_)->0.0 : economic function J_E(mathbfU_E mathbfY_E mathbfD_E).\nru=model.uop : manipulated input setpoints mathbfr_u (vector).\noptim=JuMP.Model(Ipopt.Optimizer) : nonlinear optimizer used in the predictive controller, provided as a JuMP.Model (default to Ipopt.jl optimizer).\n\nExamples\n\njulia> model = NonLinModel((x,u,_)->0.5x+u, (x,_)->2x, 10.0, 1, 1, 1);\n\njulia> mpc = NonLinMPC(model, Hp=20, Hc=1, Cwt=1e6)\nNonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, UnscentedKalmanFilter estimator and:\n 20 prediction steps Hp\n 1 control steps Hc\n 1 manipulated inputs u (0 integrators)\n 2 states x̂\n 1 measured outputs ym (1 integrators)\n 0 unmeasured outputs yu\n 0 measured disturbances d\n\nExtended Help\n\nNonLinMPC controllers based on LinModel compute the predictions with matrix algebra instead of a for loop. This feature can accelerate the optimization and is not available in any other package, to my knowledge.\n\nThe optimizations rely on JuMP.jl automatic differentiation (AD) to compute the objective and constraint derivatives. Optimizers generally benefit from exact derivatives like AD. However, the NonLinModel f and h functions must be compatible with this feature. See Automatic differentiation for common mistakes when writing these functions.\n\n\n\n\n\nNonLinMPC(estim::StateEstimator; )\n\nUse custom state estimator estim to construct NonLinMPC.\n\nExamples\n\njulia> model = NonLinModel((x,u,_)->0.5x+u, (x,_)->2x, 10.0, 1, 1, 1);\n\njulia> estim = UnscentedKalmanFilter(model, σQint_ym=[0.05]);\n\njulia> mpc = NonLinMPC(estim, Hp=20, Hc=1, Cwt=1e6)\nNonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, UnscentedKalmanFilter estimator and:\n 20 prediction steps Hp\n 1 control steps Hc\n 1 manipulated inputs u (0 integrators)\n 2 states x̂\n 1 measured outputs ym (1 integrators)\n 0 unmeasured outputs yu\n 0 measured disturbances d\n\n\n\n\n\n","category":"type"},{"location":"public/predictive_control/#Set-Constraint","page":"Predictive Controllers","title":"Set Constraint","text":"","category":"section"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"setconstraint!","category":"page"},{"location":"public/predictive_control/#ModelPredictiveControl.setconstraint!","page":"Predictive Controllers","title":"ModelPredictiveControl.setconstraint!","text":"setconstraint!(mpc::PredictiveController; )\n\nSet the constraint parameters of mpc predictive controller.\n\nThe predictive controllers support both soft and hard constraints, defined by:\n\nbeginalignat*3\n mathbfu_min - c_u_min ϵ mathbfu(k+j) mathbfu_max + c_u_max ϵ qquad j = 0 1 H_c - 1 \n mathbfΔu_min - c_Δu_min ϵ mathbfΔu(k+j) mathbfΔu_max + c_Δu_max ϵ qquad j = 0 1 H_c - 1 \n mathbfy_min - c_y_min ϵ mathbfy(k+j) mathbfy_max + c_y_max ϵ qquad j = 1 2 H_p \nendalignat*\n\nand also ϵ 0. All the constraint parameters are vector. Use ±Inf values when there is no bound. The constraint softness parameters mathbfc, 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. The output constraints mathbfy_min and mathbfy_max are soft by default.\n\nArguments\n\ninfo: Info\nThe 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).\n\numin=fill(-Inf,nu) : manipulated input lower bounds mathbfu_min \numax=fill(+Inf,nu) : manipulated input upper bounds mathbfu_max \nΔumin=fill(-Inf,nu) : manipulated input increment lower bounds mathbfΔu_min \nΔumax=fill(+Inf,nu) : manipulated input increment upper bounds mathbfΔu_max \nymin=fill(-Inf,ny) : predicted output lower bounds mathbfy_min \nymax=fill(+Inf,ny) : predicted output upper bounds mathbfy_max \nc_umin=fill(0.0,nu) : umin softness weights mathbfc_u_min \nc_umax=fill(0.0,nu) : umax softness weights mathbfc_u_max \nc_Δumin=fill(0.0,nu) : Δumin softness weights mathbfc_Δu_min \nc_Δumax=fill(0.0,nu) : Δumax softness weights mathbfc_Δu_max \nc_ymin=fill(1.0,ny) : ymin softness weights mathbfc_y_min \nc_ymax=fill(1.0,ny) : ymax softness weights mathbfc_y_max\n\nExamples\n\njulia> mpc = LinMPC(setop!(LinModel(tf(3, [30, 1]), 4), uop=[50], yop=[25]));\n\njulia> mpc = setconstraint!(mpc, umin=[0], umax=[100], c_umin=[0.0], c_umax=[0.0]);\n\njulia> mpc = setconstraint!(mpc, Δumin=[-10], Δumax=[+10], c_Δumin=[1.0], c_Δumax=[1.0])\nLinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, SteadyKalmanFilter estimator and:\n 10 prediction steps Hp\n 2 control steps Hc\n 1 manipulated inputs u (0 integrators)\n 2 states x̂\n 1 measured outputs ym (1 integrators)\n 0 unmeasured outputs yu\n 0 measured disturbances d\n\n\n\n\n\n","category":"function"},{"location":"public/predictive_control/#Move-Manipulated-Input-u","page":"Predictive Controllers","title":"Move Manipulated Input u","text":"","category":"section"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"moveinput!","category":"page"},{"location":"public/predictive_control/#ModelPredictiveControl.moveinput!","page":"Predictive Controllers","title":"ModelPredictiveControl.moveinput!","text":"moveinput!(\n mpc::PredictiveController, \n ry = mpc.estim.model.yop, \n d = Float64[];\n R̂y = repeat(ry, mpc.Hp), \n D̂ = repeat(d, mpc.Hp), \n ym = nothing\n)\n\nCompute the optimal manipulated input value u for the current control period.\n\nSolve the optimization problem of mpc PredictiveController and return the results mathbfu(k). Following the receding horizon principle, the algorithm discards the optimal future manipulated inputs mathbfu(k+1) mathbfu(k+2) The arguments ry and d are current output setpoints mathbfr_y(k) and measured disturbances mathbfd(k).\n\nThe keyword arguments R̂y and D̂ are the predicted output setpoints mathbfR_y and measured disturbances mathbfD. They are assumed constant in the future by default, that is mathbfr_y(k+j) = mathbfr_y(k) and mathbfd(k+j) = mathbfd(k) for j=1 to H_p. Current measured output ym is only required if mpc.estim is a InternalModel.\n\nCalling a PredictiveController object calls this method.\n\nSee also LinMPC, NonLinMPC.\n\nExamples\n\njulia> mpc = LinMPC(LinModel(tf(5, [2, 1]), 3), Nwt=[0], Hp=1000, Hc=1);\n\njulia> ry = [5]; u = moveinput!(mpc, ry); round.(u, digits=3)\n1-element Vector{Float64}:\n 1.0\n\n\n\n\n\n","category":"function"},{"location":"public/predictive_control/#Get-Additional-Information","page":"Predictive Controllers","title":"Get Additional Information","text":"","category":"section"},{"location":"public/predictive_control/","page":"Predictive Controllers","title":"Predictive Controllers","text":"getinfo","category":"page"},{"location":"public/predictive_control/#ModelPredictiveControl.getinfo","page":"Predictive Controllers","title":"ModelPredictiveControl.getinfo","text":"getinfo(mpc::PredictiveController) -> sol_summary, info\n\nGet additional information about mpc controller optimum to ease troubleshooting.\n\nReturn the optimizer solution summary that can be printed, sol_summary, and the dictionary info with the following fields:\n\n:ΔU : optimal manipulated input increments over Hc (mathbfΔU)\n:ϵ : optimal slack variable (ϵ)\n:J : objective value optimum (J)\n:U : optimal manipulated inputs over Hp (mathbfU)\n:u : current optimal manipulated input (mathbfu)\n:d : current measured disturbance (mathbfd)\n:D̂ : predicted measured disturbances over Hp (mathbfD)\n:ŷ : current estimated output (mathbfy)\n:Ŷ : optimal predicted outputs over Hp (mathbfY)\n:Ŷs : predicted stochastic output over Hp of InternalModel (mathbfY_s)\n:R̂y : predicted output setpoint over Hp (mathbfR_y)\n:R̂u : predicted manipulated input setpoint over Hp (mathbfR_u)\n\nExamples\n\njulia> mpc = LinMPC(LinModel(tf(5, [2, 1]), 3), Nwt=[0], Hp=1, Hc=1);\n\njulia> u = moveinput!(mpc, [10]);\n\njulia> sol_summary, info = getinfo(mpc); round.(info[:Ŷ], digits=3)\n1-element Vector{Float64}:\n 10.0\n\n\n\n\n\ngetinfo(mpc::NonLinMPC) -> sol_summary, info\n\nInvoke getinfo(::PredictiveController) and add :JE the economic optimum J_E.\n\n\n\n\n\n","category":"function"},{"location":"public/generic_func/#Functions:-Generic-Functions","page":"Generic Functions","title":"Functions: Generic Functions","text":"","category":"section"},{"location":"public/generic_func/","page":"Generic Functions","title":"Generic Functions","text":"Pages = [\"generic_func.md\"]","category":"page"},{"location":"public/generic_func/","page":"Generic Functions","title":"Generic Functions","text":"This page contains the documentation of functions that are generic to SimModel, StateEstimator and PredictiveController types.","category":"page"},{"location":"public/generic_func/#Evaluate-Output-y","page":"Generic Functions","title":"Evaluate Output y","text":"","category":"section"},{"location":"public/generic_func/","page":"Generic Functions","title":"Generic Functions","text":"evaloutput","category":"page"},{"location":"public/generic_func/#ModelPredictiveControl.evaloutput","page":"Generic Functions","title":"ModelPredictiveControl.evaloutput","text":"evaloutput(model::SimModel, d=Float64[]) -> y\n\nEvaluate SimModel outputs y from model.x states and measured disturbances d.\n\nCalling a SimModel object calls this evaloutput method.\n\nExamples\n\njulia> model = setop!(LinModel(tf(2, [10, 1]), 5.0), yop=[20]);\n\njulia> y = evaloutput(model)\n1-element Vector{Float64}:\n 20.0\n\n\n\n\n\nevaloutput(estim::StateEstimator, d=Float64[]) -> ŷ\n\nEvaluate StateEstimator outputs ŷ from estim.x̂ states and disturbances d.\n\nCalling a StateEstimator object calls this evaloutput method.\n\nExamples\n\njulia> kf = SteadyKalmanFilter(setop!(LinModel(tf(2, [10, 1]), 5), yop=[20]));\n\njulia> ŷ = evaloutput(kf)\n1-element Vector{Float64}:\n 20.0\n\n\n\n\n\nevaloutput(estim::InternalModel, ym, d=Float64[]) -> ŷ\n\nEvaluate InternalModel outputs ŷ from estim.x̂d states and measured outputs ym.\n\nInternalModel estimator needs current measured outputs mathbfy^m(k) to estimate its outputs mathbfy(k), since the strategy imposes that mathbfy^m(k) = mathbfy^m(k) is always true.\n\n\n\n\n\n","category":"function"},{"location":"public/generic_func/#Update-State-x","page":"Generic Functions","title":"Update State x","text":"","category":"section"},{"location":"public/generic_func/","page":"Generic Functions","title":"Generic Functions","text":"updatestate!","category":"page"},{"location":"public/generic_func/#ModelPredictiveControl.updatestate!","page":"Generic Functions","title":"ModelPredictiveControl.updatestate!","text":"updatestate!(model::SimModel, u, d=Float64[]) -> x\n\nUpdate model.x states with current inputs u and measured disturbances d.\n\nExamples\n\njulia> model = LinModel(ss(1, 1, 1, 0, 1.0));\n\njulia> x = updatestate!(model, [1])\n1-element Vector{Float64}:\n 1.0\n\n\n\n\n\nupdatestate!(estim::StateEstimator, u, ym, d=Float64[]) -> x̂\n\nUpdate estim.x̂ estimate with current inputs u, measured outputs ym and dist. d. \n\nThe method removes the operating points with remove_op! and call update_estimate!.\n\nExamples\n\njulia> kf = SteadyKalmanFilter(LinModel(ss(0.1, 0.5, 1, 0, 4.0)));\n\njulia> x̂ = updatestate!(kf, [1], [0]) # x̂[2] is the integrator state (nint_ym argument)\n2-element Vector{Float64}:\n 0.5\n 0.0\n\n\n\n\n\nupdatestate!(mpc::PredictiveController, u, ym, d=Float64[]) -> x̂\n\nCall updatestate! on mpc.estim StateEstimator.\n\n\n\n\n\n","category":"function"},{"location":"public/generic_func/#Init-State-x","page":"Generic Functions","title":"Init State x","text":"","category":"section"},{"location":"public/generic_func/","page":"Generic Functions","title":"Generic Functions","text":"initstate!","category":"page"},{"location":"public/generic_func/#ModelPredictiveControl.initstate!","page":"Generic Functions","title":"ModelPredictiveControl.initstate!","text":"initstate!(estim::StateEstimator, u, ym, d=Float64[]) -> x̂\n\nInit estim.x̂ states from current inputs u, measured outputs ym and disturbances d.\n\nThe method tries to find a good stead-state for the initial esitmate mathbfx(0). It removes the operating points with remove_op! and call init_estimate!:\n\nIf 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 mathbfy^m = mathbfy^m. For control applications, this solution produces a bumpless manual to automatic transfer. See init_estimate! for details.\nElse, estim.x̂ is left unchanged. Use setstate! to manually modify it.\n\nIf applicable, it also sets the error covariance estim.P̂ to mathbfP(0).\n\nExamples\n\njulia> estim = SteadyKalmanFilter(LinModel(tf(3, [10, 1]), 0.5), nint_ym=[2]);\n\njulia> u = [1]; y = [3 - 0.1]; x̂ = round.(initstate!(estim, u, y), digits=3)\n3-element Vector{Float64}:\n 5.0\n 0.0\n -0.1\n\njulia> x̂ ≈ updatestate!(estim, u, y)\ntrue\n\njulia> evaloutput(estim) ≈ y\ntrue\n\n\n\n\n\ninitstate!(mpc::PredictiveController, u, ym, d=Float64[])\n\nInit the states of mpc.estim StateEstimator and warm start mpc.ΔŨ at zero.\n\n\n\n\n\n","category":"function"},{"location":"public/generic_func/#Set-State-x","page":"Generic Functions","title":"Set State x","text":"","category":"section"},{"location":"public/generic_func/","page":"Generic Functions","title":"Generic Functions","text":"setstate!","category":"page"},{"location":"public/generic_func/#ModelPredictiveControl.setstate!","page":"Generic Functions","title":"ModelPredictiveControl.setstate!","text":"setstate!(model::SimModel, x)\n\nSet model.x states to values specified by x. \n\n\n\n\n\nsetstate!(estim::StateEstimator, x̂)\n\nSet estim.x̂ states to values specified by x̂. \n\n\n\n\n\nsetstate!(mpc::PredictiveController, x̂)\n\nSet the estimate at mpc.estim.x̂.\n\n\n\n\n\n","category":"function"},{"location":"public/generic_func/#Quick-Simulation","page":"Generic Functions","title":"Quick Simulation","text":"","category":"section"},{"location":"public/generic_func/","page":"Generic Functions","title":"Generic Functions","text":"sim!","category":"page"},{"location":"public/generic_func/#ModelPredictiveControl.sim!","page":"Generic Functions","title":"ModelPredictiveControl.sim!","text":"sim!(plant::SimModel, N::Int, u=plant.uop.+1, d=plant.dop; x0=zeros(plant.nx)) -> res\n\nOpen-loop simulation of plant for N time steps, default to unit bump test on all inputs.\n\nThe manipulated inputs mathbfu and measured disturbances mathbfd are held constant at u and d values, respectively. The plant initial state mathbfx(0) is specified by x0 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.\n\nExamples\n\njulia> plant = NonLinModel((x,u,d)->0.1x+u+d, (x,_)->2x, 10.0, 1, 1, 1, 1);\n\njulia> res = sim!(plant, 15, [0], [0], x0=[1]);\n\njulia> using Plots; plot(res, plotu=false, plotd=false, plotx=true)\n\n\n\n\n\n\nsim!(\n estim::StateEstimator,\n N::Int,\n u = estim.model.uop .+ 1,\n d = estim.model.dop;\n \n) -> res\n\nClosed-loop simulation of estim estimator for N time steps, default to input bumps.\n\nSee 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.\n\nArguments\n\nestim::StateEstimator : state estimator to simulate.\nN::Int : simulation length in time steps.\nu = estim.model.uop .+ 1 : manipulated input mathbfu value.\nd = estim.model.dop : plant measured disturbance mathbfd value.\nplant::SimModel = estim.model : simulated plant model.\nu_step = zeros(plant.nu) : step load disturbance on plant inputs mathbfu.\nu_noise = zeros(plant.nu) : gaussian load disturbance on plant inputs mathbfu.\ny_step = zeros(plant.ny) : step disturbance on plant outputs mathbfy.\ny_noise = zeros(plant.ny) : additive gaussian noise on plant outputs mathbfy.\nd_step = zeros(plant.nd) : step on measured disturbances mathbfd.\nd_noise = zeros(plant.nd) : additive gaussian noise on measured dist. mathbfd.\nx_noise = zeros(plant.nx) : additive gaussian noise on plant states mathbfx.\nx0 = zeros(plant.nx) : plant initial state mathbfx(0).\nx̂0 = nothing : initial estimate mathbfx(0), initstate! is used if nothing.\nlastu = plant.uop : last plant input mathbfu for mathbfx initialization.\n\nExamples\n\njulia> model = LinModel(tf(3, [30, 1]), 0.5);\n\njulia> estim = KalmanFilter(model, σR=[0.5], σQ=[0.25], σQ_int=[0.01], σP0_int=[0.1]);\n\njulia> res = sim!(estim, 50, [0], y_noise=[0.5], x_noise=[0.25], x0=[-10], x̂0=[0, 0]);\n\njulia> using Plots; plot(res, plotŷ=true, plotu=false, plotxwithx̂=true)\n\n\n\n\n\n\nsim!(\n mpc::PredictiveController, \n N::Int,\n ry = mpc.estim.model.yop .+ 1, \n d = mpc.estim.model.dop; \n \n) -> res\n\nClosed-loop simulation of mpc controller for N time steps, default to setpoint bumps.\n\nThe output setpoint mathbfr_y is held constant at ry. The keyword arguments are identical to sim!(::StateEstimator, ::Int).\n\nExamples\n\njulia> model = LinModel([tf(3, [30, 1]); tf(2, [5, 1])], 4);\n\njulia> mpc = setconstraint!(LinMPC(model, Mwt=[0, 1], Nwt=[0.01], Hp=30), ymin=[0, -Inf]);\n\njulia> res = sim!(mpc, 25, [0, 0], y_noise=[0.1], y_step=[-10, 0]);\n\njulia> using Plots; plot(res, plotry=true, plotŷ=true, plotymin=true, plotu=true)\n\n\n\n\n\n\n","category":"function"},{"location":"#ModelPredictiveControl.jl","page":"Home","title":"ModelPredictiveControl.jl","text":"","category":"section"},{"location":"","page":"Home","title":"Home","text":"A model predictive control package for Julia.","category":"page"},{"location":"","page":"Home","title":"Home","text":"The package depends on ControlSystemsBase.jl for the linear systems and JuMP.jl for the solving.","category":"page"},{"location":"","page":"Home","title":"Home","text":"The objective is to provide a simple and clear framework to quickly design model predictive controllers (MPCs) in Julia, while preserving the flexibility for advanced real-time optimization. Modern MPCs based on closed-loop state estimators are the main focus of the package, but classical approaches that rely on internal models are also possible. The JuMP.jl interface allows the user to test different solvers easily if the performance of the default settings is not satisfactory.","category":"page"},{"location":"","page":"Home","title":"Home","text":"The documentation is divided in two parts:","category":"page"},{"location":"","page":"Home","title":"Home","text":"Manual — This section includes step-by-step guides to design predictive controllers on multiple case studies.\nFunctions — Documentation of methods and types exported by the package. The \"Internals\" section provides implementation details of functions that are not exported.","category":"page"},{"location":"#Manual","page":"Home","title":"Manual","text":"","category":"section"},{"location":"","page":"Home","title":"Home","text":"Depth = 2\nPages = [\n \"manual/installation.md\",\n \"manual/linmpc.md\",\n \"manual/nonlinmpc.md\",\n]","category":"page"},{"location":"#Functions:-Public","page":"Home","title":"Functions: Public","text":"","category":"section"},{"location":"","page":"Home","title":"Home","text":"Depth = 2\nPages = [\n \"public/sim_model.md\",\n \"public/state_estim.md\",\n \"public/predictive_control.md\",\n \"public/generic_func.md\",\n]","category":"page"},{"location":"#Functions:-Internals","page":"Home","title":"Functions: Internals","text":"","category":"section"},{"location":"","page":"Home","title":"Home","text":"Depth = 1\nPages = [\n \"internals/sim_model.md\",\n \"internals/state_estim.md\",\n \"internals/predictive_control.md\",\n]","category":"page"},{"location":"internals/sim_model/#Functions:-SimModel-Internals","page":"Plant Models","title":"Functions: SimModel Internals","text":"","category":"section"},{"location":"internals/sim_model/","page":"Plant Models","title":"Plant Models","text":"Pages = [\"sim_model.md\"]","category":"page"},{"location":"internals/sim_model/","page":"Plant Models","title":"Plant Models","text":"ModelPredictiveControl.f\nModelPredictiveControl.h","category":"page"},{"location":"internals/sim_model/#ModelPredictiveControl.f","page":"Plant Models","title":"ModelPredictiveControl.f","text":"f(model::LinModel, x, u, d)\n\nEvaluate mathbfA x + B_u u + B_d d when model is a LinModel.\n\n\n\n\n\nCall mathbff(x u d) with model.f function for NonLinModel.\n\n\n\n\n\n","category":"function"},{"location":"internals/sim_model/#ModelPredictiveControl.h","page":"Plant Models","title":"ModelPredictiveControl.h","text":"h(model::LinModel, x, u, d)\n\nEvaluate mathbfC x + D_d d when model is a LinModel.\n\n\n\n\n\nCall mathbfh(x d) with model.h function for NonLinModel.\n\n\n\n\n\n","category":"function"}]
+}
diff --git a/v0.8.3/siteinfo.js b/v0.8.3/siteinfo.js
new file mode 100644
index 000000000..9968ccd22
--- /dev/null
+++ b/v0.8.3/siteinfo.js
@@ -0,0 +1 @@
+var DOCUMENTER_CURRENT_VERSION = "v0.8.3";
diff --git a/v0.8.3/test.jl b/v0.8.3/test.jl
new file mode 100644
index 000000000..0d8001925
--- /dev/null
+++ b/v0.8.3/test.jl
@@ -0,0 +1,39 @@
+using ModelPredictiveControl
+
+function pendulum(par, x, u)
+ g, L, K, m = par # [m/s], [m], [kg/s], [kg]
+ θ, ω = x[1], x[2] # [rad], [rad/s]
+ τ = u[1] # [N m]
+ dθ = ω
+ dω = -g/L*sin(θ) - K/m*ω + τ/m/L^2
+ return [dθ, dω]
+end
+
+Ts = 0.1 # [s]
+par = (9.8, 0.4, 1.2, 0.3)
+f(x, u, _) = x + Ts*pendulum(par, x, u)
+h(x, _ ) = [180/π*x[1]] # [rad] to [°]
+nu, nx, ny = 1, 2, 1
+model = NonLinModel(f, h, Ts, nu, nx, ny)
+
+using Plots
+p1 = plot(sim!(model, 50, [0.5])) # τ = 0.5 N m
+display(p1)
+
+par_plant = (par[1], par[2], par[3] + 0.25, par[4])
+f_plant(x, u, _) = x + Ts*pendulum(par_plant, x, u)
+plant = NonLinModel(f_plant, h, Ts, nu, nx, ny)
+
+estim = UnscentedKalmanFilter(model, σQ=[0.5, 2.5], σQ_int=[0.5])
+
+
+res = sim!(estim, 30, [0.5], plant=plant, y_noise=[0.5]) # τ = 0.5 N m
+p2 = plot(res, plotu=false, plotx=true, plotx̂=true)
+display(p2)
+
+
+mpc = NonLinMPC(estim, Hp=20, Hc=2, Mwt=[0.1], Nwt=[1.0], Cwt=Inf)
+mpc = setconstraint!(mpc, umin=[-1.5], umax=[+1.5])
+
+res = sim!(mpc, 30, [180.0], x̂=zeros(mpc.estim.nx̂), plant=plant)
+plot(res, plotŷ=true)
diff --git a/versions.js b/versions.js
index 463b76d1b..9c1e36d7a 100644
--- a/versions.js
+++ b/versions.js
@@ -10,5 +10,5 @@ var DOC_VERSIONS = [
"v0.1",
"dev",
];
-var DOCUMENTER_NEWEST = "v0.8.2";
+var DOCUMENTER_NEWEST = "v0.8.3";
var DOCUMENTER_STABLE = "stable";