added: support box constraint in LinMPC and NonLinMPC#379
Conversation
Codecov Report✅ All modified and coverable lines are covered by tests. Additional details and impacted files@@ Coverage Diff @@
## main #379 +/- ##
==========================================
+ Coverage 98.58% 98.60% +0.01%
==========================================
Files 27 27
Lines 5512 5591 +79
==========================================
+ Hits 5434 5513 +79
Misses 78 78 ☔ View full report in Codecov by Harness. 🚀 New features to boost your workflow:
|
Benchmark Results (Julia v1)Time benchmarks
Memory benchmarks
|
|
Wow these terrible results haha I did something wrong for sure 😆 |
|
Okay I ran some of the benchmark locally and many case studies did not converge anymore, that's why. There's presumably a nasty bug hidden somewhere. |
I just modify them on `setconstraint!` calls
|
Okay I have this MRE that converge to the best solution (at least a very good solution) on using ModelPredictiveControl, ControlSystemsBase, JuMP, Ipopt, BenchmarkTools
function f!(ẋ, x, u, _ , p)
g, L, K, m = p
θ, ω = x[1], x[2]
τ = u[1]
ẋ[1] = ω
ẋ[2] = -g/L*sin(θ) - K/m*ω + τ/m/L^2
end
h!(y, x, _ , _ ) = (y[1] = 180/π*x[1])
p = [9.8, 0.4, 1.2, 0.3]
nu = 1; nx = 2; ny = 1; Ts = 0.1
pendulum_model = NonLinModel(f!, h!, Ts, nu, nx, ny; p)
pendulum_p = p
h2!(y, x, _ , _ ) = (y[1] = 180/π*x[1]; y[2]=x[2])
nu, nx, ny = 1, 2, 2
pendulum_model2 = NonLinModel(f!, h2!, Ts, nu, nx, ny; p)
pendulum_p2 = p
Hp, Hc, Mwt, Nwt, Cwt = 20, 2, [0.5], [2.5], Inf
umin, umax = [-1.5], [+1.5]
model2, p = pendulum_model2, pendulum_p2
plant2 = deepcopy(model2)
plant2.p[3] = 1.25*p[3] # plant-model mismatch
σQ = [0.1, 1.0]; σR=[5.0]; nint_u=[1]; σQint_u=[0.1]
estim2 = UnscentedKalmanFilter(model2; σQ, σR, nint_u, σQint_u, i_ym=[1])
function JE(UE, ŶE, _ , p, _)
Ts = p
τ, ω = @views UE[1:end-1], ŶE[2:2:end-1]
return Ts*dot(τ, ω)
end
p = Ts; Mwt2 = [Mwt; 0.0]; Ewt = 3.5e3
x_0 = [0, 0]; x̂_0 = [0, 0, 0]; ry = [180; 0]
function gc!(LHS, Ue, Ŷe, _, p, ϵ)
Pmax = p
i_τ, i_ω = 1, 2
for i in eachindex(LHS)
τ, ω = Ue[i_τ], Ŷe[i_ω]
P = τ*ω
LHS[i] = P - Pmax - ϵ
i_τ += 1
i_ω += 2
end
return nothing
end
Cwt, Pmax, nc = 1e5, 3, Hp+1
x_0 = [0, 0]; x̂_0 = [0, 0, 0]; ry = [180; 0]
N = 35
optim = JuMP.Model(optimizer_with_attributes(Ipopt.Optimizer,"sb"=>"yes"), add_bridges=false)
transcription = MultipleShooting()
nmpc2_ipopt_ms = NonLinMPC(estim2;
Hp, Hc, Nwt=Nwt, Mwt=[0.5, 0], Cwt, gc!, nc, p=Pmax, optim, transcription
)
nmpc2_ipopt_ms = setconstraint!(nmpc2_ipopt_ms; umin, umax)
JuMP.unset_time_limit_sec(nmpc2_ipopt_ms.optim)
samples, evals, seconds = 100, 1, 15*60
# @btime(
# sim!($nmpc2_ipopt_ms, $N, $ry; plant=$plant2, x_0=$x_0, x̂_0=$x̂_0, progress=false),
# samples=samples, evals=evals, seconds=seconds, setup=GC.gc()
# )
unset_silent(nmpc2_ipopt_ms.optim)
initstate!(nmpc2_ipopt_ms, [0], [0])
setstate!(nmpc2_ipopt_ms, x̂_0)
preparestate!(nmpc2_ipopt_ms, [0])
u = moveinput!(nmpc2_ipopt_ms, ry)We can see that the objective increases throughtout the iterrations: The results on I'm not sure what's happening. I will continue my investigations. Any clue @cvanaret on why the iterations could suddenly increase like this ? edit : There is only one box constraint here, the slack edit 2: It converges to the good solution if I set |
Following discussion at #378, it is a good idea in terms of performances to treat constraints on the decision variable as box constraints, instead of linear inequality constraints, at least for NLP and interior point methods.
In this PR, these constraints:
SingleShootingare treated as box constraints. It applies to both$\mathbf{c_{(\bullet)}}$ it is no longer a box constraint and the associated bound is treated as a linear inequality constraint, like before.
LinMPCandNonLinMPC. Note that if there is a nonzero value in the associated softness parametersThe default QP solver for
LinMPCisOSQP.jl, and it does not support box constraint natively. It is still possible to define box constraints with the bridge mechanism ofJuMP.jl. The new defaultoptimargument forLinMPCisoptim=JuMP.Model(OSQP.MathOptInterfaceOSQP.Optimizer, add_bridges=true). It should not affect the performances since JuMP will automatically convert them as linear equality constraints, as it was the case before this PR. It's possible that the performances withDAQP.jlwill be improved however, since it supports box constraints natively.Warning
Constructing
LinMPCwithoptim=JuMP.Model(OSQP.MathOptInterfaceOSQP.Optimizer, add_bridges=false)will now throw an error. Please useadd_bridges=true(it should not affect performances).Let's see the benchmarks.