Skip to content

Commit

Permalink
Merge pull request #64 from JuliaControl/nonunicode_api
Browse files Browse the repository at this point in the history
Offer an alternative non-unicode API for keyword arguments
  • Loading branch information
franckgaga authored May 2, 2024
2 parents 60a9a18 + 4f2410e commit 54a626d
Show file tree
Hide file tree
Showing 9 changed files with 253 additions and 143 deletions.
4 changes: 2 additions & 2 deletions docs/src/manual/nonlinmpc.md
Original file line number Diff line number Diff line change
Expand Up @@ -73,10 +73,10 @@ plot(res, plotu=false)
savefig(ans, "plot1_NonLinMPC.svg"); nothing # hide
```

The [`setname!`](@ref) function allows customizing the Y-axis labels.

![plot1_NonLinMPC](plot1_NonLinMPC.svg)

The [`setname!`](@ref) function allows customizing the Y-axis labels.

## Nonlinear Model Predictive Controller

An [`UnscentedKalmanFilter`](@ref) estimates the plant state :
Expand Down
42 changes: 28 additions & 14 deletions src/controller/construct.jl
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,14 @@ for details on bounds and softness parameters ``\mathbf{c}``. The output and ter
constraints are all soft by default. See Extended Help for time-varying constraints.
# Arguments
!!! info
The keyword arguments `Δumin`, `Δumax`, `c_Δumin`, `c_Δumax`, `x̂min`, `x̂max`, `c_x̂min`,
`c_x̂max` and their capital letter versions have non-Unicode alternatives e.g.
*`Deltaumin`*, *`xhatmax`* and *`C_Deltaumin`*
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).
- `mpc::PredictiveController` : predictive controller to set constraints
- `umin=fill(-Inf,nu)` / `umax=fill(+Inf,nu)` : manipulated input bound ``\mathbf{u_{min/max}}``
- `Δumin=fill(-Inf,nu)` / `Δumax=fill(+Inf,nu)` : manipulated input increment bound ``\mathbf{Δu_{min/max}}``
Expand Down Expand Up @@ -114,20 +122,26 @@ LinMPC controller with a sample time Ts = 4.0 s, OSQP optimizer, SteadyKalmanFil
"""
function setconstraint!(
mpc::PredictiveController;
umin = nothing, umax = nothing,
Δumin = nothing, Δumax = nothing,
ymin = nothing, ymax = nothing,
x̂min = nothing, x̂max = nothing,
c_umin = nothing, c_umax = nothing,
c_Δumin = nothing, c_Δumax = nothing,
c_ymin = nothing, c_ymax = nothing,
c_x̂min = nothing, c_x̂max = nothing,
Umin = nothing, Umax = nothing,
ΔUmin = nothing, ΔUmax = nothing,
Ymin = nothing, Ymax = nothing,
C_umax = nothing, C_umin = nothing,
C_Δumax = nothing, C_Δumin = nothing,
C_ymax = nothing, C_ymin = nothing,
umin = nothing, umax = nothing,
Deltaumin = nothing, Deltaumax = nothing,
ymin = nothing, ymax = nothing,
xhatmin = nothing, xhatmax = nothing,
c_umin = nothing, c_umax = nothing,
c_Deltaumin = nothing, c_Deltaumax = nothing,
c_ymin = nothing, c_ymax = nothing,
c_xhatmin = nothing, c_xhatmax = nothing,
Umin = nothing, Umax = nothing,
DeltaUmin = nothing, DeltaUmax = nothing,
Ymin = nothing, Ymax = nothing,
C_umax = nothing, C_umin = nothing,
C_Deltaumax = nothing, C_Deltaumin = nothing,
C_ymax = nothing, C_ymin = nothing,
Δumin = Deltaumin, Δumax = Deltaumax,
x̂min = xhatmin, x̂max = xhatmax,
c_Δumin = c_Deltaumin, c_Δumax = c_Deltaumax,
c_x̂min = c_xhatmin, c_x̂max = c_xhatmax,
ΔUmin = DeltaUmin, ΔUmax = DeltaUmax,
C_Δumin = C_Deltaumin, C_Δumax = C_Deltaumax,
)
model, con, optim = mpc.estim.model, mpc.con, mpc.optim
nu, ny, nx̂, Hp, Hc = model.nu, model.ny, mpc.estim.nx̂, mpc.Hp, mpc.Hc
Expand Down
60 changes: 40 additions & 20 deletions src/controller/execute.jl
Original file line number Diff line number Diff line change
Expand Up @@ -24,15 +24,19 @@ Calling a [`PredictiveController`](@ref) object calls this method.
See also [`LinMPC`](@ref), [`ExplicitMPC`](@ref), [`NonLinMPC`](@ref).
# Arguments
Keyword arguments in *`italic`* are non-Unicode alternatives.
- `mpc::PredictiveController` : solve optimization problem of `mpc`.
- `ry=mpc.estim.model.yop` : current output setpoints ``\mathbf{r_y}(k)``.
- `d=[]` : current measured disturbances ``\mathbf{d}(k)``.
- `D̂=repeat(d, mpc.Hp)` : predicted measured disturbances ``\mathbf{D̂}``, constant in the
future by default or ``\mathbf{d̂}(k+j)=\mathbf{d}(k)`` for ``j=1`` to ``H_p``.
- `R̂y=repeat(ry, mpc.Hp)` : predicted output setpoints ``\mathbf{R̂_y}``, constant in the
future by default or ``\mathbf{r̂_y}(k+j)=\mathbf{r_y}(k)`` for ``j=1`` to ``H_p``.
- `R̂u=repeat(mpc.estim.model.uop, mpc.Hp)` : predicted manipulated input setpoints, constant
in the future by default or ``\mathbf{r̂_u}(k+j)=\mathbf{u_{op}}`` for ``j=0`` to ``H_p-1``.
- `D̂=repeat(d, mpc.Hp)` or *`Dhat`* : predicted measured disturbances ``\mathbf{D̂}``, constant
in the future by default or ``\mathbf{d̂}(k+j)=\mathbf{d}(k)`` for ``j=1`` to ``H_p``.
- `R̂y=repeat(ry, mpc.Hp)` or *`Rhaty`* : predicted output setpoints ``\mathbf{R̂_y}``, constant
in the future by default or ``\mathbf{r̂_y}(k+j)=\mathbf{r_y}(k)`` for ``j=1`` to ``H_p``.
- `R̂u=repeat(mpc.estim.model.uop, mpc.Hp)` or *`Rhatu`* : predicted manipulated input
setpoints, constant in the future by default or ``\mathbf{r̂_u}(k+j)=\mathbf{u_{op}}`` for
``j=0`` to ``H_p-1``.
- `ym=nothing` : current measured outputs ``\mathbf{y^m}(k)``, only required if `mpc.estim`
is an [`InternalModel`](@ref).
Expand All @@ -49,10 +53,13 @@ function moveinput!(
mpc::PredictiveController,
ry::Vector = mpc.estim.model.yop,
d ::Vector = empty(mpc.estim.x̂0);
::Vector = repeat(d, mpc.Hp),
R̂y::Vector = repeat(ry, mpc.Hp),
R̂u::Vector = mpc.noR̂u ? empty(mpc.estim.x̂0) : repeat(mpc.estim.model.uop, mpc.Hp),
ym::Union{Vector, Nothing} = nothing
Dhat ::Vector = repeat(d, mpc.Hp),
Rhaty::Vector = repeat(ry, mpc.Hp),
Rhatu::Vector = mpc.noR̂u ? empty(mpc.estim.x̂0) : repeat(mpc.estim.model.uop, mpc.Hp),
ym::Union{Vector, Nothing} = nothing,
= Dhat,
R̂y = Rhaty,
R̂u = Rhatu
)
validate_args(mpc, ry, d, D̂, R̂y, R̂u)
initpred!(mpc, mpc.estim.model, d, ym, D̂, R̂y, R̂u)
Expand All @@ -73,19 +80,22 @@ Get additional info about `mpc` [`PredictiveController`](@ref) optimum for troub
The function should be called after calling [`moveinput!`](@ref). It returns the dictionary
`info` with the following fields:
- `:ΔU` : optimal manipulated input increments over ``H_c``, ``\mathbf{ΔU}``
- `:ϵ` : optimal slack variable, ``ϵ``
!!! info
Fields in *`italic`* are non-Unicode alternatives.
- `:ΔU` or *`:DeltaU`* : optimal manipulated input increments over ``H_c``, ``\mathbf{ΔU}``
- `:ϵ` or *`:epsilon`* : optimal slack variable, ``ϵ``
- `:D̂` or *`:Dhat`* : predicted measured disturbances over ``H_p``, ``\mathbf{D̂}``
- `:ŷ` or *`:yhat`* : current estimated output, ``\mathbf{ŷ}(k)``
- `:Ŷ` or *`:Yhat`* : optimal predicted outputs over ``H_p``, ``\mathbf{Ŷ}``
- `:Ŷs` or *`:Yhats`* : predicted stochastic output over ``H_p`` of [`InternalModel`](@ref), ``\mathbf{Ŷ_s}``
- `:R̂y` or *`:Rhaty`* : predicted output setpoint over ``H_p``, ``\mathbf{R̂_y}``
- `:R̂u` or *`:Rhatu`* : predicted manipulated input setpoint over ``H_p``, ``\mathbf{R̂_u}``
- `:x̂end` or *`:xhatend`* : optimal terminal states, ``\mathbf{x̂}_{k-1}(k+H_p)``
- `:J` : objective value optimum, ``J``
- `:U` : optimal manipulated inputs over ``H_p``, ``\mathbf{U}``
- `:u` : current optimal manipulated input, ``\mathbf{u}(k)``
- `:d` : current measured disturbance, ``\mathbf{d}(k)``
- `:D̂` : predicted measured disturbances over ``H_p``, ``\mathbf{D̂}``
- `:ŷ` : current estimated output, ``\mathbf{ŷ}(k)``
- `:Ŷ` : optimal predicted outputs over ``H_p``, ``\mathbf{Ŷ}``
- `:x̂end`: optimal terminal states, ``\mathbf{x̂}_{k-1}(k+H_p)``
- `:Ŷs` : predicted stochastic output over ``H_p`` of [`InternalModel`](@ref), ``\mathbf{Ŷ_s}``
- `:R̂y` : predicted output setpoint over ``H_p``, ``\mathbf{R̂_y}``
- `:R̂u` : predicted manipulated input setpoint over ``H_p``, ``\mathbf{R̂_u}``
For [`LinMPC`](@ref) and [`NonLinMPC`](@ref), the field `:sol` also contains the optimizer
solution summary that can be printed. Lastly, the optimal economic cost `:JE` is also
Expand Down Expand Up @@ -129,6 +139,16 @@ function getinfo(mpc::PredictiveController{NT}) where NT<:Real
info[:Ŷs] = Ŷs
info[:R̂y] = mpc.R̂y0 + mpc.Yop
info[:R̂u] = mpc.R̂u0 + mpc.Uop
# --- non-Unicode fields ---
info[:DeltaU] = info[:ΔU]
info[:epsilon] = info[]
info[:Dhat] = info[:D̂]
info[:yhat] = info[:ŷ]
info[:Yhat] = info[:Ŷ]
info[:xhatend] = info[:x̂end]
info[:Yhats] = info[:Ŷs]
info[:Rhaty] = info[:R̂y]
info[:Rhatu] = info[:R̂u]
info = addinfo!(info, mpc)
return info
end
Expand Down Expand Up @@ -498,7 +518,7 @@ updatestate!(::PredictiveController, _ ) = throw(ArgumentError("missing measured
"""
setstate!(mpc::PredictiveController, x̂) -> mpc
Set the estimate at `mpc.estim.x̂`.
Set `mpc.estim.x̂0` to `x̂ - estim.x̂op` from the argument `x̂`.
"""
setstate!(mpc::PredictiveController, x̂) = (setstate!(mpc.estim, x̂); return mpc)

Expand Down
139 changes: 88 additions & 51 deletions src/estimator/kalman.jl
Original file line number Diff line number Diff line change
Expand Up @@ -86,21 +86,24 @@ the rows of ``\mathbf{Ĉ, D̂_d}`` that correspond to measured outputs ``\mathb
unmeasured ones, for ``\mathbf{Ĉ^u, D̂_d^u}``).
# Arguments
!!! info
Keyword arguments in *`italic`* are non-Unicode alternatives.
- `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.
- `σQ=fill(1/model.nx,model.nx)` or *`sigmaQ`* : main diagonal of the process noise
covariance ``\mathbf{Q}`` of `model`, specified as a standard deviation vector.
- `σR=fill(1,length(i_ym))` or *`sigmaR`* : 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).
- `σQint_u=fill(1,sum(nint_u))` or *`sigmaQint_u`* : same than `σQ` but for the unmeasured
disturbances at manipulated inputs ``\mathbf{Q_{int_u}}`` (composed of integrators).
- `σQint_ym=fill(1,sum(nint_ym))` or *`sigmaQint_u`* : same than `σQ` for the unmeasured
disturbances at measured outputs ``\mathbf{Q_{int_{ym}}}`` (composed of integrators).
# Examples
```jldoctest
Expand Down Expand Up @@ -139,12 +142,16 @@ SteadyKalmanFilter estimator with a sample time Ts = 0.5 s, LinModel and:
function SteadyKalmanFilter(
model::SM;
i_ym::IntRangeOrVector = 1:model.ny,
σQ::Vector = fill(1/model.nx, model.nx),
σR::Vector = fill(1, length(i_ym)),
sigmaQ = fill(1/model.nx, model.nx),
sigmaR = fill(1, length(i_ym)),
nint_u ::IntVectorOrInt = 0,
σQint_u::Vector = fill(1, max(sum(nint_u), 0)),
nint_ym::IntVectorOrInt = default_nint(model, i_ym, nint_u),
σQint_ym::Vector = fill(1, max(sum(nint_ym), 0))
sigmaQint_u = fill(1, max(sum(nint_u), 0)),
sigmaQint_ym = fill(1, max(sum(nint_ym), 0)),
σQ = sigmaQ,
σR = sigmaR,
σQint_u = sigmaQint_u,
σQint_ym = sigmaQint_ym,
) where {NT<:Real, SM<:LinModel{NT}}
# estimated covariances matrices (variance = σ²) :
= Hermitian(diagm(NT[σQ; σQint_u; σQint_ym ].^2), :L)
Expand Down Expand Up @@ -266,13 +273,16 @@ its initial value with ``\mathbf{P̂}_{-1}(0) =
\mathrm{diag}\{ \mathbf{P}(0), \mathbf{P_{int_{u}}}(0), \mathbf{P_{int_{ym}}}(0) \}``.
# Arguments
!!! info
Keyword arguments in *`italic`* are non-Unicode alternatives.
- `model::LinModel` : (deterministic) model for the estimations.
- `σP_0=fill(1/model.nx,model.nx)` : main diagonal of the initial estimate covariance
``\mathbf{P}(0)``, specified as a standard deviation vector.
- `σPint_u_0=fill(1,sum(nint_u))` : same than `σP_0` but for the unmeasured disturbances at
manipulated inputs ``\mathbf{P_{int_u}}(0)`` (composed of integrators).
- `σPint_ym_0=fill(1,sum(nint_ym))` : same than `σP_0` but for the unmeasured disturbances
at measured outputs ``\mathbf{P_{int_{ym}}}(0)`` (composed of integrators).
- `σP_0=fill(1/model.nx,model.nx)` or *`sigmaP_0`* : main diagonal of the initial estimate
covariance ``\mathbf{P}(0)``, specified as a standard deviation vector.
- `σPint_u_0=fill(1,sum(nint_u))` or *`sigmaPint_u_0`* : same than `σP_0` but for the unmeasured
disturbances at manipulated inputs ``\mathbf{P_{int_u}}(0)`` (composed of integrators).
- `σPint_ym_0=fill(1,sum(nint_ym))` or *`sigmaPint_ym_0`* : same than `σP_0` but for the unmeasured
disturbances at measured outputs ``\mathbf{P_{int_{ym}}}(0)`` (composed of integrators).
- `<keyword arguments>` of [`SteadyKalmanFilter`](@ref) constructor.
# Examples
Expand All @@ -291,15 +301,22 @@ KalmanFilter estimator with a sample time Ts = 0.5 s, LinModel and:
function KalmanFilter(
model::SM;
i_ym::IntRangeOrVector = 1:model.ny,
σP_0::Vector = fill(1/model.nx, model.nx),
σQ ::Vector = fill(1/model.nx, model.nx),
σR ::Vector = fill(1, length(i_ym)),
nint_u ::IntVectorOrInt = 0,
σQint_u ::Vector = fill(1, max(sum(nint_u), 0)),
σPint_u_0 ::Vector = fill(1, max(sum(nint_u), 0)),
nint_ym ::IntVectorOrInt = default_nint(model, i_ym, nint_u),
σQint_ym ::Vector = fill(1, max(sum(nint_ym), 0)),
σPint_ym_0::Vector = fill(1, max(sum(nint_ym), 0)),
sigmaP_0 = fill(1/model.nx, model.nx),
sigmaQ = fill(1/model.nx, model.nx),
sigmaR = fill(1, length(i_ym)),
nint_u ::IntVectorOrInt = 0,
nint_ym::IntVectorOrInt = default_nint(model, i_ym, nint_u),
sigmaPint_u_0 = fill(1, max(sum(nint_u), 0)),
sigmaQint_u = fill(1, max(sum(nint_u), 0)),
sigmaPint_ym_0 = fill(1, max(sum(nint_ym), 0)),
sigmaQint_ym = fill(1, max(sum(nint_ym), 0)),
σP_0 = sigmaP_0,
σQ = sigmaQ,
σR = sigmaR,
σPint_u_0 = sigmaPint_u_0,
σQint_u = sigmaQint_u,
σPint_ym_0 = sigmaPint_ym_0,
σQint_ym = sigmaQint_ym,
) where {NT<:Real, SM<:LinModel{NT}}
# estimated covariances matrices (variance = σ²) :
P̂_0 = Hermitian(diagm(NT[σP_0; σPint_u_0; σPint_ym_0].^2), :L)
Expand Down Expand Up @@ -440,10 +457,13 @@ represents the measured outputs of ``\mathbf{ĥ}`` function (and unmeasured one
``\mathbf{ĥ^u}``).
# Arguments
!!! info
Keyword arguments in *`italic`* are non-Unicode alternatives.
- `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)``.
- `κ=0` : kappa parameter, another spread parameter ``(0 ≤ κ ≤ 3)``.
- `α=1e-3` or *`alpha`* : alpha parameter, spread of the state distribution ``(0 < α ≤ 1)``.
- `β=2` or *`beta`* : beta parameter, skewness and kurtosis of the states distribution ``(β ≥ 0)``.
- `κ=0` or *`kappa`* : kappa parameter, another spread parameter ``(0 ≤ κ ≤ 3)``.
- `<keyword arguments>` of [`SteadyKalmanFilter`](@ref) constructor.
- `<keyword arguments>` of [`KalmanFilter`](@ref) constructor.
Expand All @@ -470,18 +490,28 @@ UnscentedKalmanFilter estimator with a sample time Ts = 10.0 s, NonLinModel and:
function UnscentedKalmanFilter(
model::SM;
i_ym::IntRangeOrVector = 1:model.ny,
σP_0::Vector = fill(1/model.nx, model.nx),
σQ ::Vector = fill(1/model.nx, model.nx),
σR ::Vector = fill(1, length(i_ym)),
nint_u ::IntVectorOrInt = 0,
σQint_u ::Vector = fill(1, max(sum(nint_u), 0)),
σPint_u_0 ::Vector = fill(1, max(sum(nint_u), 0)),
nint_ym ::IntVectorOrInt = default_nint(model, i_ym, nint_u),
σQint_ym ::Vector = fill(1, max(sum(nint_ym), 0)),
σPint_ym_0::Vector = fill(1, max(sum(nint_ym), 0)),
α::Real = 1e-3,
β::Real = 2,
κ::Real = 0
sigmaP_0 = fill(1/model.nx, model.nx),
sigmaQ = fill(1/model.nx, model.nx),
sigmaR = fill(1, length(i_ym)),
nint_u ::IntVectorOrInt = 0,
nint_ym::IntVectorOrInt = default_nint(model, i_ym, nint_u),
sigmaPint_u_0 = fill(1, max(sum(nint_u), 0)),
sigmaQint_u = fill(1, max(sum(nint_u), 0)),
sigmaPint_ym_0 = fill(1, max(sum(nint_ym), 0)),
sigmaQint_ym = fill(1, max(sum(nint_ym), 0)),
alpha::Real = 1e-3,
beta ::Real = 2,
kappa::Real = 0,
σP_0 = sigmaP_0,
σQ = sigmaQ,
σR = sigmaR,
σPint_u_0 = sigmaPint_u_0,
σQint_u = sigmaQint_u,
σPint_ym_0 = sigmaPint_ym_0,
σQint_ym = sigmaQint_ym,
α = alpha,
β = beta,
κ = kappa,
) where {NT<:Real, SM<:SimModel{NT}}
# estimated covariances matrices (variance = σ²) :
P̂_0 = Hermitian(diagm(NT[σP_0; σPint_u_0; σPint_ym_0].^2), :L)
Expand Down Expand Up @@ -732,15 +762,22 @@ ExtendedKalmanFilter estimator with a sample time Ts = 5.0 s, NonLinModel and:
function ExtendedKalmanFilter(
model::SM;
i_ym::IntRangeOrVector = 1:model.ny,
σP_0::Vector = fill(1/model.nx, model.nx),
σQ ::Vector = fill(1/model.nx, model.nx),
σR ::Vector = fill(1, length(i_ym)),
nint_u ::IntVectorOrInt = 0,
σQint_u ::Vector = fill(1, max(sum(nint_u), 0)),
σPint_u_0 ::Vector = fill(1, max(sum(nint_u), 0)),
nint_ym ::IntVectorOrInt = default_nint(model, i_ym, nint_u),
σQint_ym ::Vector = fill(1, max(sum(nint_ym), 0)),
σPint_ym_0::Vector = fill(1, max(sum(nint_ym), 0)),
sigmaP_0 = fill(1/model.nx, model.nx),
sigmaQ = fill(1/model.nx, model.nx),
sigmaR = fill(1, length(i_ym)),
nint_u ::IntVectorOrInt = 0,
nint_ym::IntVectorOrInt = default_nint(model, i_ym, nint_u),
sigmaPint_u_0 = fill(1, max(sum(nint_u), 0)),
sigmaQint_u = fill(1, max(sum(nint_u), 0)),
sigmaPint_ym_0 = fill(1, max(sum(nint_ym), 0)),
sigmaQint_ym = fill(1, max(sum(nint_ym), 0)),
σP_0 = sigmaP_0,
σQ = sigmaQ,
σR = sigmaR,
σPint_u_0 = sigmaPint_u_0,
σQint_u = sigmaQint_u,
σPint_ym_0 = sigmaPint_ym_0,
σQint_ym = sigmaQint_ym,
) where {NT<:Real, SM<:SimModel{NT}}
# estimated covariances matrices (variance = σ²) :
P̂_0 = Hermitian(diagm(NT[σP_0; σPint_u_0; σPint_ym_0].^2), :L)
Expand Down
Loading

0 comments on commit 54a626d

Please sign in to comment.