Skip to content

Commit 4709a3d

Browse files
committed
doc add MPC vectors nomenclature in introduction
1 parent 3bf3052 commit 4709a3d

File tree

4 files changed

+57
-28
lines changed

4 files changed

+57
-28
lines changed

docs/src/public/predictive_control.md

Lines changed: 41 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,47 @@ assumes by default that the current model mismatch estimation is constant in the
1212
(same approach than dynamic matrix control, DMC).
1313

1414
!!! info
15-
The nomenclature uses hats for the predictions (or estimations, for the state
16-
estimators) e.g. ``\mathbf{Ŷ}`` encompasses the future model outputs ``\mathbf{y}`` over
17-
the prediction horizon ``H_p``.
15+
The nomenclature use capital letters for time series (and matrices) and hats for the
16+
predictions (and estimations, for state estimators).
17+
18+
To be precise, at the ``k``th control period, the vectors that encompass the future measured
19+
disturbances ``\mathbf{d̂}``, model outputs ``\mathbf{ŷ}`` and setpoints ``\mathbf{r̂_y}``
20+
over the prediction horizon ``H_p`` are defined as:
21+
22+
```math
23+
\mathbf{D̂} = \begin{bmatrix}
24+
\mathbf{d̂}(k+1) \\ \mathbf{d̂}(k+2) \\ \vdots \\ \mathbf{d̂}(k+H_p)
25+
\end{bmatrix} \: , \quad
26+
\mathbf{Ŷ} = \begin{bmatrix}
27+
\mathbf{ŷ}(k+1) \\ \mathbf{ŷ}(k+2) \\ \vdots \\ \mathbf{ŷ}(k+H_p)
28+
\end{bmatrix} \: \text{and} \quad
29+
\mathbf{R̂_y} = \begin{bmatrix}
30+
\mathbf{r̂_y}(k+1) \\ \mathbf{r̂_y}(k+2) \\ \vdots \\ \mathbf{r̂_y}(k+H_p)
31+
\end{bmatrix}
32+
```
33+
34+
The vectors for the manipulated input ``\mathbf{u}`` are shifted by one time step:
35+
36+
```math
37+
\mathbf{U} = \begin{bmatrix}
38+
\mathbf{u}(k+0) \\ \mathbf{u}(k+1) \\ \vdots \\ \mathbf{u}(k+H_p-1)
39+
\end{bmatrix} \: \text{and} \quad
40+
\mathbf{R̂_u} = \begin{bmatrix}
41+
\mathbf{r_u} \\ \mathbf{r_u} \\ \vdots \\ \mathbf{r_u}
42+
\end{bmatrix}
43+
```
44+
45+
assuming constant input setpoints at ``\mathbf{r_u}``. Defining the manipulated input
46+
increment as ``\mathbf{Δu}(k+j) = \mathbf{u}(k+j) - \mathbf{u}(k+j-1)``, the control horizon
47+
``H_c`` enforces that ``\mathbf{Δu}(k+j) = \mathbf{0}`` for ``j ≥ H_c``. For this reason,
48+
the vector that collects them is truncated up to ``k+H_c-1``:
49+
50+
```math
51+
\mathbf{ΔU} =
52+
\begin{bmatrix}
53+
\mathbf{Δu}(k+0) \\ \mathbf{Δu}(k+1) \\ \vdots \\ \mathbf{Δu}(k+H_c-1)
54+
\end{bmatrix}
55+
```
1856

1957
## PredictiveController
2058

docs/src/public/state_estim.md

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,9 +18,10 @@ error with closed-loop control (offset-free tracking).
1818

1919
The estimators are all implemented in the predictor form (a.k.a. observer form), that is,
2020
they all estimates at each discrete time ``k`` the states of the next period
21-
``\mathbf{x̂}_k(k+1)`` (also written ``\mathbf{x̂}_{k+1|k}`` [elsewhere](https://en.wikipedia.org/wiki/Kalman_filter)).
22-
In contrast, the filter form that estimates ``\mathbf{x̂}_k(k)`` is
23-
sometimes slightly more accurate.
21+
``\mathbf{x̂}_k(k+1)``[^1]. In contrast, the filter form that estimates ``\mathbf{x̂}_k(k)``
22+
is sometimes slightly more accurate.
23+
24+
[^1]: also denoted ``\mathbf{x̂}_{k+1|k}`` [elsewhere](https://en.wikipedia.org/wiki/Kalman_filter).
2425

2526
The predictor form comes in handy for control applications since the estimations come after
2627
the controller computations, without introducing any additional delays. Moreover, the

src/estimator/kalman.jl

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,8 @@ end
6464
6565
Construct a steady-state Kalman Filter with the [`LinModel`](@ref) `model`.
6666
67-
The steady-state (or asymptotic) Kalman filter is based on the process model :
67+
The steady-state (or [asymptotic](https://en.wikipedia.org/wiki/Kalman_filter#Asymptotic_form))
68+
Kalman filter is based on the process model :
6869
```math
6970
\begin{aligned}
7071
\mathbf{x}(k+1) &=

src/predictive_control.jl

Lines changed: 10 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -227,28 +227,17 @@ Compute the optimal manipulated input value `u` for the current control period.
227227
228228
Solve the optimization problem of `mpc` [`PredictiveController`](@ref) and return the
229229
results ``\mathbf{u}(k)``. Following the receding horizon principle, the algorithm discards
230-
the optimal future manipulated inputs ``\mathbf{u}(k+1), \mathbf{u}(k+2), ``... The
230+
the optimal future manipulated inputs ``\mathbf{u}(k+1), \mathbf{u}(k+2), ...`` The
231231
arguments `ry` and `d` are current output setpoints ``\mathbf{r_y}(k)`` and measured
232-
disturbances ``\mathbf{d}(k)``. The predicted output setpoint `R̂y` and measured disturbances
233-
`D̂` are defined as:
234-
```math
235-
\mathbf{R̂_y} = \begin{bmatrix}
236-
\mathbf{r̂_y}(k+1) \\
237-
\mathbf{r̂_y}(k+2) \\
238-
\vdots \\
239-
\mathbf{r̂_y}(k+H_p)
240-
\end{bmatrix} \qquad \text{and} \qquad
241-
\mathbf{D̂} = \begin{bmatrix}
242-
\mathbf{d̂}(k+1) \\
243-
\mathbf{d̂}(k+2) \\
244-
\vdots \\
245-
\mathbf{d̂}(k+H_p)
246-
\end{bmatrix}
247-
```
248-
They are assumed constant in the future by default, that is
249-
``\mathbf{r̂_y}(k+j) = \mathbf{r_y}(k)`` and ``\mathbf{d̂}(k+j) = \mathbf{d}(k)`` for ``j=1``
250-
to ``H_p``. Current measured outputs `ym` (keyword argument) are only required if
251-
`mpc.estim` is a [`InternalModel`](@ref).
232+
disturbances ``\mathbf{d}(k)``.
233+
234+
The keyword arguments `R̂y` and `D̂` are the predicted output setpoints ``\mathbf{R̂_y}`` and
235+
measured disturbances ``\mathbf{D̂}``. They are assumed constant in the future by default,
236+
that is ``\mathbf{r̂_y}(k+j) = \mathbf{r_y}(k)`` and ``\mathbf{d̂}(k+j) = \mathbf{d}(k)`` for
237+
``j=1`` to ``H_p``. Current measured output `ym` is only required if `mpc.estim` is a
238+
[`InternalModel`](@ref).
239+
240+
Calling a [`PredictiveController`](@ref) object calls this method.
252241
253242
See also [`LinMPC`](@ref), [`NonLinMPC`](@ref).
254243

0 commit comments

Comments
 (0)