Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
b6a148e
WIP: `TrapezoidalMethod()` collocation
franckgaga Aug 23, 2025
3063a81
Merge branch 'doc_model_aug' into trapezoidal
franckgaga Aug 27, 2025
91c164a
Merge branch 'doc_model_aug' into trapezoidal
franckgaga Aug 27, 2025
ecc2714
Merge branch 'main' into trapezoidal
franckgaga Aug 27, 2025
0689b5c
changed: removed useless unpacking in transcriptions
franckgaga Aug 27, 2025
df10988
changed: removed the hat for states in aug. model
franckgaga Aug 27, 2025
75c83cc
changed: rename `TrapezoidalMethod` to `TrapezoidalCollocation`
franckgaga Aug 27, 2025
7175b02
debug: rename the transcription everywhere
franckgaga Aug 28, 2025
08a09e3
debug: idem
franckgaga Aug 28, 2025
55e4aa9
added: `ShootingMethod` and `CollocationMethod` abstract types
franckgaga Aug 28, 2025
f9c5202
added: validate `model` and `transcription` combo
franckgaga Aug 28, 2025
c213281
added: show `TranscriptionMethod` when printing `PredictiveController`
franckgaga Aug 28, 2025
781f43b
doc: `jldoctest` modifications
franckgaga Aug 28, 2025
c34531f
doc: mention defaults in manual
franckgaga Aug 28, 2025
f185e7c
Merge branch 'print_transcription' into trapezoidal
franckgaga Aug 28, 2025
cf8a1cb
doc: details on operating points and continuous dynamics
franckgaga Aug 28, 2025
1548b21
doc: minor modification
franckgaga Aug 28, 2025
ab55d5c
doc: debug
franckgaga Aug 28, 2025
356e573
doc: comment on the stochastic model with `TrapezoidalCollocation`
franckgaga Aug 28, 2025
4137880
added: adapt `K0` size to number of collocation points
franckgaga Aug 28, 2025
29ed663
doc: mention that the builtin estimator uses `solver`
franckgaga Aug 28, 2025
d503153
doc: move details on the stochastic part in Extended Help
franckgaga Aug 28, 2025
bf181ac
bench: cancel current job on new commits
franckgaga Aug 28, 2025
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions .github/workflows/benchmark.yml
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@ name: Benchmark
on:
pull_request_target:
branches: [ main ]
concurrency:
# Skip intermediate builds: always.
# Cancel intermediate builds: only if it is a pull request build.
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: ${{ startsWith(github.ref, 'refs/pull/') }}
permissions:
pull-requests: write # needed to post comments
jobs:
Expand Down
5 changes: 3 additions & 2 deletions docs/src/manual/linmpc.md
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +78,9 @@ mpc = setconstraint!(mpc, ymin=[48, -Inf])

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`](@ref) controllers use [`OSQP`](https://osqp.org/) to solve the problem,
soft constraints on output predictions ``\mathbf{ŷ}`` to ensure feasibility, and a
default, [`LinMPC`](@ref) controllers use [`OSQP`](https://osqp.org/) and a direct
[`SingleShooting`](@ref) transcription method to solve the optimal control problem, soft
constraints on output predictions ``\mathbf{ŷ}`` to ensure feasibility, and a
[`SteadyKalmanFilter`](@ref) to estimate the plant states[^1]. An attentive reader will also
notice that the Kalman filter estimates two additional states compared to the plant model.
These are the integrating states for the unmeasured plant disturbances, and they are
Expand Down
6 changes: 4 additions & 2 deletions docs/src/manual/nonlinmpc.md
Original file line number Diff line number Diff line change
Expand Up @@ -119,8 +119,10 @@ umin, umax = [-1.5], [+1.5]
nmpc = setconstraint!(nmpc; umin, umax)
```

The option `Cwt=Inf` disables the slack variable `ϵ` for constraint softening. We test `mpc`
performance on `plant` by imposing an angular setpoint of 180° (inverted position):
The option `Cwt=Inf` disables the slack variable `ϵ` for constraint softening. By default,
[`NonLinMPC`](@ref) controllers use [`Ipopt`](https://coin-or.github.io/Ipopt/) and a direct
[`SingleShooting`](@ref) transcription method to solve the optimal control problem. We test
`mpc` performance on `plant` by imposing an angular setpoint of 180° (inverted position):

```@example man_nonlin
using JuMP; unset_time_limit_sec(nmpc.optim) # hide
Expand Down
6 changes: 6 additions & 0 deletions docs/src/public/predictive_control.md
Original file line number Diff line number Diff line change
Expand Up @@ -109,3 +109,9 @@ SingleShooting
```@docs
MultipleShooting
```

### TrapezoidalCollocation

```@docs
TrapezoidalCollocation
```
2 changes: 1 addition & 1 deletion src/ModelPredictiveControl.jl
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ export MovingHorizonEstimator
export ManualEstimator
export default_nint, initstate!
export PredictiveController, ExplicitMPC, LinMPC, NonLinMPC, setconstraint!, moveinput!
export TranscriptionMethod, SingleShooting, MultipleShooting
export TranscriptionMethod, SingleShooting, MultipleShooting, TrapezoidalCollocation
export SimResult, getinfo, sim!

include("general.jl")
Expand Down
8 changes: 4 additions & 4 deletions src/controller/construct.jl
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ constraints are all soft by default. See Extended Help for time-varying constrai
julia> mpc = LinMPC(setop!(LinModel(tf(3, [30, 1]), 4), uop=[50], yop=[25]));

julia> mpc = setconstraint!(mpc, umin=[0], umax=[100], Δumin=[-10], Δumax=[+10])
LinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, SteadyKalmanFilter estimator and:
LinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, SingleShooting transcription, SteadyKalmanFilter estimator and:
10 prediction steps Hp
2 control steps Hc
1 slack variable ϵ (control constraints)
Expand Down Expand Up @@ -600,11 +600,11 @@ end
ex̂, fx̂, gx̂, jx̂, kx̂, vx̂, bx̂,
Eŝ, Fŝ, Gŝ, Jŝ, Kŝ, Vŝ, Bŝ,
gc!=nothing, nc=0
) -> con, nϵ, P̃Δu, P̃u, Ẽ, Ẽŝ
) -> con, nϵ, P̃Δu, P̃u, Ẽ

Init `ControllerConstraint` struct with default parameters based on estimator `estim`.

Also return `P̃Δu`, `P̃u`, `Ẽ` and `Ẽŝ` matrices for the the augmented decision vector `Z̃`.
Also return `P̃Δu`, `P̃u` and `` matrices for the the augmented decision vector `Z̃`.
"""
function init_defaultcon_mpc(
estim::StateEstimator{NT},
Expand Down Expand Up @@ -660,7 +660,7 @@ function init_defaultcon_mpc(
C_ymin , C_ymax , c_x̂min , c_x̂max , i_g,
gc! , nc
)
return con, nϵ, P̃Δu, P̃u, Ẽ, Ẽŝ
return con, nϵ, P̃Δu, P̃u, Ẽ
end

"Repeat predictive controller constraints over prediction `Hp` and control `Hc` horizons."
Expand Down
1 change: 1 addition & 0 deletions src/controller/explicitmpc.jl
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ struct ExplicitMPC{
R̂y, R̂u, Tu_lastu0 = zeros(NT, ny*Hp), zeros(NT, nu*Hp), zeros(NT, nu*Hp)
lastu0 = zeros(NT, nu)
transcription = SingleShooting() # explicit MPC only supports SingleShooting
validate_transcription(model, transcription)
PΔu = init_ZtoΔU(estim, transcription, Hp, Hc)
Pu, Tu = init_ZtoU(estim, transcription, Hp, Hc, nb)
E, G, J, K, V, B = init_predmat(model, estim, transcription, Hp, Hc)
Expand Down
17 changes: 9 additions & 8 deletions src/controller/linmpc.jl
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ struct LinMPC{
NT<:Real,
SE<:StateEstimator,
CW<:ControllerWeights,
TM<:TranscriptionMethod,
TM<:ShootingMethod,
JM<:JuMP.GenericModel
} <: PredictiveController{NT}
estim::SE
Expand Down Expand Up @@ -54,7 +54,7 @@ struct LinMPC{
NT<:Real,
SE<:StateEstimator,
CW<:ControllerWeights,
TM<:TranscriptionMethod,
TM<:ShootingMethod,
JM<:JuMP.GenericModel
}
model = estim.model
Expand All @@ -63,6 +63,7 @@ struct LinMPC{
# dummy vals (updated just before optimization):
R̂y, R̂u, Tu_lastu0 = zeros(NT, ny*Hp), zeros(NT, nu*Hp), zeros(NT, nu*Hp)
lastu0 = zeros(NT, nu)
validate_transcription(model, transcription)
PΔu = init_ZtoΔU(estim, transcription, Hp, Hc)
Pu, Tu = init_ZtoU(estim, transcription, Hp, Hc, nb)
E, G, J, K, V, B, ex̂, gx̂, jx̂, kx̂, vx̂, bx̂ = init_predmat(
Expand All @@ -71,7 +72,7 @@ struct LinMPC{
Eŝ, Gŝ, Jŝ, Kŝ, Vŝ, Bŝ = init_defectmat(model, estim, transcription, Hp, Hc)
# dummy vals (updated just before optimization):
F, fx̂, Fŝ = zeros(NT, ny*Hp), zeros(NT, nx̂), zeros(NT, nx̂*Hp)
con, nϵ, P̃Δu, P̃u, Ẽ, Ẽŝ = init_defaultcon_mpc(
con, nϵ, P̃Δu, P̃u, Ẽ = init_defaultcon_mpc(
estim, weights, transcription,
Hp, Hc,
PΔu, Pu, E,
Expand Down Expand Up @@ -156,7 +157,7 @@ arguments. This controller allocates memory at each time step for the optimizati
- `N_Hc=Diagonal(repeat(Nwt,Hc))` : positive semidefinite symmetric matrix ``\mathbf{N}_{H_c}``.
- `L_Hp=Diagonal(repeat(Lwt,Hp))` : positive semidefinite symmetric matrix ``\mathbf{L}_{H_p}``.
- `Cwt=1e5` : slack variable weight ``C`` (scalar), use `Cwt=Inf` for hard constraints only.
- `transcription=SingleShooting()` : a [`TranscriptionMethod`](@ref) for the optimization.
- `transcription=SingleShooting()` : [`SingleShooting`](@ref) or [`MultipleShooting`](@ref).
- `optim=JuMP.Model(OSQP.MathOptInterfaceOSQP.Optimizer)` : quadratic optimizer used in
the predictive controller, provided as a [`JuMP.Model`](@extref) object (default to
[`OSQP`](https://osqp.org/docs/parsers/jump.html) optimizer).
Expand All @@ -167,7 +168,7 @@ arguments. This controller allocates memory at each time step for the optimizati
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:
LinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, SingleShooting transcription, SteadyKalmanFilter estimator and:
30 prediction steps Hp
1 control steps Hc
1 slack variable ϵ (control constraints)
Expand Down Expand Up @@ -215,7 +216,7 @@ function LinMPC(
N_Hc = Diagonal(repeat(Nwt, get_Hc(move_blocking(Hp, Hc)))),
L_Hp = Diagonal(repeat(Lwt, Hp)),
Cwt = DEFAULT_CWT,
transcription::TranscriptionMethod = DEFAULT_LINMPC_TRANSCRIPTION,
transcription::ShootingMethod = DEFAULT_LINMPC_TRANSCRIPTION,
optim::JuMP.GenericModel = JuMP.Model(DEFAULT_LINMPC_OPTIMIZER, add_bridges=false),
kwargs...
)
Expand All @@ -237,7 +238,7 @@ Use custom state estimator `estim` to construct `LinMPC`.
julia> estim = KalmanFilter(LinModel([tf(3, [30, 1]); tf(-2, [5, 1])], 4), i_ym=[2]);

julia> mpc = LinMPC(estim, Mwt=[0, 1], Nwt=[0.5], Hp=30, Hc=1)
LinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, KalmanFilter estimator and:
LinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, SingleShooting transcription, KalmanFilter estimator and:
30 prediction steps Hp
1 control steps Hc
1 slack variable ϵ (control constraints)
Expand All @@ -259,7 +260,7 @@ function LinMPC(
N_Hc = Diagonal(repeat(Nwt, get_Hc(move_blocking(Hp, Hc)))),
L_Hp = Diagonal(repeat(Lwt, Hp)),
Cwt = DEFAULT_CWT,
transcription::TranscriptionMethod = DEFAULT_LINMPC_TRANSCRIPTION,
transcription::ShootingMethod = DEFAULT_LINMPC_TRANSCRIPTION,
optim::JM = JuMP.Model(DEFAULT_LINMPC_OPTIMIZER, add_bridges=false),
) where {NT<:Real, SE<:StateEstimator{NT}, JM<:JuMP.GenericModel}
isa(estim.model, LinModel) || error(MSG_LINMODEL_ERR)
Expand Down
11 changes: 7 additions & 4 deletions src/controller/nonlinmpc.jl
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,7 @@ struct NonLinMPC{
# dummy vals (updated just before optimization):
R̂y, R̂u, Tu_lastu0 = zeros(NT, ny*Hp), zeros(NT, nu*Hp), zeros(NT, nu*Hp)
lastu0 = zeros(NT, nu)
validate_transcription(model, transcription)
PΔu = init_ZtoΔU(estim, transcription, Hp, Hc)
Pu, Tu = init_ZtoU(estim, transcription, Hp, Hc, nb)
E, G, J, K, V, B, ex̂, gx̂, jx̂, kx̂, vx̂, bx̂ = init_predmat(
Expand All @@ -94,7 +95,7 @@ struct NonLinMPC{
Eŝ, Gŝ, Jŝ, Kŝ, Vŝ, Bŝ = init_defectmat(model, estim, transcription, Hp, Hc)
# dummy vals (updated just before optimization):
F, fx̂, Fŝ = zeros(NT, ny*Hp), zeros(NT, nx̂), zeros(NT, nx̂*Hp)
con, nϵ, P̃Δu, P̃u, Ẽ, Ẽŝ = init_defaultcon_mpc(
con, nϵ, P̃Δu, P̃u, Ẽ = init_defaultcon_mpc(
estim, weights, transcription,
Hp, Hc,
PΔu, Pu, E,
Expand Down Expand Up @@ -223,7 +224,7 @@ This controller allocates memory at each time step for the optimization.
julia> model = NonLinModel((x,u,_,_)->0.5x+u, (x,_,_)->2x, 10.0, 1, 1, 1, solver=nothing);

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:
NonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, SingleShooting transcription, UnscentedKalmanFilter estimator and:
20 prediction steps Hp
1 control steps Hc
1 slack variable ϵ (control constraints)
Expand Down Expand Up @@ -327,7 +328,7 @@ julia> model = NonLinModel((x,u,_,_)->0.5x+u, (x,_,_)->2x, 10.0, 1, 1, 1, solver
julia> estim = UnscentedKalmanFilter(model, σQint_ym=[0.05]);

julia> mpc = NonLinMPC(estim, Hp=20, Hc=1, Cwt=1e6)
NonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, UnscentedKalmanFilter estimator and:
NonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, SingleShooting transcription, UnscentedKalmanFilter estimator and:
20 prediction steps Hp
1 control steps Hc
1 slack variable ϵ (control constraints)
Expand Down Expand Up @@ -561,8 +562,10 @@ Inspired from: [User-defined operators with vector outputs](@extref JuMP User-de
function get_optim_functions(mpc::NonLinMPC, ::JuMP.GenericModel{JNT}) where JNT<:Real
# ----------- common cache for Jfunc, gfuncs and geqfuncs ----------------------------
model = mpc.estim.model
transcription = mpc.transcription
grad, jac = mpc.gradient, mpc.jacobian
nu, ny, nx̂, nϵ, nk = model.nu, model.ny, mpc.estim.nx̂, mpc.nϵ, model.nk
nu, ny, nx̂, nϵ = model.nu, model.ny, mpc.estim.nx̂, mpc.nϵ
nk = get_nk(model, transcription)
Hp, Hc = mpc.Hp, mpc.Hc
ng, nc, neq = length(mpc.con.i_g), mpc.con.nc, mpc.con.neq
nZ̃, nU, nŶ, nX̂, nK = length(mpc.Z̃), Hp*nu, Hp*ny, Hp*nx̂, Hp*nk
Expand Down
Loading