Skip to content

Commit 8dbbe78

Browse files
committed
breaking change: continuous dynamics by default for NonLinModel
1 parent 55d10fd commit 8dbbe78

File tree

14 files changed

+118
-99
lines changed

14 files changed

+118
-99
lines changed

docs/src/manual/nonlinmpc.md

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -53,13 +53,13 @@ const par = (9.8, 0.4, 1.2, 0.3)
5353
f(x, u, _ ) = pendulum(par, x, u)
5454
h(x, _ ) = [180/π*x[1]] # [°]
5555
Ts, nu, nx, ny = 0.1, 1, 2, 1
56-
solver = RungeKutta()
57-
model = NonLinModel(f, h, Ts, nu, nx, ny; solver)
56+
model = NonLinModel(f, h, Ts, nu, nx, ny)
5857
```
5958

6059
The output function ``\mathbf{h}`` converts the ``θ`` angle to degrees. Note that special
6160
characters like ``θ`` can be typed in the Julia REPL or VS Code by typing `\theta` and
6261
pressing the `<TAB>` key. The tuple `par` is constant here to improve the [performance](https://docs.julialang.org/en/v1/manual/performance-tips/#Avoid-untyped-global-variables).
62+
Note that a 4th order [`RungeKutta`](@ref) differential equation solver is used by default.
6363
It is good practice to first simulate `model` using [`sim!`](@ref) as a quick sanity check:
6464

6565
```@example 1
@@ -92,7 +92,7 @@ estimator tuning is tested on a plant with a 25 % larger friction coefficient ``
9292
```@example 1
9393
const par_plant = (par[1], par[2], 1.25*par[3], par[4])
9494
f_plant(x, u, _ ) = pendulum(par_plant, x, u)
95-
plant = NonLinModel(f_plant, h, Ts, nu, nx, ny; solver)
95+
plant = NonLinModel(f_plant, h, Ts, nu, nx, ny)
9696
res = sim!(estim, N, [0.5], plant=plant, y_noise=[0.5])
9797
plot(res, plotu=false, plotxwithx̂=true)
9898
savefig(ans, "plot2_NonLinMPC.svg"); nothing # hide
@@ -170,8 +170,8 @@ Kalman Filter similar to the previous one (``\mathbf{y^m} = θ`` and ``\mathbf{y
170170
```@example 1
171171
h2(x, _ ) = [180/π*x[1], x[2]]
172172
nu, nx, ny = 1, 2, 2
173-
model2 = NonLinModel(f , h2, Ts, nu, nx, ny; solver)
174-
plant2 = NonLinModel(f_plant, h2, Ts, nu, nx, ny; solver)
173+
model2 = NonLinModel(f , h2, Ts, nu, nx, ny)
174+
plant2 = NonLinModel(f_plant, h2, Ts, nu, nx, ny)
175175
estim2 = UnscentedKalmanFilter(model2; σQ, σR, nint_u, σQint_u, i_ym=[1])
176176
```
177177

@@ -184,7 +184,7 @@ function JE(UE, ŶE, _ )
184184
τ, ω = UE[1:end-1], ŶE[2:2:end-1]
185185
return Ts*sum(τ.*ω)
186186
end
187-
empc = NonLinMPC(estim2, Hp=20, Hc=2, Mwt=[0.5, 0], Nwt=[2.5], Ewt=4e3, JE=JE)
187+
empc = NonLinMPC(estim2, Hp=20, Hc=2, Mwt=[0.5, 0], Nwt=[2.5], Ewt=3e9, JE=JE)
188188
empc = setconstraint!(empc, umin=[-1.5], umax=[+1.5])
189189
```
190190

src/controller/nonlinmpc.jl

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -145,7 +145,7 @@ This method uses the default state estimator :
145145
146146
# Examples
147147
```jldoctest
148-
julia> model = NonLinModel((x,u,_)->0.5x+u, (x,_)->2x, 10.0, 1, 1, 1);
148+
julia> model = NonLinModel((x,u,_)->0.5x+u, (x,_)->2x, 10.0, 1, 1, 1, solver=nothing);
149149
150150
julia> mpc = NonLinMPC(model, Hp=20, Hc=1, Cwt=1e6)
151151
NonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, UnscentedKalmanFilter estimator and:
@@ -166,8 +166,8 @@ NonLinMPC controller with a sample time Ts = 10.0 s, Ipopt optimizer, UnscentedK
166166
167167
The optimization relies on [`JuMP`](https://github.com/jump-dev/JuMP.jl) automatic
168168
differentiation (AD) to compute the objective and constraint derivatives. Optimizers
169-
generally benefit from exact derivatives like AD. However, the [`NonLinModel`](@ref) `f`
170-
and `h` functions must be compatible with this feature. See [Automatic differentiation](https://jump.dev/JuMP.jl/stable/manual/nlp/#Automatic-differentiation)
169+
generally benefit from exact derivatives like AD. However, the [`NonLinModel`](@ref)
170+
state-space functions must be compatible with this feature. See [Automatic differentiation](https://jump.dev/JuMP.jl/stable/manual/nlp/#Automatic-differentiation)
171171
for common mistakes when writing these functions.
172172
173173
Note that if `Cwt≠Inf`, the attribute `nlp_scaling_max_gradient` of `Ipopt` is set to
@@ -221,7 +221,7 @@ Use custom state estimator `estim` to construct `NonLinMPC`.
221221
222222
# Examples
223223
```jldoctest
224-
julia> model = NonLinModel((x,u,_)->0.5x+u, (x,_)->2x, 10.0, 1, 1, 1);
224+
julia> model = NonLinModel((x,u,_)->0.5x+u, (x,_)->2x, 10.0, 1, 1, 1, solver=nothing);
225225
226226
julia> estim = UnscentedKalmanFilter(model, σQint_ym=[0.05]);
227227

src/estimator/kalman.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -434,7 +434,7 @@ represents the measured outputs of ``\mathbf{ĥ}`` function (and unmeasured one
434434
435435
# Examples
436436
```jldoctest
437-
julia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1);
437+
julia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1, solver=nothing);
438438
439439
julia> estim = UnscentedKalmanFilter(model, σR=[1], nint_ym=[2], σP0int_ym=[1, 1])
440440
UnscentedKalmanFilter estimator with a sample time Ts = 10.0 s, NonLinModel and:
@@ -685,7 +685,7 @@ automatic differentiation.
685685
686686
# Examples
687687
```jldoctest
688-
julia> model = NonLinModel((x,u,_)->0.2x+u, (x,_)->-3x, 5.0, 1, 1, 1);
688+
julia> model = NonLinModel((x,u,_)->0.2x+u, (x,_)->-3x, 5.0, 1, 1, 1, solver=nothing);
689689
690690
julia> estim = ExtendedKalmanFilter(model, σQ=[2], σQint_ym=[2], σP0=[0.1], σP0int_ym=[0.1])
691691
ExtendedKalmanFilter estimator with a sample time Ts = 5.0 s, NonLinModel and:

src/estimator/mhe/construct.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,7 @@ matrix ``\mathbf{P̂}_{k-N_k}(k-N_k+1)`` is estimated with an [`ExtendedKalmanFi
206206
207207
# Examples
208208
```jldoctest
209-
julia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1);
209+
julia> model = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1, solver=nothing);
210210
211211
julia> estim = MovingHorizonEstimator(model, He=5, σR=[1], σP0=[0.01])
212212
MovingHorizonEstimator estimator with a sample time Ts = 10.0 s, Ipopt optimizer, NonLinModel and:

src/model/linearization.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ Jacobians of ``\mathbf{f}`` and ``\mathbf{h}`` functions are automatically compu
2222
2323
# Examples
2424
```jldoctest
25-
julia> model = NonLinModel((x,u,_)->x.^3 + u, (x,_)->x, 0.1, 1, 1, 1);
25+
julia> model = NonLinModel((x,u,_)->x.^3 + u, (x,_)->x, 0.1, 1, 1, 1, solver=nothing);
2626
2727
julia> linmodel = linearize(model, x=[10.0], u=[0.0]);
2828

src/model/linmodel.jl

Lines changed: 27 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -35,26 +35,35 @@ end
3535
3636
Construct a linear model from state-space model `sys` with sampling time `Ts` in second.
3737
38-
`Ts` can be omitted when `sys` is discrete-time. Its state-space matrices are:
38+
The system `sys` can be continuous or discrete-time (`Ts` can be omitted for the latter).
39+
For continuous dynamics, its state-space equations are (discrete case in Extended Help):
3940
```math
4041
\begin{aligned}
41-
\mathbf{x}(k+1) &= \mathbf{A x}(k) + \mathbf{B z}(k) \\
42-
\mathbf{y}(k) &= \mathbf{C x}(k) + \mathbf{D z}(k)
42+
\mathbf{ẋ}(t) &= \mathbf{A x}(t) + \mathbf{B z}(t) \\
43+
\mathbf{y}(t) &= \mathbf{C x}(t) + \mathbf{D z}(t)
4344
\end{aligned}
4445
```
4546
with the state ``\mathbf{x}`` and output ``\mathbf{y}`` vectors. The ``\mathbf{z}`` vector
4647
comprises the manipulated inputs ``\mathbf{u}`` and measured disturbances ``\mathbf{d}``,
4748
in any order. `i_u` provides the indices of ``\mathbf{z}`` that are manipulated, and `i_d`,
48-
the measured disturbances. See Extended Help if `sys` is continuous-time, or discrete-time
49-
with `Ts ≠ sys.Ts`.
49+
the measured disturbances. The constructor automatically discretizes continuous systems,
50+
resamples discrete ones if `Ts ≠ sys.Ts`, compute a new realization if not minimal, and
51+
separate the ``\mathbf{z}`` terms in two parts (details in Extended Help). The rest of the
52+
documentation assumes discrete dynamics since all systems end up in this form.
5053
51-
See also [`ss`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/constructors/#ControlSystemsBase.ss),
52-
[`tf`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/constructors/#ControlSystemsBase.tf).
54+
See also [`ss`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/constructors/#ControlSystemsBase.ss)
5355
5456
# Examples
5557
```jldoctest
56-
julia> model = LinModel(ss(0.4, 0.2, 0.3, 0, 0.1))
57-
Discrete-time linear model with a sample time Ts = 0.1 s and:
58+
julia> model1 = LinModel(ss(-0.1, 1.0, 1.0, 0), 2.0) # continuous-time StateSpace
59+
LinModel with a sample time Ts = 2.0 s and:
60+
1 manipulated inputs u
61+
1 states x
62+
1 outputs y
63+
0 measured disturbances d
64+
65+
julia> model2 = LinModel(ss(0.4, 0.2, 0.3, 0, 0.1)) # discrete-time StateSpace
66+
LinModel with a sample time Ts = 0.1 s and:
5867
1 manipulated inputs u
5968
1 states x
6069
1 outputs y
@@ -63,9 +72,9 @@ Discrete-time linear model with a sample time Ts = 0.1 s and:
6372
6473
# Extended Help
6574
!!! details "Extended Help"
66-
State-space matrices are similar if `sys` is continuous (replace ``\mathbf{x}(k+1)``
67-
with ``\mathbf{ẋ}(t)`` and ``k`` with ``t`` on the LHS). In such a case, it's
68-
discretized with [`c2d`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/constructors/#ControlSystemsBase.c2d)
75+
State-space equations are similar if `sys` is discrete-time (replace ``\mathbf{ẋ}(t)``
76+
with ``\mathbf{x}(k+1)`` and ``k`` with ``t`` on the LHS). Continuous dynamics are
77+
internally discretized using [`c2d`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/constructors/#ControlSystemsBase.c2d)
6978
and `:zoh` for manipulated inputs, and `:tustin`, for measured disturbances. Lastly, if
7079
`sys` is discrete and the provided argument `Ts ≠ sys.Ts`, the system is resampled by
7180
using the aforementioned discretization methods.
@@ -124,8 +133,8 @@ function LinModel(
124133
sysd_dis = sysd
125134
end
126135
end
127-
# minreal to merge common poles if possible and ensure observability
128-
sys_dis = minreal([sysu_dis sysd_dis])
136+
# minreal to merge common poles if possible and ensure controllability/observability:
137+
sys_dis = minreal([sysu_dis sysd_dis]) # same realization if already minimal
129138
nu = length(i_u)
130139
A = sys_dis.A
131140
Bu = sys_dis.B[:,1:nu]
@@ -144,10 +153,12 @@ Convert to minimal realization state-space when `sys` is a transfer function.
144153
`sys` is equal to ``\frac{\mathbf{y}(s)}{\mathbf{z}(s)}`` for continuous-time, and
145154
``\frac{\mathbf{y}(z)}{\mathbf{z}(z)}``, for discrete-time.
146155
156+
See also [`tf`](https://juliacontrol.github.io/ControlSystems.jl/stable/lib/constructors/#ControlSystemsBase.tf)
157+
147158
# Examples
148159
```jldoctest
149160
julia> model = LinModel([tf(3, [30, 1]) tf(-2, [5, 1])], 0.5, i_d=[2])
150-
Discrete-time linear model with a sample time Ts = 0.5 s and:
161+
LinModel with a sample time Ts = 0.5 s and:
151162
1 manipulated inputs u
152163
2 states x
153164
1 outputs y
@@ -245,6 +256,4 @@ function h!(y, model::LinModel, x, d)
245256
mul!(y, model.C, x, 1, 1)
246257
mul!(y, model.Dd, d, 1, 1)
247258
return nothing
248-
end
249-
250-
typestr(model::LinModel) = "linear"
259+
end

src/model/nonlinmodel.jl

Lines changed: 43 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -24,24 +24,25 @@ struct NonLinModel{NT<:Real, F<:Function, H<:Function, DS<:DiffSolver} <: SimMod
2424
end
2525

2626
@doc raw"""
27-
NonLinModel{NT}(f::Function, h::Function, Ts, nu, nx, ny, nd=0; solver=nothing)
28-
NonLinModel{NT}(f!::Function, h!::Function, Ts, nu, nx, ny, nd=0; solver=nothing)
27+
NonLinModel{NT}(f::Function, h::Function, Ts, nu, nx, ny, nd=0; solver=RungeKutta(4))
28+
NonLinModel{NT}(f!::Function, h!::Function, Ts, nu, nx, ny, nd=0; solver=RungeKutta(4))
2929
3030
Construct a nonlinear model from state-space functions `f`/`f!` and `h`/`h!`.
3131
32-
Default arguments assume discrete-time dynamics, in which the state update ``\mathbf{f}``
33-
and output ``\mathbf{h}`` functions are defined as :
32+
Both continuous and discrete-time models are supported. The default arguments assume
33+
continuous dynamics. Use `solver=nothing` for the discrete case (see Extended Help). The
34+
functions are defined as:
3435
```math
35-
\begin{aligned}
36-
\mathbf{x}(k+1) &= \mathbf{f}\Big( \mathbf{x}(k), \mathbf{u}(k), \mathbf{d}(k) \Big) \\
37-
\mathbf{y}(k) &= \mathbf{h}\Big( \mathbf{x}(k), \mathbf{d}(k) \Big)
38-
\end{aligned}
36+
\begin{aligned}
37+
\mathbf{ẋ}(t) &= \mathbf{f}\Big( \mathbf{x}(t), \mathbf{u}(t), \mathbf{d}(t) \Big) \\
38+
\mathbf{y}(t) &= \mathbf{h}\Big( \mathbf{x}(t), \mathbf{d}(t) \Big)
39+
\end{aligned}
3940
```
40-
Denoting ``\mathbf{x}(k+1)`` as `xnext`, they can be implemented in two possible ways:
41+
They can be implemented in two possible ways:
4142
42-
- Non-mutating functions (out-of-place): they must be defined as `f(x, u, d) -> xnext` and
43+
- Non-mutating functions (out-of-place): defined them as `f(x, u, d) -> ` and
4344
`h(x, d) -> y`. This syntax is simple and intuitive but it allocates more memory.
44-
- Mutating functions (in-place): they must be defined as `f!(xnext, x, u, d) -> nothing` and
45+
- Mutating functions (in-place): defined them as `f!(, x, u, d) -> nothing` and
4546
`h!(y, x, d) -> nothing`. This syntax reduces the allocations and potentially the
4647
computational burden as well.
4748
@@ -50,10 +51,11 @@ manipulated inputs, states, outputs and measured disturbances.
5051
5152
!!! tip
5253
Replace the `d` argument with `_` if `nd = 0` (see Examples below).
53-
54-
Specifying a differential equation solver with the the `solver` keyword argument implies a
55-
continuous-time model (see Extended Help for details). The optional parameter `NT`
56-
explicitly set the number type of vectors (default to `Float64`).
54+
55+
A 4th order [`RungeKutta`](@ref) solver discretizes the differential equations by default.
56+
The rest of the documentation assumes discrete dynamics since all models end up in this
57+
form. The optional parameter `NT` explicitly set the number type of vectors (default to
58+
`Float64`).
5759
5860
!!! warning
5961
The two functions must be in pure Julia to use the model in [`NonLinMPC`](@ref),
@@ -63,19 +65,23 @@ See also [`LinModel`](@ref).
6365
6466
# Examples
6567
```jldoctest
66-
julia> model1 = NonLinModel((x,u,_)->0.1x+u, (x,_)->2x, 10.0, 1, 1, 1)
67-
Discrete-time nonlinear model with a sample time Ts = 10.0 s, empty solver and:
68+
julia> f!(ẋ, x, u, _ ) = (ẋ .= -0.2x .+ u; nothing);
69+
70+
julia> h!(y, x, _ ) = (y .= 0.1x; nothing);
71+
72+
julia> model1 = NonLinModel(f!, h!, 5.0, 1, 1, 1) # continuous dynamics
73+
NonLinModel with a sample time Ts = 5.0 s, RungeKutta solver and:
6874
1 manipulated inputs u
6975
1 states x
7076
1 outputs y
7177
0 measured disturbances d
7278
73-
julia> f!(ẋ, x, u, _ ) = (ẋ .= -0.1x .+ u; nothing);
79+
julia> f(x, u, _ ) = 0.1x + u;
7480
75-
julia> h!(y, x, _ ) = (y .= 2x; nothing);
81+
julia> h(x, _ ) = 2x;
7682
77-
julia> model2 = NonLinModel(f!, h!, 5.0, 1, 1, 1, solver=RungeKutta())
78-
Discrete-time nonlinear model with a sample time Ts = 5.0 s, RungeKutta solver and:
83+
julia> model2 = NonLinModel(f, h, 2.0, 1, 1, 1, solver=nothing) # discrete dynamics
84+
NonLinModel with a sample time Ts = 2.0 s, empty solver and:
7985
1 manipulated inputs u
8086
1 states x
8187
1 outputs y
@@ -84,17 +90,22 @@ Discrete-time nonlinear model with a sample time Ts = 5.0 s, RungeKutta solver a
8490
8591
# Extended Help
8692
!!! details "Extended Help"
87-
State-space equations are similar for continuous-time models (replace ``\mathbf{x}(k+1)``
88-
with ``\mathbf{ẋ}(t)`` and ``k`` with ``t`` on the LHS), with also two possible
89-
implementations (second one to reduce the allocations):
90-
91-
- Non-mutating functions (out-of-place): they must be defined as `f(x, u, d) -> ẋ` and
92-
`h(x, d) -> y`.
93-
- Mutating functions (in-place): they must be defined as `f!(ẋ, x, u, d) -> nothing` and
94-
`h!(y, x, d) -> nothing`.
93+
The state-space functions are similar for discrete dynamics:
94+
```math
95+
\begin{aligned}
96+
\mathbf{x}(k+1) &= \mathbf{f}\Big( \mathbf{x}(k), \mathbf{u}(k), \mathbf{d}(k) \Big) \\
97+
\mathbf{y}(k) &= \mathbf{h}\Big( \mathbf{x}(k), \mathbf{d}(k) \Big)
98+
\end{aligned}
99+
```
100+
with two possible implementations as well:
101+
102+
- Non-mutating functions: defined them as `f(x, u, d) -> xnext` and `h(x, d) -> y`.
103+
- Mutating functions: defined them as `f!(xnext, x, u, d) -> nothing` and
104+
`h!(y, x, d) -> nothing`.
95105
"""
96106
function NonLinModel{NT}(
97-
f::Function, h::Function, Ts::Real, nu::Int, nx::Int, ny::Int, nd::Int=0; solver=nothing
107+
f::Function, h::Function, Ts::Real, nu::Int, nx::Int, ny::Int, nd::Int=0;
108+
solver=RungeKutta(4)
98109
) where {NT<:Real}
99110
isnothing(solver) && (solver=EmptySolver())
100111
ismutating_f = validate_f(NT, f)
@@ -107,7 +118,8 @@ function NonLinModel{NT}(
107118
end
108119

109120
function NonLinModel(
110-
f::Function, h::Function, Ts::Real, nu::Int, nx::Int, ny::Int, nd::Int=0; solver=nothing
121+
f::Function, h::Function, Ts::Real, nu::Int, nx::Int, ny::Int, nd::Int=0;
122+
solver=RungeKutta(4)
111123
)
112124
return NonLinModel{Float64}(f, h, Ts, nu, nx, ny, nd; solver)
113125
end
@@ -158,6 +170,5 @@ f!(xnext, model::NonLinModel, x, u, d) = model.f!(xnext, x, u, d)
158170
"Call `h!(y, x, d)` with `model.h` method for [`NonLinModel`](@ref)."
159171
h!(y, model::NonLinModel, x, d) = model.h!(y, x, d)
160172

161-
typestr(model::NonLinModel) = "nonlinear"
162173
detailstr(model::NonLinModel) = ", $(typeof(model.solver).name.name) solver"
163174
detailstr(::NonLinModel{<:Real, <:Function, <:Function, <:EmptySolver}) = ", empty solver"

src/model/solver.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,11 +24,11 @@ struct RungeKutta <: DiffSolver
2424
end
2525

2626
"""
27-
RungeKutta(order::Int=4; supersample::Int=1)
27+
RungeKutta(order=4; supersample=1)
2828
2929
Create a Runge-Kutta solver with optional super-sampling.
3030
31-
Only the fourth order Runge-Kutta is supported for now. The keyword argument `supersample`
31+
Only the 4th order Runge-Kutta is supported for now. The keyword argument `supersample`
3232
provides the number of internal steps (default to 1 step).
3333
"""
3434
function RungeKutta(order::Int=4; supersample::Int=1)

src/plot_sim.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ on them (see Examples below). Note that the method mutates `plant` internal stat
101101
102102
# Examples
103103
```julia-repl
104-
julia> plant = NonLinModel((x,u,d)->0.1x+u+d, (x,_)->2x, 10.0, 1, 1, 1, 1);
104+
julia> plant = NonLinModel((x,u,d)->0.1x+u+d, (x,_)->2x, 10.0, 1, 1, 1, 1, solver=nothing);
105105
106106
julia> res = sim!(plant, 15, [0], [0], x0=[1])
107107
Simulation results of NonLinModel with 15 time steps.

src/precompile.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ sim!(exmpc, 3, [55, 30])
6767
f(x,u,_) = model.A*x + model.Bu*u
6868
h(x,_) = model.C*x
6969

70-
nlmodel = setop!(NonLinModel(f, h, Ts, 2, 2, 2), uop=[10, 10], yop=[50, 30])
70+
nlmodel = setop!(NonLinModel(f, h, Ts, 2, 2, 2, solver=nothing), uop=[10, 10], yop=[50, 30])
7171
y = nlmodel()
7272
nmpc_im = setconstraint!(NonLinMPC(InternalModel(nlmodel), Hp=10, Cwt=Inf), ymin=[45, -Inf])
7373
initstate!(nmpc_im, nlmodel.uop, y)

0 commit comments

Comments
 (0)