ControlSystemsBase.BodemagWorkspace
— MethodBodemagWorkspace(sys::LTISystem, N::Int)
BodemagWorkspace(sys::LTISystem, ω::AbstractVector)
BodemagWorkspace(R::Array{Complex{T}, 3}, mag::Array{T, 3})
BodemagWorkspace{T}(ny, nu, N)
Generate a workspace object for use with the in-place function bodemag!
. N
is the number of frequency points, alternatively, the input ω
can be provided instead of N
. Note: for threaded applications, create one workspace object per thread.
Arguments:
mag
: The output array ∈ 𝐑(ny, nu, nω)R
: Frequency-response array ∈ 𝐂(ny, nu, nω)
ControlSystemsBase.DelayLtiSystem
— Typestruct DelayLtiSystem{T, S <: Real} <: LTISystem
Represents an LTISystem with internal time-delay. See ?delay
for a convenience constructor.
ControlSystemsBase.DelayLtiSystem
— MethodDelayLtiSystem{T, S}(sys::StateSpace, Tau::AbstractVector{S}=Float64[]) where {T <: Number, S <: Real}
Create a delayed system by specifying both the system and time-delay vector. NOTE: if you want to create a system with simple input or output delays, use the Function delay(τ)
.
ControlSystemsBase.HammersteinWienerSystem
— Typestruct HammersteinWienerSystem{T} <: LTISystem
Represents an LTISystem with element-wise static nonlinearities at the inputs and outputs. See ?nonlinearity
for a convenience constructor. NOTE: The nonlinear functionality in ControlSystemsBase.jl is currently experimental and subject to breaking changes not respecting semantic versioning. Use at your own risk.
┌─────────┐
y◄───┤ │◄────u
│ P │
Δy┌───┤ │◄───┐Δu
│ └─────────┘ │
│ ┌───┐ │
└─────►│ f ├───────┘
└───┘
ControlSystemsBase.HammersteinWienerSystem
— MethodHammersteinWienerSystem{T, S}(sys::StateSpace, f::Vector{Function}=[]) where {T <: Number}
Create a nonlinear system by speciying both the system and nonlinearity. Users should prefer to use the function nonlinearity
.
ControlSystemsBase.LsimWorkspace
— MethodLsimWorkspace(sys::AbstractStateSpace, N::Int)
LsimWorkspace(sys::AbstractStateSpace, u::AbstractMatrix)
LsimWorkspace{T}(ny, nu, nx, N)
Generate a workspace object for use with the in-place function lsim!
. sys
is the discrete-time system to be simulated and N
is the number of time steps, alternatively, the input u
can be provided instead of N
. Note: for threaded applications, create one workspace object per thread.
ControlSystemsBase.PartitionedStateSpace
— TypeA StateSpace model with a partioning imposed according to
A | B1 B2 ——— ———————— C1 | D11 D12 C2 | D21 D22
It corresponds to partioned input and output signals u = [u1 u2]^T y = [y1 y2]^T
ControlSystemsBase.RootLocusResult
— TypeRootLocusResult{T} <: AbstractResult
Result structure containing the result of the root locus using rlocus
. The structure can be plotted using
result = rlocus(...)
plot(result; plotu=true, plotx=false)?
and destructured like
roots, Z, K = result
Fields:
roots::Tr
Z::Tz
K::Tk
sys::Ts
ControlSystemsBase.SimResult
— TypeSimResult{Ty, Tt, Tx, Tu, Ts} <: AbstractSimResult
Result structure containing the results of time-domain simulations using lsim, step, impulse
. The structure can be plotted using
result = lsim(...)
plot(result, plotu=true, plotx=false)
and destructured like
y, t, x, u = result
Fields:
y::Ty
t::Tt
x::Tx
u::Tu
sys::Ts
ControlSystemsBase.StateSpace
— TypeStateSpace{TE, T} <: AbstractStateSpace{TE}
An object representing a standard state space system.
See the function ss
for a user facing constructor as well as the documentation page creating systems.
Fields:
A::Matrix{T}
B::Matrix{T}
C::Matrix{T}
D::Matrix{T}
timeevol::TE
ControlSystemsBase.StaticStateSpace
— MethodStaticStateSpace(sys::AbstractStateSpace)
Return a HeteroStateSpace
where the system matrices are of type SMatrix.
NOTE: This function is fundamentally type unstable. For maximum performance, create the static system manually, or make use of the function-barrier technique.
ControlSystemsBase.StepInfo
— TypeStepInfo
Computed using stepinfo
Fields:
y0
: The initial value of the step response.yf
: The final value of the step response.stepsize
: The size of the step.peak
: The peak value of the step response.peaktime
: The time at which the peak occurs.overshoot
: The overshoot of the step response.settlingtime
: The time at which the step response has settled to withinsettling_th
of the final value.settlingtimeind::Int
: The index at which the step response has settled to withinsettling_th
of the final value.risetime
: The time at which the response rises fromrisetime_th[1]
torisetime_th[2]
of the final valuei10::Int
: The index at which the response reachesrisetime_th[1]
i90::Int
: The index at which the response reachesrisetime_th[2]
res::SimResult{SR}
: The simulation result used to compute the step response characteristics.settling_th
: The threshold used to computesettlingtime
andsettlingtimeind
.risetime_th
: The thresholds used to computerisetime
,i10
, andi90
.
ControlSystemsBase.TransferFunction
— MethodF(s)
, F(omega, true)
, F(z, false)
Notation for frequency response evaluation.
- F(s) evaluates the continuous-time transfer function F at s.
- F(omega,true) evaluates the discrete-time transfer function F at exp(imTsomega)
- F(z,false) evaluates the discrete-time transfer function F at z
Base.:*
— MethodSeries connection of partioned StateSpace systems.
Base.exp
— Methodexp(G::TransferFunction{Continuous,SisoRational})
Create a time delay of length tau
with exp(-τ*s)
where s=tf("s")
and τ
> 0.
See also: delay
which is arguably more convenient than this function.
Base.step
— Methody, t, x = step(sys[, tfinal])
y, t, x = step(sys[, t])
Calculate the step response of system sys
. If the final time tfinal
or time vector t
is not provided, one is calculated based on the system pole locations. The return value is a structure of type SimResult
that can be plotted or destructured as y, t, x = result
.
y
has size (ny, length(t), nu)
, x
has size (nx, length(t), nu)
ControlSystemsBase.G_CS
— MethodG_CS(P, C)
The closed-loop transfer function from (-) measurement noise or (+) reference to control signal. Technically, the transfer function is given by (1 + CP)⁻¹C
so SC
would be a better, but nonstandard name.
▲
│e₁
│ ┌─────┐
d₁────+──┴──► P ├─────┬──►e₄
│ └─────┘ │
│ │
│ ┌─────┐ -│
e₂◄──┴─────┤ C ◄──┬──+───d₂
└─────┘ │
│e₃
▼
input_sensitivity
is the transfer function from d₁ to e₁, (I + CP)⁻¹output_sensitivity
is the transfer function from d₂ to e₃, (I + PC)⁻¹input_comp_sensitivity
is the transfer function from d₁ to e₂, (I + CP)⁻¹CPoutput_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PCG_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹PG_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
ControlSystemsBase.G_PS
— MethodG_PS(P, C)
The closed-loop transfer function from load disturbance to plant output. Technically, the transfer function is given by (1 + PC)⁻¹P
so SP
would be a better, but nonstandard name.
▲
│e₁
│ ┌─────┐
d₁────+──┴──► P ├─────┬──►e₄
│ └─────┘ │
│ │
│ ┌─────┐ -│
e₂◄──┴─────┤ C ◄──┬──+───d₂
└─────┘ │
│e₃
▼
input_sensitivity
is the transfer function from d₁ to e₁, (I + CP)⁻¹output_sensitivity
is the transfer function from d₂ to e₃, (I + PC)⁻¹input_comp_sensitivity
is the transfer function from d₁ to e₂, (I + CP)⁻¹CPoutput_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PCG_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹PG_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
ControlSystemsBase._fix_conjugate_pairs!
— MethodTypically LAPACK returns a vector with, e.g., eigenvalues to a real matrix, they are paired up in exact conjugate pairs. This fact is used in some places for working with zpk representations of LTI systems. eigvals(A) returns a on this form, however, for generalized eigenvalues there is a small numerical discrepancy, which breaks some functions. This function fixes small discrepancies in the conjugate pairs.
ControlSystemsBase._linscale
— Methodp2 = _linscale(p::Polynomial, a)
Given a polynomial p
and a number a, returns the polynomials
p2such that
p2(s) == p(a*s)`.
ControlSystemsBase._printcoefficient
— MethodHeuristic function that tries to add parentheses when printing the coefficient for systems on zpk form. Should at least handle the following types Measurement, Dual, Sym.
ControlSystemsBase._processfreqplot
— Method_processfreqplot(plottype, system::LTISystem, [w])
_processfreqplot(plottype, system::AbstractVector{<:LTISystem}, [w])
Calculate default frequency vector and put system in array of not already array. plottype
is one of Val{:bode}, Val{:nyquist}, ...
for which _default_freq_vector
is defined. Check that system dimensions are compatible.
ControlSystemsBase._to1series
— MethodThis is a helper function to make multiple series into one series separated by Inf
. This makes plotting vastly more efficient. It's also useful to make many lines appear as a single series with a single legend entry.
ControlSystemsBase.acker
— Methodacker(A,B,P)
Implements Ackermann's formula for placing poles of (A-BK) in p
Ackermann's formula works for SISO systems only, but a trick is possible to make Ackermann work for MIMO systems: The code below introduces a random projection matrix P
that projects the input space to one dimension, and then shifts the application of P
from B
to K
.
nx = 5
nu = 2
A = randn(nx,nx)
B = randn(nx,nu)
P = randn(nu,1)
K = place(A,B*P,zeros(nx))
K2 = P*K
eigvals(A-B*K2)
See also place_knvd
which naturally handles MIMO systems.
ControlSystemsBase.add_input
— Functionadd_input(sys::AbstractStateSpace, B2::AbstractArray, D2 = 0)
Add inputs to sys
by forming
\[x' = Ax + [B \; B_2]u y = Cx + [D \; D_2]u\]
If B2
is an integer it will be interpreted as an index and an input matrix containing a single 1 at the specified index will be used.
Example: The following example forms an innovation model that takes innovations as inputs
G = ssrand(2,2,3, Ts=1)
K = kalman(G, I(G.nx), I(G.ny))
sys = add_input(G, K)
ControlSystemsBase.add_output
— Functionadd_output(sys::AbstractStateSpace, C2::AbstractArray, D2 = 0)
Add outputs to sys
by forming
\[x' = Ax + Bu y = [C; C_2]x + [D; D_2]u\]
If C2
is an integer it will be interpreted as an index and an output matrix containing a single 1 at the specified index will be used.
ControlSystemsBase.append
— Methodappend(systems::StateSpace...), append(systems::TransferFunction...)
Append systems in block diagonal form
ControlSystemsBase.are
— Methodare(::Continuous, A, B, Q, R)
Compute 'X', the solution to the continuous-time algebraic Riccati equation, defined as A'X + XA - (XB)R^-1(B'X) + Q = 0, where R is non-singular.
In an LQR problem, Q
is associated with the state penalty $x'Qx$ while R
is associated with the control penalty $u'Ru$. See lqr
for more details.
Uses MatrixEquations.arec
. For keyword arguments, see the docstring of ControlSystemsBase.MatrixEquations.arec
, note that they define the input arguments in a different order.
ControlSystemsBase.are
— Methodare(::Discrete, A, B, Q, R; kwargs...)
Compute X
, the solution to the discrete-time algebraic Riccati equation, defined as A'XA - X - (A'XB)(B'XB + R)^-1(B'XA) + Q = 0, where Q>=0 and R>0
In an LQR problem, Q
is associated with the state penalty $x'Qx$ while R
is associated with the control penalty $u'Ru$. See lqr
for more details.
Uses MatrixEquations.ared
. For keyword arguments, see the docstring of ControlSystemsBase.MatrixEquations.ared
, note that they define the input arguments in a different order.
ControlSystemsBase.array2mimo
— Methodarray2mimo(M::AbstractArray{<:LTISystem})
Take an array of LTISystem
s and create a single MIMO system.
ControlSystemsBase.balance
— FunctionS, P, B = balance(A[, perm=true])
Compute a similarity transform T = S*P
resulting in B = T\A*T
such that the row and column norms of B
are approximately equivalent. If perm=false
, the transformation will only scale A
using diagonal S
, and not permute A
(i.e., set P=I
).
ControlSystemsBase.balance_statespace
— FunctionA, B, C, T = balance_statespace{S}(A::Matrix{S}, B::Matrix{S}, C::Matrix{S}, perm::Bool=false)
sys, T = balance_statespace(sys::StateSpace, perm::Bool=false)
Computes a balancing transformation T
that attempts to scale the system so that the row and column norms of [TA/T TB; C/T 0] are approximately equal. If perm=true
, the states in A
are allowed to be reordered.
The inverse of sysb, T = balance_statespace(sys)
is given by similarity_transform(sysb, T)
This is not the same as finding a balanced realization with equal and diagonal observability and reachability gramians, see balreal
ControlSystemsBase.balance_transform
— FunctionT = balance_transform{R}(A::AbstractArray, B::AbstractArray, C::AbstractArray, perm::Bool=false)
T = balance_transform(sys::StateSpace, perm::Bool=false) = balance_transform(A,B,C,perm)
Computes a balancing transformation T
that attempts to scale the system so that the row and column norms of [TA/T TB; C/T 0] are approximately equal. If perm=true
, the states in A
are allowed to be reordered.
This is not the same as finding a balanced realization with equal and diagonal observability and reachability gramians, see balreal
See also balance_statespace
, balance
ControlSystemsBase.balreal
— Methodsysr, G, T = balreal(sys::StateSpace)
Calculates a balanced realization of the system sys, such that the observability and reachability gramians of the balanced system are equal and diagonal diagm(G)
. T
is the similarity transform between the old state x
and the new state z
such that Tz = x
.
Reference: Varga A., Balancing-free square-root algorithm for computing singular perturbation approximations.
ControlSystemsBase.baltrunc
— Methodsysr, G, T = baltrunc(sys::StateSpace; atol = √ϵ, rtol=1e-3, n = nothing, residual = false)
Reduces the state dimension by calculating a balanced realization of the system sys, such that the observability and reachability gramians of the balanced system are equal and diagonal diagm(G)
, and truncating it to order n
. If n
is not provided, it's chosen such that all states corresponding to singular values less than atol
and less that rtol σmax
are removed.
T
is the projection matrix between the old state x
and the newstate z
such that z = Tx
. T
will in general be a non-square matrix.
If residual = true
, matched static gain is achieved through "residualization", i.e., setting
\[0 = A_{21}x_{1} + A_{22}x_{2} + B_{2}u\]
where indices 1/2 correspond to the remaining/truncated states respectively.
See also gram
, balreal
Glad, Ljung, Reglerteori: Flervariabla och Olinjära metoder.
For more advanced model reduction, see RobustAndOptimalControl.jl - Model Reduction.
Extended help
Note: Gramian computations are sensitive to input-output scaling. For the result of a numerical balancing, gramian computation or truncation of MIMO systems to be meaningful, the inputs and outputs of the system must thus be scaled in a meaningful way. A common (but not the only) approach is:
- The outputs are scaled such that the maximum allowed control error, the maximum expected reference variation, or the maximum expected variation, is unity.
- The input variables are scaled to have magnitude one. This is done by dividing each variable by its maximum expected or allowed change, i.e., $u_{scaled} = u / u_{max}$
Without such scaling, the result of balancing will depend on the units used to measure the input and output signals, e.g., a change of unit for one output from meter to millimeter will make this output 1000x more important.
ControlSystemsBase.bode
— Methodmag, phase, w = bode(sys[, w]; unwrap=true)
Compute the magnitude and phase parts of the frequency response of system sys
at frequencies w
. See also bodeplot
mag
and phase
has size (ny, nu, length(w))
. If unwrap
is true (default), the function unwrap!
will be applied to the phase angles. This procedure is costly and can be avoided if the unwrapping is not required.
For higher performance, see the function bodemag!
that computes the magnitude only.
ControlSystemsBase.bodemag!
— Methodmag = bodemag!(ws::BodemagWorkspace, sys::LTISystem, w::AbstractVector)
Compute the Bode magnitude operating in-place on an instance of BodemagWorkspace
. Note that the returned magnitude array is aliased with ws.mag
. The output array mag
is ∈ 𝐑(ny, nu, nω).
ControlSystemsBase.bodeplot
— Functionfig = bodeplot(sys, args...)
bodeplot(LTISystem[sys1, sys2...], args...; plotphase=true, balance = true, kwargs...)
Create a Bode plot of the LTISystem
(s). A frequency vector w
can be optionally provided. To change the Magnitude scale see setPlotScale
. The default magnitude scale is "log10" (absolute scale).
- If
hz=true
, the plot x-axis will be displayed in Hertz, the input frequency vector is still treated as rad/s. balance
: Callbalance_statespace
on the system before plotting.
kwargs
is sent as argument to RecipesBase.plot.
ControlSystemsBase.bodev
— Methodbodev(sys::LTISystem, w::AbstractVector; $(Expr(:kw, :unwrap, true)))
For use with SISO systems where it acts the same as bode
but with the extra dimensions removed in the returned values.
ControlSystemsBase.bodev
— Methodbodev(sys::LTISystem; )
For use with SISO systems where it acts the same as bode
but with the extra dimensions removed in the returned values.
ControlSystemsBase.c2d
— Functionc2d(G::DelayLtiSystem, Ts, method=:zoh)
ControlSystemsBase.c2d
— Functionsysd = c2d(sys::AbstractStateSpace{<:Continuous}, Ts, method=:zoh; w_prewarp=0)
Gd = c2d(G::TransferFunction{<:Continuous}, Ts, method=:zoh)
Convert the continuous-time system sys
into a discrete-time system with sample time Ts
, using the specified method
(:zoh
, :foh
, :fwdeuler
or :tustin
). Note that the forward-Euler method generally requires the sample time to be very small relative to the time constants of the system.
method = :tustin
performs a bilinear transform with prewarp frequency w_prewarp
.
w_prewarp
: Frequency (rad/s) for pre-warping when using the Tustin method, has no effect for other methods.
See also c2d_x0map
ControlSystemsBase.c2d
— MethodQd = c2d(sys::StateSpace{Continuous}, Qc::Matrix, Ts; opt=:o)
Qd, Rd = c2d(sys::StateSpace{Continuous}, Qc::Matrix, Rc::Matrix, Ts; opt=:o)
Qd = c2d(sys::StateSpace{Discrete}, Qc::Matrix; opt=:o)
Qd, Rd = c2d(sys::StateSpace{Discrete}, Qc::Matrix, Rc::Matrix; opt=:o)
Sample a continuous-time covariance or LQR cost matrix to fit the provided discrete-time system.
If opt = :o
(default), the matrix is assumed to be a covariance matrix. The measurement covariance R
may also be provided. If opt = :c
, the matrix is instead assumed to be a cost matrix for an LQR problem.
Measurement covariance (here called Rc
) is usually estimated in discrete time, and is in this case not dependent on the sample rate. Discretization of the measurement covariance only makes sense when a continuous-time controller has been designed and the closest corresponding discrete-time controller is desired.
The method used comes from theorem 5 in the reference below.
Ref: "Discrete-time Solutions to the Continuous-time Differential Lyapunov Equation With Applications to Kalman Filtering", Patrik Axelsson and Fredrik Gustafsson
On singular covariance matrices: The traditional double integrator with covariance matrix Q = diagm([0,σ²])
can not be sampled with this method. Instead, the input matrix ("Cholesky factor") of Q
must be manually kept track of, e.g., the noise of variance σ²
enters like N = [0, 1]
which is sampled using ZoH and becomes Nd = [1/2 Ts^2; Ts]
which results in the covariance matrix σ² * Nd * Nd'
.
Example:
The following example designs a continuous-time LQR controller for a resonant system. This is simulated with OrdinaryDiffEq to allow the ODE integrator to also integrate the continuous-time LQR cost (the cost is added as an additional state variable). We then discretize both the system and the cost matrices and simulate the same thing. The discretization of an LQR contorller in this way is sometimes refered to as lqrd
.
using ControlSystemsBase, LinearAlgebra, OrdinaryDiffEq, Test
sysc = DemoSystems.resonant()
x0 = ones(sysc.nx)
Qc = [1 0.01; 0.01 2] # Continuous-time cost matrix for the state
Rc = I(1) # Continuous-time cost matrix for the input
L = lqr(sysc, Qc, Rc)
dynamics = function (xc, p, t)
x = xc[1:sysc.nx]
u = -L*x
dx = sysc.A*x + sysc.B*u
dc = dot(x, Qc, x) + dot(u, Rc, u)
return [dx; dc]
end
prob = ODEProblem(dynamics, [x0; 0], (0.0, 10.0))
sol = solve(prob, Tsit5(), reltol=1e-8, abstol=1e-8)
cc = sol.u[end][end] # Continuous-time cost
# Discrete-time version
Ts = 0.01
sysd = c2d(sysc, Ts)
Ld = lqr(sysd, Qd, Rd)
sold = lsim(sysd, (x, t) -> -Ld*x, 0:Ts:10, x0 = x0)
function cost(x, u, Q, R)
dot(x, Q, x) + dot(u, R, u)
end
cd = cost(sold.x, sold.u, Qd, Rd) # Discrete-time cost
@test cc ≈ cd rtol=0.01 # These should be similar
ControlSystemsBase.c2d_poly2poly
— Methodc2d_poly2poly(ro, Ts)
returns the polynomial coefficients in discrete time given polynomial coefficients in continuous time
ControlSystemsBase.c2d_roots2poly
— Methodc2d_roots2poly(ro, Ts)
returns the polynomial coefficients in discrete time given a vector of roots in continuous time
ControlSystemsBase.c2d_x0map
— Functionsysd, x0map = c2d_x0map(sys::AbstractStateSpace{<:Continuous}, Ts, method=:zoh; w_prewarp=0)
Returns the discretization sysd
of the system sys
and a matrix x0map
that transforms the initial conditions to the discrete domain by x0_discrete = x0map*[x0; u0]
See c2d
for further details.
ControlSystemsBase.charpoly
— MethodImplements: "An accurate and efficient algorithm for the computation of the characteristic polynomial of a general square matrix."
ControlSystemsBase.comp_sensitivity
— Method ▲
│e₁
│ ┌─────┐
d₁────+──┴──► P ├─────┬──►e₄
│ └─────┘ │
│ │
│ ┌─────┐ -│
e₂◄──┴─────┤ C ◄──┬──+───d₂
└─────┘ │
│e₃
▼
input_sensitivity
is the transfer function from d₁ to e₁, (I + CP)⁻¹output_sensitivity
is the transfer function from d₂ to e₃, (I + PC)⁻¹input_comp_sensitivity
is the transfer function from d₁ to e₂, (I + CP)⁻¹CPoutput_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PCG_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹PG_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
ControlSystemsBase.convert_pidparams_from_standard
— Methodparam_p, param_i, param_d = convert_pidparams_from_standard(Kp, Ti, Td, form)
Convert parameters to form form
from :standard
form.
The form
can be chosen as one of the following
:standard
- $K_p(1 + 1/(T_i s) + T_ds)$:series
- $K_c(1 + 1/(τ_i s))(τ_d s + 1)$:parallel
- $K_p + K_i/s + K_d s$
ControlSystemsBase.convert_pidparams_from_to
— Methodconvert_pidparams_from_to(kp, ki, kd, from::Symbol, to::Symbol)
ControlSystemsBase.convert_pidparams_to_standard
— MethodKp, Ti, Td = convert_pidparams_to_standard(param_p, param_i, param_d, form)
Convert parameters from form form
to :standard
form.
The form
can be chosen as one of the following
:standard
- $K_p(1 + 1/(T_i s) + T_ds)$:series
- $K_c(1 + 1/(τ_i s))(τ_d s + 1)$:parallel
- $K_p + K_i/s + K_d s$
ControlSystemsBase.covar
— MethodP = covar(sys, W)
Calculate the stationary covariance P = E[y(t)y(t)']
of the output y
of a StateSpace
model sys
driven by white Gaussian noise w
with covariance E[w(t)w(τ)]=W*δ(t-τ)
(δ is the Dirac delta).
Remark: If sys
is unstable then the resulting covariance is a matrix of Inf
s. Entries corresponding to direct feedthrough (DWD' .!= 0) will equal Inf
for continuous-time systems.
ControlSystemsBase.ctrb
— Methodctrb(A, B)
ctrb(sys)
Compute the controllability matrix for the system described by (A, B)
or sys
.
Note that checking for controllability by computing the rank from ctrb
is not the most numerically accurate way, a better method is checking if gram(sys, :c)
is positive definite.
ControlSystemsBase.d2c
— FunctionQc = d2c(sys::AbstractStateSpace{<:Discrete}, Qd::AbstractMatrix; opt=:o)
Resample discrete-time covariance matrix belonging to sys
to the equivalent continuous-time matrix.
The method used comes from theorem 5 in the reference below.
If opt = :c
, the matrix is instead assumed to be a cost matrix for an LQR problem.
Ref: Discrete-time Solutions to the Continuous-time Differential Lyapunov Equation With Applications to Kalman Filtering Patrik Axelsson and Fredrik Gustafsson
ControlSystemsBase.d2c
— Functiond2c(sys::AbstractStateSpace{<:Discrete}, method::Symbol = :zoh; w_prewarp=0)
Convert discrete-time system to a continuous time system, assuming that the discrete-time system was discretized using method
. Available methods are `:zoh, :fwdeuler´.
w_prewarp
: Frequency for pre-warping when using the Tustin method, has no effect for other methods.
ControlSystemsBase.dab
— MethodX,Y = dab(A,B,C)
Solves the Diophantine-Aryabhatta-Bezout identity
$AX + BY = C$, where $A, B, C, X$ and $Y$ are polynomials and $deg Y = deg A - 1$.
See Computer-Controlled Systems: Theory and Design, Third Edition Karl Johan Åström, Björn Wittenmark
ControlSystemsBase.damp
— MethodWn, zeta, ps = damp(sys)
Compute the natural frequencies, Wn
, and damping ratios, zeta
, of the poles, ps
, of sys
ControlSystemsBase.dampreport
— Methoddampreport(sys)
Display a report of the poles, damping ratio, natural frequency, and time constant of the system sys
ControlSystemsBase.dcgain
— Functiondcgain(sys, ϵ=0)
Compute the dcgain of system sys
.
equal to G(0) for continuous-time systems and G(1) for discrete-time systems.
ϵ
can be provided to evaluate the dcgain with a small perturbation into the stability region of the complex plane.
ControlSystemsBase.deadzone
— Methoddeadzone(val)
deadzone(lower, upper)
Create a dead-zone nonlinearity.
y▲
│ /
│ /
lower │ /
─────|──┼──|───────► u
/ │ upper
/ │
/ │
NOTE: The nonlinear functionality in ControlSystemsBase.jl is currently experimental and subject to breaking changes not respecting semantic versioning. Use at your own risk.
Note: when composing linear systems with nonlinearities, it's often important to handle operating points correctly. See ControlSystemsBase.offset
for handling operating points.
ControlSystemsBase.delay
— Methoddelay(tau)
delay(tau, Ts)
delay(T::Type{<:Number}, tau)
delay(T::Type{<:Number}, tau, Ts)
Create a pure time delay of length τ
of type T
.
The type T
defaults to promote_type(Float64, typeof(tau))
.
If Ts
is given, the delay is discretized with sampling time Ts
and a discrete-time StateSpace object is returned.
Example:
Create a LTI system with an input delay of L
L = 1
tf(1, [1, 1])*delay(L)
s = tf("s")
tf(1, [1, 1])*exp(-s*L) # Equivalent to the version above
ControlSystemsBase.delayd_ss
— Methoddelayd_ss(τ, Ts)
Discrete-time statespace realization of a delay τ sampled with period Ts, i.e. of z^-N where N = τ / Ts.
τ must be a multiple of Ts.
ControlSystemsBase.delaymargin
— Methoddₘ = delaymargin(G::LTISystem)
Return the delay margin, dₘ. For discrete-time systems, the delay margin is normalized by the sample time, i.e., the value represents the margin in number of sample times. Only supports SISO systems.
ControlSystemsBase.det
— Methoddet(sys)
Compute the determinant of the Matrix sys
of SisoTf systems, returns a SisoTf system.
ControlSystemsBase.diagonalize
— Methoddsys = diagonalize(s::StateSpace, digits=12)
Diagonalizes the system such that the A-matrix is diagonal.
ControlSystemsBase.evalfr
— Methodevalfr(sys, x)
Evaluate the transfer function of the LTI system sys at the complex number s=x (continuous-time) or z=x (discrete-time).
For many values of x
, use freqresp
instead.
ControlSystemsBase.extended_gangoffour
— Functionextended_gangoffour(P, C, pos=true)
Returns a single statespace system that maps
w1
reference or measurement noisew2
load disturbance
to
z1
control errorz2
control input
z1 z2
▲ ┌─────┐ ▲ ┌─────┐
│ │ │ │ │ │
w1──+─┴─►│ C ├──┴───+─►│ P ├─┐
│ │ │ │ │ │ │
│ └─────┘ │ └─────┘ │
│ w2 │
└────────────────────────────┘
The returned system has the transfer-function matrix
\[\begin{bmatrix} I \\ C \end{bmatrix} (I + PC)^{-1} \begin{bmatrix} I & P \end{bmatrix}\]
or in code
# For SISO P
S = G[1, 1]
PS = G[1, 2]
CS = G[2, 1]
T = G[2, 2]
# For MIMO P
S = G[1:P.ny, 1:P.nu]
PS = G[1:P.ny, P.ny+1:end]
CS = G[P.ny+1:end, 1:P.ny]
T = G[P.ny+1:end, P.ny+1:end] # Input complimentary sensitivity function
The gang of four can be plotted like so
Gcl = extended_gangoffour(G, C) # Form closed-loop system
bodeplot(Gcl, lab=["S" "CS" "PS" "T"], plotphase=false) |> display # Plot gang of four
Note, the last input of Gcl is the negative of the PS
and T
transfer functions from gangoffour2
. To get a transfer matrix with the same sign as G_PS
and input_comp_sensitivity
, call extended_gangoffour(P, C, pos=false)
. See glover_mcfarlane
from RobustAndOptimalControl.jl for an extended example. See also ncfmargin
and feedback_control
from RobustAndOptimalControl.jl.
ControlSystemsBase.f_lsim
— Methodf_lsim(dx, x, p, t)
Internal function: Dynamics equation for simulation of a linear system.
Arguments:
dx
: State derivative vector written to in place.x
: Statep
: is equal to(A, B, u)
whereu(x, t)
returns the control inputt
: Time
ControlSystemsBase.feedback
— Methodfeedback(sys1::AbstractStateSpace, sys2::AbstractStateSpace;
U1=:, Y1=:, U2=:, Y2=:, W1=:, Z1=:, W2=Int[], Z2=Int[],
Wperm=:, Zperm=:, pos_feedback::Bool=false)
Basic use feedback(sys1, sys2)
forms the (negative) feedback interconnection
┌──────────────┐
◄──────────┤ sys1 │◄──── Σ ◄──────
│ │ │ │
│ └──────────────┘ -1
│ |
│ ┌──────────────┐ │
└─────►│ sys2 ├──────┘
│ │
└──────────────┘
If no second system sys2
is given, negative identity feedback (sys2 = 1
) is assumed.
Advanced use feedback
also supports more flexible use according to the figure below
┌──────────────┐
z1◄─────┤ sys1 │◄──────w1
┌─── y1◄─────┤ │◄──────u1 ◄─┐
│ └──────────────┘ │
│ α
│ ┌──────────────┐ │
└──► u2─────►│ sys2 ├───────►y2──┘
w2─────►│ ├───────►z2
└──────────────┘
U1
, W1
specifies the indices of the input signals of sys1
corresponding to u1
and w1
Y1
, Z1
specifies the indices of the output signals of sys1
corresponding to y1
and z1
U2
, W2
, Y2
, Z2
specifies the corresponding signals of sys2
Specify Wperm
and Zperm
to reorder the inputs (corresponding to [w1; w2]) and outputs (corresponding to [z1; z2]) in the resulting statespace model.
Negative feedback (α = -1) is the default. Specify pos_feedback=true
for positive feedback (α = 1).
See also lft
, starprod
, sensitivity
, input_sensitivity
, output_sensitivity
, comp_sensitivity
, input_comp_sensitivity
, output_comp_sensitivity
, G_PS
, G_CS
.
The manual section From block diagrams to code contains higher-level instructions on how to use this function.
See Zhou, Doyle, Glover (1996) for similar (somewhat less symmetric) formulas.
ControlSystemsBase.feedback
— Methodfeedback(sys)
feedback(sys1, sys2)
For a general LTI-system, feedback
forms the negative feedback interconnection
>-+ sys1 +-->
| |
(-)sys2 +
If no second system is given, negative identity feedback is assumed
ControlSystemsBase.feedback2dof
— Methodfeedback2dof(P,R,S,T)
feedback2dof(B,A,R,S,T)
- Return
BT/(AR+ST)
where B and A are the numerator and denominator polynomials ofP
respectively - Return
BT/(AR+ST)
ControlSystemsBase.feedback2dof
— Methodfeedback2dof(P::TransferFunction, C::TransferFunction, F::TransferFunction)
Return the transfer function P(F+C)/(1+PC)
which is the closed-loop system with process P
, controller C
and feedforward filter F
from reference to control signal (by-passing C
).
+-------+
| |
+-----> F +----+
| | | |
| +-------+ |
| +-------+ | +-------+
r | - | | | | | y
+--+-----> C +----+----> P +---+-->
| | | | | |
| +-------+ +-------+ |
| |
+--------------------------------+
ControlSystemsBase.fix_D_matrix
— MethodIf D=0 then create zero matrix of correct size and type, else, convert D to correct type
ControlSystemsBase.freqresp!
— Methodfreqresp!(R::Array{T, 3}, sys::LTISystem, w_vec::AbstractVector{<:Real})
In-place version of freqresp
that takes a pre-allocated array R
of size (ny, nu, nw)`
ControlSystemsBase.freqresp!v
— Methodfreqresp!v(R::Array{T, 3}, sys::AbstractStateSpace, w_vec::AbstractVector{W}; )
For use with SISO systems where it acts the same as freqresp!
but with the extra dimensions removed in the returned values.
ControlSystemsBase.freqresp
— Methodsys_fr = freqresp(sys, w)
Evaluate the frequency response of a linear system
w -> C*((iw*im*I - A)^-1)*B + D
of system sys
over the frequency vector w
.
ControlSystemsBase.freqresp_nohess
— Functionfreqresp_nohess(sys::AbstractStateSpace, w_vec::AbstractVector{<:Real})
Compute the frequency response of sys
without forming a Hessenberg factorization. This function is called automatically if the Hessenberg factorization fails.
ControlSystemsBase.freqresp_nohess!v
— Methodfreqresp_nohess!v(R::Array{T, 3}, sys::AbstractStateSpace, w_vec::AbstractVector{W}; )
For use with SISO systems where it acts the same as freqresp_nohess!
but with the extra dimensions removed in the returned values.
ControlSystemsBase.freqresp_nohess!v
— Methodfreqresp_nohess!v(R::Array{T, 3}, sys::StaticStateSpace, w_vec::AbstractVector{W}; )
For use with SISO systems where it acts the same as freqresp_nohess!
but with the extra dimensions removed in the returned values.
ControlSystemsBase.freqrespv
— Methodfreqrespv(G::AbstractMatrix, w_vec::AbstractVector{<:Real}; )
For use with SISO systems where it acts the same as freqresp
but with the extra dimensions removed in the returned values.
ControlSystemsBase.freqrespv
— Methodfreqrespv(G::Number, w_vec::AbstractVector{<:Real}; )
For use with SISO systems where it acts the same as freqresp
but with the extra dimensions removed in the returned values.
ControlSystemsBase.freqrespv
— Methodfreqrespv(sys::LTISystem, w_vec::AbstractVector{W}; )
For use with SISO systems where it acts the same as freqresp
but with the extra dimensions removed in the returned values.
ControlSystemsBase.gangoffour
— MethodS, PS, CS, T = gangoffour(P, C; minimal=true)
gangoffour(P::AbstractVector, C::AbstractVector; minimal=true)
Given a transfer function describing the plant P
and a transfer function describing the controller C
, computes the four transfer functions in the Gang-of-Four.
S = 1/(1+PC)
Sensitivity functionPS = (1+PC)\P
Load disturbance to measurement signalCS = (1+PC)\C
Measurement noise to control signalT = PC/(1+PC)
Complementary sensitivity function
If minimal=true
, minreal
will be applied to all transfer functions.
ControlSystemsBase.gangoffourplot
— MethodControlSystemsBase.gangofseven
— MethodS, PS, CS, T, RY, RU, RE = gangofseven(P,C,F)
Given transfer functions describing the Plant P
, the controller C
and a feed forward block F
, computes the four transfer functions in the Gang-of-Four and the transferfunctions corresponding to the feed forward.
S = 1/(1+PC)
Sensitivity functionPS = P/(1+PC)
CS = C/(1+PC)
T = PC/(1+PC)
Complementary sensitivity functionRY = PCF/(1+PC)
RU = CF/(1+P*C)
RE = F/(1+P*C)
ControlSystemsBase.gram
— Methodgram(sys, opt; kwargs...)
Compute the grammian of system sys
. If opt
is :c
, computes the controllability grammian. If opt
is :o
, computes the observability grammian.
See also grampd
For keyword arguments, see grampd
.
Extended help
Note: Gramian computations are sensitive to input-output scaling. For the result of a numerical balancing, gramian computation or truncation of MIMO systems to be meaningful, the inputs and outputs of the system must thus be scaled in a meaningful way. A common (but not the only) approach is:
- The outputs are scaled such that the maximum allowed control error, the maximum expected reference variation, or the maximum expected variation, is unity.
- The input variables are scaled to have magnitude one. This is done by dividing each variable by its maximum expected or allowed change, i.e., $u_{scaled} = u / u_{max}$
Without such scaling, the result of balancing will depend on the units used to measure the input and output signals, e.g., a change of unit for one output from meter to millimeter will make this output 1000x more important.
ControlSystemsBase.grampd
— MethodU = grampd(sys, opt; kwargs...)
Return a Cholesky factor U
of the grammian of system sys
. If opt
is :c
, computes the controllability grammian G = U*U'
. If opt
is :o
, computes the observability grammian G = U'U
.
Obtain a Cholesky
object by Cholesky(U)
for observability grammian
Uses MatrixEquations.plyapc/plyapd
. For keyword arguments, see the docstring of ControlSystemsBase.MatrixEquations.plyapc/plyapd
ControlSystemsBase.hcat_1
— MethodConcatenate systems horizontally with same first output y1 being the sum second output y2 = [y21; y22, ...] and inputs u1 = [u11; u12, ...] u2 = [u21; u22, ...] for u1i, u2i, y1i, y2i, where i denotes system i
ControlSystemsBase.hinfnorm
— MethodNinf, ω_peak = hinfnorm(sys; tol=1e-6)
Compute the H∞ norm Ninf
of the LTI system sys
, together with a frequency ω_peak
at which the gain Ninf is achieved.
Ninf := sup_ω σ_max[sys(iω)]
if G
is stable (σ_max = largest singular value) := Inf' if
G` is unstable
tol
is an optional keyword argument for the desired relative accuracy for the computed H∞ norm (not an absolute certificate).
sys
is first converted to a state space model if needed.
The continuous-time L∞ norm computation implements the 'two-step algorithm' in:
N.A. Bruinsma and M. Steinbuch, 'A fast algorithm to compute the H∞-norm of a transfer function matrix', Systems and Control Letters (1990), pp. 287-293.
For the discrete-time version, see:
P. Bongers, O. Bosgra, M. Steinbuch, 'L∞-norm calculation for generalized state space systems in continuous and discrete time', American Control Conference, 1991.
See also linfnorm
.
ControlSystemsBase.impulse
— Methody, t, x = impulse(sys[, tfinal])
y, t, x = impulse(sys[, t])
Calculate the impulse response of system sys
. If the final time tfinal
or time vector t
is not provided, one is calculated based on the system pole locations. The return value is a structure of type SimResult
that can be plotted or destructured as y, t, x = result
.
y
has size (ny, length(t), nu)
, x
has size (nx, length(t), nu)
ControlSystemsBase.index2range
— Methodouts = index2range(ind1, ind2)
Helper function to convert indexes with scalars to ranges. Used to avoid dropping dimensions
ControlSystemsBase.innovation_form
— Methodsysi = innovation_form(sys, R1, R2[, R12])
sysi = innovation_form(sys; sysw=I, syse=I, R1=I, R2=I)
Takes a system
x' = Ax + Bu + w ~ R1
y = Cx + Du + e ~ R2
and returns the system
x' = Ax + Kv
y = Cx + v
where v
is the innovation sequence.
If sysw
(syse
) is given, the covariance resulting in filtering noise with R1
(R2
) through sysw
(syse
) is used as covariance.
See Stochastic Control, Chapter 4, Åström
ControlSystemsBase.innovation_form
— Methodsysi = innovation_form(sys, K)
Takes a system
x' = Ax + Bu + Kv
y = Cx + Du + v
and returns the system
x' = Ax + Kv
y = Cx + v
where v
is the innovation sequence.
See Stochastic Control, Chapter 4, Åström
ControlSystemsBase.input_comp_sensitivity
— Methodinput_comp_sensitivity(P,C)
Transfer function from load disturbance to control signal.
- "Input" signifies that the transfer function is from the input of the plant.
- "Complimentary" signifies that the transfer function is to an output (in this case controller output)
▲
│e₁
│ ┌─────┐
d₁────+──┴──► P ├─────┬──►e₄
│ └─────┘ │
│ │
│ ┌─────┐ -│
e₂◄──┴─────┤ C ◄──┬──+───d₂
└─────┘ │
│e₃
▼
input_sensitivity
is the transfer function from d₁ to e₁, (I + CP)⁻¹output_sensitivity
is the transfer function from d₂ to e₃, (I + PC)⁻¹input_comp_sensitivity
is the transfer function from d₁ to e₂, (I + CP)⁻¹CPoutput_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PCG_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹PG_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
ControlSystemsBase.input_names
— Methodinput_names(P)
input_names(P, i)
Get a vector of strings with the names of the inputs of P
, or the i
:th name if an index is given.
ControlSystemsBase.input_sensitivity
— Methodinput_sensitivity(P, C)
Transfer function from load disturbance to total plant input.
- "Input" signifies that the transfer function is from the input of the plant.
▲
│e₁
│ ┌─────┐
d₁────+──┴──► P ├─────┬──►e₄
│ └─────┘ │
│ │
│ ┌─────┐ -│
e₂◄──┴─────┤ C ◄──┬──+───d₂
└─────┘ │
│e₃
▼
input_sensitivity
is the transfer function from d₁ to e₁, (I + CP)⁻¹output_sensitivity
is the transfer function from d₂ to e₃, (I + PC)⁻¹input_comp_sensitivity
is the transfer function from d₁ to e₂, (I + CP)⁻¹CPoutput_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PCG_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹PG_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
ControlSystemsBase.iscontinuous
— Methodiscontinuous(sys)
Returns true
for a continuous-time system sys
, else returns false
.
ControlSystemsBase.isdiscrete
— Methodisdiscrete(sys)
Returns true
for a discrete-time system sys
, else returns false
.
ControlSystemsBase.isproper
— Methodisproper(tf)
Returns true
if the TransferFunction
is proper. This means that order(den)
= order(num))
ControlSystemsBase.issiso
— Methodissiso(sys)
Returns true
if sys
is SISO, else returns false
.
ControlSystemsBase.isstable
— Methodisstable(sys)
Returns true
if sys
is stable, else returns false
.
ControlSystemsBase.kalman
— Methodkalman(Continuous, A, C, R1, R2)
kalman(Discrete, A, C, R1, R2; direct = false)
kalman(sys, R1, R2; direct = false)
Calculate the optimal Kalman gain.
If direct = true
, the observer gain is computed for the pair (A, CA)
instead of (A,C)
. This option is intended to be used together with the option direct = true
to observer_controller
. Ref: "Computer-Controlled Systems" pp 140.
To obtain a discrete-time approximation to a continuous-time LQG problem, the function c2d
can be used to obtain corresponding discrete-time covariance matrices.
The args...; kwargs...
are sent to the Riccati solver, allowing specification of cross-covariance etc. See ?MatrixEquations.arec/ared
for more help.
ControlSystemsBase.laglink
— Methodlaglink(a, M; [Ts])
Returns a phase retarding link, the rule of thumb a = 0.1ωc
guarantees less than 6 degrees phase margin loss. The bode curve will go from M
, bend down at a/M
and level out at 1 for frequencies > a
\[\dfrac{s + a}{s + a/M} = M \dfrac{1 + s/a}{1 + sM/a}\]
ControlSystemsBase.leadlink
— Functionleadlink(b, N, K=1; [Ts])
Returns a phase advancing link, the top of the phase curve is located at ω = b√(N)
where the link amplification is K√(N)
The bode curve will go from K
, bend up at b
and level out at KN
for frequencies > bN
The phase advance at ω = b√(N)
can be plotted as a function of N
with leadlinkcurve()
Values of N < 1
will give a phase retarding link.
\[KN \dfrac{s + b}{s + bN} = K \dfrac{1 + s/b}{1 + s/(bN)}\]
See also leadlinkat
laglink
ControlSystemsBase.leadlinkat
— Functionleadlinkat(ω, N, K=1; [Ts])
Returns a phase advancing link, the top of the phase curve is located at ω
where the link amplification is K√(N)
The bode curve will go from K
, bend up at ω/√(N)
and level out at KN
for frequencies > ω√(N)
The phase advance at ω
can be plotted as a function of N
with leadlinkcurve()
Values of N < 1
will give a phase retarding link.
See also leadlink
laglink
ControlSystemsBase.leadlinkcurve
— Functionleadlinkcurve(start=1)
Plot the phase advance as a function of N
for a lead link (phase advance link) If an input argument start
is given, the curve is plotted from start
to 10, else from 1 to 10.
See also leadlink, leadlinkat
ControlSystemsBase.lft
— Functionlft(G, Δ, type=:l)
Lower and upper linear fractional transformation between systems G
and Δ
.
Specify :l
lor lower LFT, and :u
for upper LFT.
G
must have more inputs and outputs than Δ
has outputs and inputs.
For details, see Chapter 9.1 in Zhou, K. and JC Doyle. Essentials of robust control, Prentice hall (NJ), 1998
ControlSystemsBase.linearize
— MethodA, B = linearize(f, x, u, args...)
Linearize dynamics $ẋ = f(x, u, args...)$ around operating point $(x,u,args...)$ using ForwardDiff. args
can be empty, or contain, e.g., parameters and time (p, t)
like in the SciML interface. This function can also be used to linearize an output equation C, D = linearize(h, x, u, args...)
.
ControlSystemsBase.linearize
— Methodlinearize(sys::HammersteinWienerSystem, Δy)
Linearize the nonlinear system sys
around the operating point implied by the specified Δy
┌─────────┐
y◄───┤ │◄────u
│ P │
Δy┌───┤ │◄───┐Δu
│ └─────────┘ │
│ │
│ ┌───┐ │
│ │ │ │
└─────►│ f ├───────┘
│ │
└───┘
NOTE: The nonlinear functionality in ControlSystemsBase.jl is currently experimental and subject to breaking changes not respecting semantic versioning. Use at your own risk.
ControlSystemsBase.linfnorm
— MethodNinf, ω_peak = linfnorm(sys; tol=1e-6)
Compute the L∞ norm Ninf
of the LTI system sys
, together with a frequency ω_peak
at which the gain Ninf
is achieved.
Ninf := sup_ω σ_max[sys(iω)]
(σ_max denotes the largest singular value)
tol
is an optional keyword argument representing the desired relative accuracy for the computed L∞ norm (this is not an absolute certificate however).
sys
is first converted to a state space model if needed.
The continuous-time L∞ norm computation implements the 'two-step algorithm' in:
N.A. Bruinsma and M. Steinbuch, 'A fast algorithm to compute the H∞-norm of a transfer function matrix', Systems and Control Letters (1990), pp. 287-293.
For the discrete-time version, see:
P. Bongers, O. Bosgra, M. Steinbuch, 'L∞-norm calculation for generalized state space systems in continuous and discrete time', American Control Conference, 1991.
See also hinfnorm
.
ControlSystemsBase.loopshapingPI
— MethodC, kp, ki, fig, CF = loopshapingPI(P, ωp; ϕl, rl, phasemargin, form=:standard, doplot=false, Tf, F)
Selects the parameters of a PI-controller (on parallel form) such that the Nyquist curve of P
at the frequency ωp
is moved to rl exp(i ϕl)
The parameters can be returned as one of several common representations chosen by form
, the options are
:standard
- $K_p(1 + 1/(T_i s) + T_ds)$:series
- $K_c(1 + 1/(τ_i s))(τ_d s + 1)$:parallel
- $K_p + K_i/s + K_d s$
If phasemargin
is supplied (in degrees), ϕl
is selected such that the curve is moved to an angle of phasemargin - 180
degrees
If no rl
is given, the magnitude of the curve at ωp
is kept the same and only the phase is affected, the same goes for ϕl
if no phasemargin is given.
Tf
: An optional time constant for second-order measurement noise filter on the formtf(1, [Tf^2, 2*Tf/sqrt(2), 1])
to make the controller strictly proper.F
: A pre-designed filter to use instead of the default second-order filter that is used ifTf
is given.doplot
plot thegangoffourplot
andnyquistplot
of the system.
See also loopshapingPID
, pidplots
, stabregionPID
and placePI
.
ControlSystemsBase.loopshapingPID
— MethodC, kp, ki, kd, fig, CF = loopshapingPID(P, ω; Mt = 1.3, ϕt=75, form=:standard, doplot=false, lb=-10, ub=10, Tf = 1/1000ω, F = nothing)
Selects the parameters of a PID-controller such that the Nyquist curve of the loop-transfer function $L = PC$ at the frequency ω
is tangent to the circle where the magnitude of $T = PC / (1+PC)$ equals Mt
. ϕt
denotes the positive angle in degrees between the real axis and the tangent point.
The default values for Mt
and ϕt
are chosen to give a good design for processes with inertia, and may need tuning for simpler processes.
The gain of the resulting controller is generally increasing with increasing ω
and Mt
.
Arguments:
P
: A SISO plant.ω
: The specification frequency.Mt
: The magnitude of the complementary sensitivity function at the specification frequency, $|T(iω)|$.ϕt
: The positive angle in degrees between the real axis and the tangent point.doplot
: If true, gang of four and Nyquist plots will be returned infig
.lb
: log10 of lower bound forkd
.ub
: log10 of upper bound forkd
.Tf
: Time constant for second-order measurement noise filter on the formtf(1, [Tf^2, 2*Tf/sqrt(2), 1])
to make the controller strictly proper. A practical controller typically sets this time constant slower than the default, e.g.,Tf = 1/100ω
orTf = 1/10ω
F
: A pre-designed filter to use instead of the default second-order filter.
The parameters can be returned as one of several common representations chosen by form
, the options are
:standard
- $K_p(1 + 1/(T_i s) + T_ds)$:series
- $K_c(1 + 1/(τ_i s))(τ_d s + 1)$:parallel
- $K_p + K_i/s + K_d s$
See also loopshapingPI
, pidplots
, stabregionPID
and placePI
.
Example:
P = tf(1, [1,0,0]) # A double integrator
Mt = 1.3 # Maximum magnitude of complementary sensitivity
ω = 1 # Frequency at which the specification holds
C, kp, ki, kd, fig, CF = loopshapingPID(P, ω; Mt, ϕt = 75, doplot=true)
ControlSystemsBase.lqr
— Methodlqr(sys, Q, R)
lqr(Continuous, A, B, Q, R, args...; kwargs...)
lqr(Discrete, A, B, Q, R, args...; kwargs...)
Calculate the optimal gain matrix K
for the state-feedback law u = -K*x
that minimizes the cost function:
J = integral(x'Qx + u'Ru, 0, inf) for the continuous-time model dx = Ax + Bu
. J = sum(x'Qx + u'Ru, 0, inf) for the discrete-time model x[k+1] = Ax[k] + Bu[k]
.
Solve the LQR problem for state-space system sys
. Works for both discrete and continuous time systems.
The args...; kwargs...
are sent to the Riccati solver, allowing specification of cross-covariance etc. See ?MatrixEquations.arec / ared
for more help.
To obtain also the solution to the Riccati equation and the eigenvalues of the closed-loop system as well, call ControlSystemsBase.MatrixEquations.arec / ared
instead (note the different order of the arguments to these functions).
To obtain a discrete-time approximation to a continuous-time LQR problem, the function c2d
can be used to obtain corresponding discrete-time cost matrices.
Examples
Continuous time
using LinearAlgebra # For identity matrix I
using Plots
A = [0 1; 0 0]
B = [0; 1]
C = [1 0]
sys = ss(A,B,C,0)
Q = I
R = I
L = lqr(sys,Q,R) # lqr(Continuous,A,B,Q,R) can also be used
u(x,t) = -L*x # Form control law,
t=0:0.1:5
x0 = [1,0]
y, t, x, uout = lsim(sys,u,t,x0=x0)
plot(t,x', lab=["Position" "Velocity"], xlabel="Time [s]")
Discrete time
using LinearAlgebra # For identity matrix I
using Plots
Ts = 0.1
A = [1 Ts; 0 1]
B = [0;1]
C = [1 0]
sys = ss(A, B, C, 0, Ts)
Q = I
R = I
L = lqr(Discrete, A,B,Q,R) # lqr(sys,Q,R) can also be used
u(x,t) = -L*x # Form control law,
t=0:Ts:5
x0 = [1,0]
y, t, x, uout = lsim(sys,u,t,x0=x0)
plot(t,x', lab=["Position" "Velocity"], xlabel="Time [s]")
ControlSystemsBase.lsim!
— Methodres = lsim!(ws::LsimWorkspace, sys::AbstractStateSpace{<:Discrete}, u, [t]; x0)
In-place version of lsim
that takes a workspace object created by calling LsimWorkspace
. Notice, if u
is a function, res.u === ws.u
. If u
is an array, res.u === u
.
ControlSystemsBase.lsim
— Methodresult = lsim(sys, u[, t]; x0, method])
result = lsim(sys, u::Function, t; x0, method)
Calculate the time response of system sys
to input u
. If x0
is omitted, a zero vector is used.
The result structure contains the fields y, t, x, u
and can be destructured automatically by iteration, e.g.,
y, t, x, u = result
result::SimResult
can also be plotted directly:
plot(result, plotu=true, plotx=false)
y
, x
, u
have time in the second dimension. Initial state x0
defaults to zero.
Continuous-time systems are simulated using an ODE solver if u
is a function (requires using ControlSystems). If u
is an array, the system is discretized (with method=:zoh
by default) before simulation. For a lower-level interface, see ?Simulator
and ?solve
u
can be a function or a matrix of precalculated control signals and must have dimensions (nu, length(t))
. If u
is a function, then u(x,i)
(for discrete systems) or u(x,t)
(for continuous ones) is called to calculate the control signal at every iteration (time instance used by solver). This can be used to provide a control law such as state feedback u(x,t) = -L*x
calculated by lqr
. To simulate a unit step at t=t₀
, use (x,t)-> t ≥ t₀
, for a ramp, use (x,t)-> t
, for a step at t=5
, use (x,t)-> (t >= 5)
etc.
Note: The function u
will be called once before simulating to verify that it returns an array of the correct dimensions. This can cause problems if u
is stateful. You can disable this check by passing check_u = false
.
For maximum performance, see function lsim!
, available for discrete-time systems only.
Usage example:
using ControlSystems
using LinearAlgebra: I
using Plots
A = [0 1; 0 0]
B = [0;1]
C = [1 0]
sys = ss(A,B,C,0)
Q = I
R = I
L = lqr(sys,Q,R)
u(x,t) = -L*x # Form control law
t = 0:0.1:5
x0 = [1,0]
y, t, x, uout = lsim(sys,u,t,x0=x0)
plot(t,x', lab=["Position" "Velocity"], xlabel="Time [s]")
# Alternative way of plotting
res = lsim(sys,u,t,x0=x0)
plot(res)
ControlSystemsBase.ltitr
— Functionltitr(A, B, u[,x0])
ltitr(A, B, u::Function, iters[,x0])
Simulate the discrete time system x[k + 1] = A x[k] + B u[k]
, returning x
. If x0
is not provided, a zero-vector is used.
The type of x0
determines the matrix structure of the returned result, e.g, x0
should preferably not be a sparse vector.
If u
is a function, then u(x,i)
is called to calculate the control signal every iteration. This can be used to provide a control law such as state feedback u=-Lx
calculated by lqr
. In this case, an integrer iters
must be provided that indicates the number of iterations.
ControlSystemsBase.margin
— Methodwgm, gm, wpm, pm = margin(sys::LTISystem, w::Vector; full=false, allMargins=false)
returns frequencies for gain margins, gain margins, frequencies for phase margins, phase margins
If !allMargins
, return only the smallest margin
If full
return also fullPhase
See also delaymargin
and RobustAndOptimalControl.diskmargin
ControlSystemsBase.markovparam
— Methodmarkovparam(sys, n)
Compute the n
th markov parameter of discrete-time state-space system sys
. This is defined as the following:
h(0) = D
h(n) = C*A^(n-1)*B
ControlSystemsBase.minorpoles
— Methodminorpoles(sys)
Compute the poles of all minors of the system.
ControlSystemsBase.minreal
— Functionminreal(tf::TransferFunction, eps=sqrt(eps()))
Create a minimal representation of each transfer function in tf
by cancelling poles and zeros will promote system to an appropriate numeric type
ControlSystemsBase.minreal
— Methodminreal(sys::T; fast=false, kwargs...)
Minimal realisation algorithm from P. Van Dooreen, The generalized eigenstructure problem in linear system theory, IEEE Transactions on Automatic Control
For information about the options, see ?ControlSystemsBase.MatrixPencils.lsminreal
See also sminreal
, which is both numerically exact and substantially faster than minreal
, but with a much more limited potential in removing non-minimal dynamics.
ControlSystemsBase.nicholsplot
— Functionfig = nicholsplot{T<:LTISystem}(systems::Vector{T}, w::AbstractVector; kwargs...)
Create a Nichols plot of the LTISystem
(s). A frequency vector w
can be optionally provided.
Keyword arguments:
text = true
Gains = [12, 6, 3, 1, 0.5, -0.5, -1, -3, -6, -10, -20, -40, -60]
pInc = 30
sat = 0.4
val = 0.85
fontsize = 10
pInc
determines the increment in degrees between phase lines.
sat
∈ [0,1] determines the saturation of the gain lines
val
∈ [0,1] determines the brightness of the gain lines
Additional keyword arguments are sent to the function plotting the systems and can be used to specify colors, line styles etc. using regular RecipesBase.jl syntax
This function is based on code subject to the two-clause BSD licence Copyright 2011 Will Robertson Copyright 2011 Philipp Allgeuer
ControlSystemsBase.nonlinearity
— Methodnonlinearity(f)
nonlinearity(T, f)
Create a pure nonlinearity. f
is assumed to be a static (no memory) nonlinear function from $f : R -> R$.
The type T
defaults to Float64
.
NOTE: The nonlinear functionality in ControlSystemsBase.jl is currently experimental and subject to breaking changes not respecting semantic versioning. Use at your own risk.
Example:
Create a LTI system with a static input nonlinearity that saturates the input to [-1,1].
tf(1, [1, 1])*nonlinearity(x->clamp(x, -1, 1))
See also predefined nonlinearities saturation
, offset
.
Note: when composing linear systems with nonlinearities, it's often important to handle operating points correctly. See ControlSystemsBase.offset
for handling operating points.
ControlSystemsBase.nyquist
— Methodre, im, w = nyquist(sys[, w])
Compute the real and imaginary parts of the frequency response of system sys
at frequencies w
. See also nyquistplot
re
and im
has size (ny, nu, length(w))
ControlSystemsBase.nyquistplot
— Functionfig = nyquistplot(sys; Ms_circles=Float64[], Mt_circles=Float64[], unit_circle=false, hz=false, critical_point=-1, kwargs...)
nyquistplot(LTISystem[sys1, sys2...]; Ms_circles=Float64[], Mt_circles=Float64[], unit_circle=false, hz=false, critical_point=-1, kwargs...)
Create a Nyquist plot of the LTISystem
(s). A frequency vector w
can be optionally provided.
unit_circle
: if the unit circle should be displayed. The Nyquist curve crosses the unit circle at the gain crossover frequency.Ms_circles
: draw circles corresponding to given levels of sensitivity (circles around -1 with radii1/Ms
).Ms_circles
can be supplied as a number or a vector of numbers. A design staying outside such a circle has a phase margin of at least2asin(1/(2Ms))
rad and a gain margin of at leastMs/(Ms-1)
.Mt_circles
: draw circles corresponding to given levels of complementary sensitivity.Mt_circles
can be supplied as a number or a vector of numbers.critical_point
: point on real axis to mark as critical for encirclements- If
hz=true
, the hover information will be displayed in Hertz, the input frequency vector is still treated as rad/s. balance
: Callbalance_statespace
on the system before plotting.
kwargs
is sent as argument to plot.
ControlSystemsBase.nyquistv
— Methodnyquistv(sys::LTISystem, w::AbstractVector; )
For use with SISO systems where it acts the same as nyquist
but with the extra dimensions removed in the returned values.
ControlSystemsBase.nyquistv
— Methodnyquistv(sys::LTISystem; )
For use with SISO systems where it acts the same as nyquist
but with the extra dimensions removed in the returned values.
ControlSystemsBase.observer_controller
— Methodcont = observer_controller(sys, L::AbstractMatrix, K::AbstractMatrix; direct=false)
If direct = false
Return the observer_controller cont
that is given by ss(A - B*L - K*C + K*D*L, K, L, 0)
such that feedback(sys, cont)
produces a closed-loop system with eigenvalues given by A-KC
and A-BL
.
This controller does not have a direct term, and corresponds to state feedback operating on state estimated by observer_predictor
. Use this form if the computed control signal is applied at the next sampling instant, or with an otherwise large delay in relation to the measurement fed into the controller.
Ref: "Computer-Controlled Systems" Eq 4.37
If direct = true
Return the observercontroller cont
that is given by ss((I-KC)(A-BL), (I-KC)(A-BL)K, L, LK)
such that feedback(sys, cont)
produces a closed-loop system with eigenvalues given by A-BL
and A-BL-KC
. This controller has a direct term, and corresponds to state feedback operating on state estimated by [`observerfilter`](@ref). Use this form if the computed control signal is applied immediately after receiveing a measurement. This version typically has better performance than the one without a direct term.
Ref: Ref: "Computer-Controlled Systems" pp 140 and "Computer-Controlled Systems" pp 162 prob 4.7
Arguments:
sys
: Model of systemL
: State-feedback gainu = -Lx
K
: Observer gain
See also observer_predictor
and innovation_form
.
ControlSystemsBase.observer_filter
— Methodobserver_filter(sys, K; output_state = false)
Return the observer filter
\[\begin{aligned} x̂(k|k) &= (I - KC)Ax̂(k-1|k-1) + (I - KC)Bu(k-1) + Ky(k) \\ \end{aligned}\]
with the input equation [(I - KC)B K] * [u(k-1); y(k)]
.
Note the time indices in the equations, the filter assumes that the user passes the current $y(k)$, but the past $u(k-1)$, that is, this filter is used to estimate the state before the current control input has been applied. This causes a state-feedback controller acting on the estimate produced by this observer to have a direct term.
This is similar to observer_predictor
, but in contrast to the predictor, the filter output depends on the current measurement, whereas the predictor output only depend on past measurements.
The observer filter is equivalent to the observer_predictor
for continuous-time systems.
Ref: "Computer-Controlled Systems" Eq 4.32
ControlSystemsBase.observer_predictor
— Methodobserver_predictor(sys::AbstractStateSpace, K; h::Int = 1, output_state = false)
observer_predictor(sys::AbstractStateSpace, R1, R2[, R12]; output_state = false)
If sys
is continuous, return the observer predictor system
\[\begin{aligned} x̂' &= (A - KC)x̂ + (B-KD)u + Ky \\ ŷ &= Cx + Du \end{aligned}\]
with the input equation [B-KD K] * [u; y]
If sys
is discrete, the prediction horizon h
may be specified, in which case measurements up to and including time t-h
and inputs up to and including time t
are used to predict y(t)
.
If covariance matrices R1, R2
are given, the kalman gain K
is calculated using kalman
.
If output_state
is true, the output is the state estimate x̂
instead of the output estimate ŷ
.
See also innovation_form
, observer_controller
and observer_filter
.
ControlSystemsBase.obsv
— Functionobsv(A, C, n=size(A,1))
obsv(sys, n=sys.nx)
Compute the observability matrix with n
rows for the system described by (A, C)
or sys
. Providing the optional n > sys.nx
returns an extended observability matrix.
Note that checking for observability by computing the rank from obsv
is not the most numerically accurate way, a better method is checking if gram(sys, :o)
is positive definite.
ControlSystemsBase.offset
— Methodoffset(val)
Create a constant-offset nonlinearity x -> x + val
.
NOTE: The nonlinear functionality in ControlSystemsBase.jl is currently experimental and subject to breaking changes not respecting semantic versioning. Use at your own risk.
Example:
To create a linear system that operates around operating point y₀, u₀
, use
offset_sys = offset(y₀) * sys * offset(-u₀)
note the sign on the offset u₀
. This ensures that sys
operates in the coordinates Δu = u-u₀, Δy = y-y₀
and the inputs and outputs to the offset system are in their non-offset coordinate system. If the system is linearized around x₀
, y₀
is given by C*x₀
. Additional information and an example is available here https://juliacontrol.github.io/ControlSystemsBase.jl/latest/lib/nonlinear/#Non-zero-operating-point
ControlSystemsBase.output_comp_sensitivity
— Methodoutput_comp_sensitivity(P,C)
Transfer function from measurement noise / reference to plant output.
- "output" signifies that the transfer function is from the output of the plant.
- "Complimentary" signifies that the transfer function is to an output (in this case plant output)
▲
│e₁
│ ┌─────┐
d₁────+──┴──► P ├─────┬──►e₄
│ └─────┘ │
│ │
│ ┌─────┐ -│
e₂◄──┴─────┤ C ◄──┬──+───d₂
└─────┘ │
│e₃
▼
input_sensitivity
is the transfer function from d₁ to e₁, (I + CP)⁻¹output_sensitivity
is the transfer function from d₂ to e₃, (I + PC)⁻¹input_comp_sensitivity
is the transfer function from d₁ to e₂, (I + CP)⁻¹CPoutput_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PCG_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹PG_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
ControlSystemsBase.output_names
— Methodoutput_names(P)
output_names(P, i)
Get a vector of strings with the names of the outputs of P
, or the i
:th name if an index is given.
ControlSystemsBase.output_sensitivity
— Methodoutput_sensitivity(P, C)
Transfer function from measurement noise / reference to control error.
- "output" signifies that the transfer function is from the output of the plant.
▲
│e₁
│ ┌─────┐
d₁────+──┴──► P ├─────┬──►e₄
│ └─────┘ │
│ │
│ ┌─────┐ -│
e₂◄──┴─────┤ C ◄──┬──+───d₂
└─────┘ │
│e₃
▼
input_sensitivity
is the transfer function from d₁ to e₁, (I + CP)⁻¹output_sensitivity
is the transfer function from d₂ to e₃, (I + PC)⁻¹input_comp_sensitivity
is the transfer function from d₁ to e₂, (I + CP)⁻¹CPoutput_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PCG_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹PG_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
ControlSystemsBase.pade
— Methodpade(G::DelayLtiSystem, N)
Approximate all time-delays in G
by Padé approximations of degree N
.
ControlSystemsBase.pade
— Methodpade(τ::Real, N::Int)
Compute the N
th order Padé approximation of a time-delay of length τ
.
ControlSystemsBase.pairup_conjugates!
— MethodReorder the vector x of complex numbers so that complex conjugates come after each other, with the one with positive imaginary part first. Returns true if the conjugates can be paired and otherwise false.
ControlSystemsBase.parallel
— Methodparallel(sys1::LTISystem, sys2::LTISystem)
Connect systems in parallel, equivalent to sys2+sys1
ControlSystemsBase.pid
— FunctionC = pid(param_p, param_i, [param_d]; form=:standard, state_space=false, [Tf], [Ts])
Calculates and returns a PID controller.
The form
can be chosen as one of the following
:standard
-Kp*(1 + 1/(Ti*s) + Td*s)
:series
-Kc*(1 + 1/(τi*s))*(τd*s + 1)
:parallel
-Kp + Ki/s + Kd*s
If state_space
is set to true
, either kd
has to be zero or a positive Tf
has to be provided for creating a filter on the input to allow for a state space realization. The filter used is 1 / (1 + s*Tf + (s*Tf)^2/2)
, where Tf
can typically be chosen as Ti/N
for a PI controller and Td/N
for a PID controller, and N
is commonly in the range 2 to 20. The state space will be returned on controllable canonical form.
For a discrete controller a positive Ts
can be supplied. In this case, the continuous-time controller is discretized using the Tustin method.
Examples
C1 = pid(3.3, 1, 2) # Kd≠0 works without filter in tf form
C2 = pid(3.3, 1, 2; Tf=0.3, state_space=true) # In statespace a filter is needed
C3 = pid(2., 3, 0; Ts=0.4, state_space=true) # Discrete
The functions pid_tf
and pid_ss
are also exported. They take the same parameters and is what is actually called in pid
based on the state_space
parameter.
ControlSystemsBase.pidplots
— Methodpidplots(P, args...; params_p, params_i, params_d=0, form=:standard, ω=0, grid=false, kwargs...)
Plots interesting figures related to closing the loop around process P
with a PID controller supplied in params
on one of the following forms:
:standard
-Kp*(1 + 1/(Ti*s) + Td*s)
:series
-Kc*(1 + 1/(τi*s))*(τd*s + 1)
:parallel
-Kp + Ki/s + Kd*s
The sent in values can be arrays to evaluate multiple different controllers, and if grid=true
it will be a grid search over all possible combinations of the values.
Available plots are :gof
for Gang of four, :nyquist
, :controller
for a bode plot of the controller TF and :pz
for pole-zero maps and should be supplied as additional arguments to the function.
One can also supply a frequency vector ω
to be used in Bode and Nyquist plots.
See also loopshapingPI
, stabregionPID
ControlSystemsBase.place
— Functionplace(A, B, p, opt=:c; direct = false)
place(sys::StateSpace, p, opt=:c; direct = false)
Calculate the gain matrix K
such that A - BK
has eigenvalues p
.
place(A, C, p, opt=:o)
place(sys::StateSpace, p, opt=:o)
Calculate the observer gain matrix L
such that A - LC
has eigenvalues p
.
If direct = true
and opt = :o
, the the observer gain K
is calculated such that A - KCA
has eigenvalues p
, this option is to be used together with direct = true
in observer_controller
.
Note: only apply direct = true
to discrete-time systems.
Ref: "Computer-Controlled Systems" pp 140.
Uses Ackermann's formula for SISO systems and place_knvd
for MIMO systems.
Please note that this function can be numerically sensitive, solving the placement problem in extended precision might be beneficial.
ControlSystemsBase.placePI
— MethodC, kp, ki = placePI(P, ω₀, ζ; form=:standard)
Selects the parameters of a PI-controller such that the poles of closed loop between P
and C
are placed to match the poles of s^2 + 2ζω₀s + ω₀^2
.
The parameters can be returned as one of several common representations chose by form
, the options are
:standard
- $K_p(1 + 1/(T_i s))$:series
- $K_c(1 + 1/(τ_i s))$ (equivalent to above for PI controllers):parallel
- $K_p + K_i/s$
C
is the returned transfer function of the controller and params
is a named tuple containing the parameters. The parameters can be accessed as params.Kp
or params["Kp"]
from the named tuple, or they can be unpacked using Kp, Ti, Td = values(params)
.
See also loopshapingPI
ControlSystemsBase.place_knvd
— Methodplace_knvd(A::AbstractMatrix, B, λ; verbose = false, init = :s)
Robust pole placement using the algorithm from
"Robust Pole Assignment in Linear State Feedback", Kautsky, Nichols, Van Dooren
This implementation uses "method 0" for the X-step and the QR factorization for all factorizations.
This function will be called automatically when place
is called with a MIMO system.
Arguments:
init
: Determines the initialization strategy for the iterations for find theX
matrix. Possible choices are:id
(default),:rand
,:s
.
ControlSystemsBase.plyap
— MethodXc = plyap(sys::AbstractStateSpace, Ql; kwargs...)
Lyapunov solver that takes the L
Cholesky factor of Q
and returns a triangular matrix Xc
such that Xc*Xc' = X
.
ControlSystemsBase.poles
— Methodpoles(sys)
Compute the poles of system sys
.
ControlSystemsBase.printpolyfun
— Methodf = printpolyfun(var) fun
Prints polynomial in descending order, with variable var
ControlSystemsBase.pzmap
— Functionfig = pzmap(fig, system, args...; hz = false, kwargs...)
Create a pole-zero map of the LTISystem
(s) in figure fig
, args
and kwargs
will be sent to the scatter
plot command.
To customize the unit-circle drawn for discrete systems, modify the line attributes, e.g., linecolor=:red
.
If hz
is true, all poles and zeros are scaled by 1/2π.
ControlSystemsBase.ratelimit
— Methodratelimit(val; Tf)
ratelimit(lower, upper; Tf)
Create a nonlinearity that limits the rate of change of a signal, roughly equivalent to $1/s ∘ sat ∘ s$. Tf
controls the filter time constant on the derivative used to calculate the rate. NOTE: The nonlinear functionality in ControlSystemsBase.jl is currently experimental and subject to breaking changes not respecting semantic versioning. Use at your own risk.
ControlSystemsBase.reduce_sys
— Methodreduce_sys(A::AbstractMatrix, B::AbstractMatrix, C::AbstractMatrix, D::AbstractMatrix, meps::AbstractFloat)
Implements REDUCE in the Emami-Naeini & Van Dooren paper. Returns transformed A, B, C, D matrices. These are empty if there are no zeros.
ControlSystemsBase.relative_gain_array
— Methodrelative_gain_array(A::AbstractMatrix; tol = 1.0e-15)
Reference: "On the Relative Gain Array (RGA) with Singular and Rectangular Matrices" Jeffrey Uhlmann https://arxiv.org/pdf/1805.10312.pdf
ControlSystemsBase.relative_gain_array
— Methodrelative_gain_array(G, w::AbstractVector)
relative_gain_array(G, w::Number)
Calculate the relative gain array of G
at frequencies w
. G(iω) .* pinv(tranpose(G(iω)))
The RGA can be used to find input-output pairings for MIMO control using individually tuned loops. Pair the inputs and outputs such that the RGA(ωc) at the crossover frequency becomes as close to diagonal as possible. Avoid pairings such that RGA(0) contains negative diagonal elements.
- The sum of the absolute values of the entries in the RGA is a good measure of the "true condition number" of G, the best condition number that can be achieved by input/output scaling of
G
, -Glad, Ljung. - The RGA is invariant to input/output scaling of
G
. - If the RGA contains large entries, the system may be sensitive to model errors, -Skogestad, "Multivariable Feedback Control: Analysis and Design":
- Uncertainty in the input channels (diagonal input uncertainty). Plants with
- Element uncertainty. Large RGA-elements imply sensitivity to element-by-element uncertainty.
The relative gain array is computed using the The unit-consistent (UC) generalized inverse Reference: "On the Relative Gain Array (RGA) with Singular and Rectangular Matrices" Jeffrey Uhlmann https://arxiv.org/pdf/1805.10312.pdf
ControlSystemsBase.rgaplot
— Functionrgaplot(sys, args...; hz=false)
rgaplot(LTISystem[sys1, sys2...], args...; hz=false, balance=true)
Plot the relative-gain array entries of the LTISystem
(s). A frequency vector w
can be optionally provided.
- If
hz=true
, the plot x-axis will be displayed in Hertz, the input frequency vector is still treated as rad/s. balance
: Callbalance_statespace
on the system before plotting.
kwargs
is sent as argument to Plots.plot.
ControlSystemsBase.rstc
— MethodSee ?rstd
for the discrete case
ControlSystemsBase.rstd
— MethodR,S,T = rstd(BPLUS,BMINUS,A,BM1,AM,AO,AR,AS)
R,S,T = rstd(BPLUS,BMINUS,A,BM1,AM,AO,AR)
R,S,T = rstd(BPLUS,BMINUS,A,BM1,AM,AO)
Polynomial synthesis in discrete time.
Polynomial synthesis according to "Computer-Controlled Systems" ch 10 to design a controller $R(q) u(k) = T(q) r(k) - S(q) y(k)$
Inputs:
BPLUS
: Part of open loop numeratorBMINUS
: Part of open loop numeratorA
: Open loop denominatorBM1
: Additional zerosAM
: Closed loop denominatorAO
: Observer polynomialAR
: Pre-specified factor of R,
e.g integral part [1, -1]^k
AS
: Pre-specified factor of S,
e.g notch filter [1, 0, w^2]
Outputs: R,S,T
: Polynomials in controller
See function dab
how the solution to the Diophantine- Aryabhatta-Bezout identity is chosen.
See Computer-Controlled Systems: Theory and Design, Third Edition Karl Johan Åström, Björn Wittenmark
ControlSystemsBase.saturation
— Methodsaturation(val)
saturation(lower, upper)
Create a saturating nonlinearity. Connect it to the output of a controller C
using
Csat = saturation(val) * C
y▲ ────── upper
│ /
│ /
│/
──────────┼────────► u
/│
/ │
/ │
lower────
NOTE: The nonlinear functionality in ControlSystemsBase.jl is currently experimental and subject to breaking changes not respecting semantic versioning. Use at your own risk.
Note: when composing linear systems with nonlinearities, it's often important to handle operating points correctly. See ControlSystemsBase.offset
for handling operating points.
ControlSystemsBase.sensitivity
— MethodThe output sensitivity function $S_o = (I + PC)^{-1}$ is the transfer function from a reference input to control error, while the input sensitivity function $S_i = (I + CP)^{-1}$ is the transfer function from a disturbance at the plant input to the total plant input. For SISO systems, input and output sensitivity functions are equal. In general, we want to minimize the sensitivity function to improve robustness and performance, but practical constraints always cause the sensitivity function to tend to 1 for high frequencies. A robust design minimizes the peak of the sensitivity function, $M_S$. The peak magnitude of $S$ is the inverse of the distance between the open-loop Nyquist curve and the critical point -1. Upper bounding the sensitivity peak $M_S$ gives lower-bounds on phase and gain margins according to
\[ϕ_m ≥ 2\text{sin}^{-1}(\frac{1}{2M_S}), g_m ≥ \frac{M_S}{M_S-1}\]
Generally, bounding $M_S$ is a better objective than looking at gain and phase margins due to the possibility of combined gain and pahse variations, which may lead to poor robustness despite large gain and pahse margins.
▲
│e₁
│ ┌─────┐
d₁────+──┴──► P ├─────┬──►e₄
│ └─────┘ │
│ │
│ ┌─────┐ -│
e₂◄──┴─────┤ C ◄──┬──+───d₂
└─────┘ │
│e₃
▼
input_sensitivity
is the transfer function from d₁ to e₁, (I + CP)⁻¹output_sensitivity
is the transfer function from d₂ to e₃, (I + PC)⁻¹input_comp_sensitivity
is the transfer function from d₁ to e₂, (I + CP)⁻¹CPoutput_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PCG_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹PG_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
ControlSystemsBase.series
— Methodseries(sys1::LTISystem, sys2::LTISystem)
Connect systems in series, equivalent to sys2*sys1
ControlSystemsBase.seriesform
— MethodGs, k = seriesform(G::TransferFunction{Discrete})
Convert a transfer function G
to a vector of second-order transfer functions and a scalar gain k
, the product of which equals G
.
ControlSystemsBase.setPlotScale
— MethodsetPlotScale(str)
Set the default scale of magnitude in bodeplot
and sigmaplot
. str
should be either "dB"
or "log10"
. The default scale if none is chosen is "log10"
.
ControlSystemsBase.sigma
— Methodsv, w = sigma(sys[, w])
Compute the singular values sv
of the frequency response of system sys
at frequencies w
. See also sigmaplot
sv
has size (min(ny, nu), length(w))
ControlSystemsBase.sigmaplot
— Functionsigmaplot(sys, args...; hz=false balance=true, extrema)
sigmaplot(LTISystem[sys1, sys2...], args...; hz=false, balance=true, extrema)
Plot the singular values of the frequency response of the LTISystem
(s). A frequency vector w
can be optionally provided.
- If
hz=true
, the plot x-axis will be displayed in Hertz, the input frequency vector is still treated as rad/s. balance
: Callbalance_statespace
on the system before plotting.extrema
: Only plot the largest and smallest singular values.
kwargs
is sent as argument to Plots.plot.
ControlSystemsBase.sigmav
— Methodsigmav(sys::LTISystem, w::AbstractVector; )
For use with SISO systems where it acts the same as sigma
but with the extra dimensions removed in the returned values.
ControlSystemsBase.sigmav
— Methodsigmav(sys::LTISystem; )
For use with SISO systems where it acts the same as sigma
but with the extra dimensions removed in the returned values.
ControlSystemsBase.similarity_transform
— Methodsyst = similarity_transform(sys, T; unitary=false)
Perform a similarity transform T : Tx̃ = x
on sys
such that
à = T⁻¹AT
B̃ = T⁻¹ B
C̃ = CT
D̃ = D
If unitary=true
, T
is assumed unitary and the matrix adjoint is used instead of the inverse. See also balance_statespace
.
ControlSystemsBase.siso_ss_to_zpk
— MethodConvert get zpk representation of sys from input j to output i
ControlSystemsBase.sisomargin
— Methodωgm, gm, ωpm, pm = sisomargin(sys::LTISystem, w::Vector; full=false, allMargins=false)
Return frequencies for gain margins, gain margins, frequencies for phase margins, phase margins. If allMargins=false
, only the smallest margins are returned.
ControlSystemsBase.sminreal
— Methodsminreal(sys)
Compute the structurally minimal realization of the state-space system sys
. A structurally minimal realization is one where only states that can be determined to be uncontrollable and unobservable based on the location of 0s in sys
are removed.
Systems with numerical noise in the coefficients, e.g., noise on the order of eps
require truncation to zero to be affected by structural simplification, e.g.,
trunc_zero!(A) = A[abs.(A) .< 10eps(maximum(abs, A))] .= 0
trunc_zero!(sys.A); trunc_zero!(sys.B); trunc_zero!(sys.C)
sminreal(sys)
In contrast to minreal
, which performs pole-zero cancellation using linear-algebra operations, has an 𝑂(nₓ^3) complexity and is subject to numerical tolerances, sminreal
is computationally very cheap and numerically exact (operates on integers). However, the ability of sminreal
to reduce the order of the model is much less powerful.
See also minreal
.
ControlSystemsBase.ss
— Methodsys = ss(A, B, C, D) # Continuous
sys = ss(A, B, C, D, Ts) # Discrete
Create a state-space model sys::StateSpace{TE, T}
with matrix element type T
and TE is Continuous
or <:Discrete
.
This is a continuous-time model if Ts
is omitted. Otherwise, this is a discrete-time model with sampling period Ts
.
D
may be specified as 0
in which case a zero matrix of appropriate size is constructed automatically. sys = ss(D [, Ts])
specifies a static gain matrix D
.
To associate names with states, inputs and outputs, see named_ss
.
ControlSystemsBase.ssdata
— MethodA, B, C, D = ssdata(sys)
A destructor that outputs the statespace matrices.
ControlSystemsBase.ssrand
— Methodssrand(T::Type, ny::Int, nu::Int, nstates::Int; proper=false, stable=true, Ts=nothing)
Returns a random StateSpace
model with ny
outputs, nu
inputs, and nstates
states, whose matrix elements are normally distributed.
It is possible to specify if the system should be proper
or stable
.
Specify a sample time Ts
to obtain a discrete-time system.
ControlSystemsBase.stabregionPID
— Functionkp, ki, fig = stabregionPID(P, [ω]; kd=0, doplot=false, form=:standard)
Segments of the curve generated by this program is the boundary of the stability region for a process with transfer function P(s) The provided derivative gain is expected on parallel form, i.e., the form kp + ki/s + kd s, but the result can be transformed to any form given by the form
keyword. The curve is found by analyzing
\[P(s)C(s) = -1 ⟹ \\ |PC| = |P| |C| = 1 \\ arg(P) + arg(C) = -π\]
If P
is a function (e.g. s -> exp(-sqrt(s)) ), the stability of feedback loops using PI-controllers can be analyzed for processes with models with arbitrary analytic functions See also loopshapingPI
, loopshapingPID
, pidplots
ControlSystemsBase.starprod
— Methodstarprod(sys1, sys2, dimu, dimy)
Compute the Redheffer star product.
length(U1) = length(Y2) = dimu
and length(Y1) = length(U2) = dimy
For details, see Chapter 9.3 in Zhou, K. and JC Doyle. Essentials of robust control, Prentice hall (NJ), 1998
ControlSystemsBase.state_names
— Methodstate_names(P)
state_names(P, i)
Get a vector of strings with the names of the states of P
, or the i
:th name if an index is given.
ControlSystemsBase.stepinfo
— Methodstepinfo(res::SimResult; y0 = nothing, yf = nothing, settling_th = 0.02, risetime_th = (0.1, 0.9))
Compute the step response characteristics for a simulation result. The following information is computed and stored in a StepInfo
struct:
y0
: The initial value of the responseyf
: The final value of the responsestepsize
: The size of the steppeak
: The peak value of the responsepeaktime
: The time at which the peak occursovershoot
: The percentage overshoot of the responseundershoot
: The percentage undershoot of the response. If the step response never reaches below the initial value, the undershoot is zero.settlingtime
: The time at which the response settles withinsettling_th
of the final valuesettlingtimeind
: The index at which the response settles withinsettling_th
of the final valuerisetime
: The time at which the response rises fromrisetime_th[1]
torisetime_th[2]
of the final value
Arguments:
res
: The result from a simulation usingstep
(orlsim
)y0
: The initial value, if not provided, the first value of the response is used.yf
: The final value, if not provided, the last value of the response is used. The simulation must have reached steady-state for an automatically computed value to make sense. If the simulation has not reached steady state, you may provide the final value manually.settling_th
: The threshold for computing the settling time. The settling time is the time at which the response settles withinsettling_th
of the final value.risetime_th
: The lower and upper threshold for computing the rise time. The rise time is the time at which the response rises fromrisetime_th[1]
torisetime_th[2]
of the final value.
Example:
G = tf([1], [1, 1, 1])
res = step(G, 15)
si = stepinfo(res)
plot(si)
ControlSystemsBase.struct_ctrb_states
— Methodstruct_ctrb_states(A::AbstractVecOrMat, B::AbstractVecOrMat)
Compute a bit-vector, expressing whether a state of the pair (A, B) is structurally controllable based on the location of zeros in the matrices.
ControlSystemsBase.system_name
— Methodsystem_name(nothing::LTISystem)
Return the name of the system. If the system does not have a name, an empty string is returned.
ControlSystemsBase.tf
— Methodsys = tf(num, den[, Ts])
sys = tf(gain[, Ts])
Create as a fraction of polynomials:
sys::TransferFunction{SisoRational{T,TR}} = numerator/denominator
where T is the type of the coefficients in the polynomial.
num
: the coefficients of the numerator polynomial. Either scalar or vector to create SISO systems
or an array of vectors to create MIMO system.
den
: the coefficients of the denominator polynomial. Either vector to create SISO systems
or an array of vectors to create MIMO system.
Ts
: Sample time if discrete time system.
The polynomial coefficients are ordered starting from the highest order term.
Other uses:
tf(sys)
: Convertsys
totf
form.tf("s")
,tf("z")
: Create the continuous transferfunctions
.
ControlSystemsBase.time_scale
— Methodtime_scale(sys::AbstractStateSpace{Continuous}, a; balanced = false)
time_scale(G::TransferFunction{Continuous}, a; balanced = true)
Rescale the time axis (change time unit) of sys
.
For systems where the dominant time constants are very far from 1, e.g., in electronics, rescaling the time axis may be beneficial for numerical performance, in particular for continuous-time simulations.
Scaling of time for a function $f(t)$ with Laplace transform $F(s)$ can be stated as
\[f(at) \leftrightarrow \dfrac{1}{a} F\big(\dfrac{s}{a}\big)\]
The keyword argument balanced
indicates whether or not to apply a balanced scaling on the B
and C
matrices. For statespace systems, this defaults to false since it changes the state representation, only B
will be scaled. For transfer functions, it defaults to true.
Example:
The following example show how a system with a time constant on the order of one micro-second is rescaled such that the time constant becomes 1, i.e., the time unit is changed from seconds to micro-seconds.
Gs = tf(1, [1e-6, 1]) # micro-second time scale modeled in seconds
Gms = time_scale(Gs, 1e-6) # Change to micro-second time scale
Gms == tf(1, [1, 1]) # Gms now has micro-seconds as time unit
The next example illustrates how the time axis of a time-domain simulation changes by time scaling
t = 0:0.1:50 # original time axis
a = 10 # Scaling factor
sys1 = ssrand(1,1,5)
res1 = step(sys1, t) # Perform original simulation
sys2 = time_scale(sys, a) # Scale time
res2 = step(sys2, t ./ a) # Simulate on scaled time axis, note the `1/a`
isapprox(res1.y, res2.y, rtol=1e-3, atol=1e-3)
ControlSystemsBase.timeevol
— Methodtimeevol(sys::LTISystem)
Get the timeevol::TimeEvolution from system sys
, usually sys.timeevol
ControlSystemsBase.to_similar_matrices
— MethodPromote A,B,C,D to same types, fix D matrix (see fix_D_matrix
)
ControlSystemsBase.to_sized
— Methodto_sized(sys::AbstractStateSpace)
Return a HeteroStateSpace
where the system matrices are of type SizedMatrix.
NOTE: This function is fundamentally type unstable. For maximum performance, create the sized system manually, or make use of the function-barrier technique.
ControlSystemsBase.tzeros
— Methodtzeros(sys)
Compute the invariant zeros of the system sys
. If sys
is a minimal realization, these are also the transmission zeros.
ControlSystemsBase.unwrap
— Methodunwrap(m::AbstractArray, args...)
Unwrap a vector of phase angles (radians) in (-π, π) such that it does not wrap around the edges -π and π, i.e., the result may leave the range (-π, π).
ControlSystemsBase.vcat_1
— MethodConcatenate systems vertically with same first input u1 second input [u21; u22 ...] and output y1 = [y11; y12, ...] y2 = [y21; y22, ...] for u1i, u2i, y1i, y2i, where i denotes system i
ControlSystemsBase.zpconv
— Methodzpc(a,r,b,s)
form conv(a,r) + conv(b,s)
where the lengths of the polynomials are equalized by zero-padding such that the addition can be carried out
ControlSystemsBase.zpk
— Methodzpk(gain[, Ts])
zpk(num, den, k[, Ts])
zpk(sys)
Create transfer function on zero pole gain form. The numerator and denominator are represented by their poles and zeros.
sys::TransferFunction{SisoZpk{T,TR}} = k*numerator/denominator
where T
is the type of k
and TR
the type of the zeros/poles, usually Float64 and Complex{Float64}.
num
: the roots of the numerator polynomial. Either scalar or vector to create SISO systems
or an array of vectors to create MIMO system.
den
: the roots of the denominator polynomial. Either vector to create SISO systems
or an array of vectors to create MIMO system.
k
: The gain of the system. Obs, this is not the same asdcgain
.Ts
: Sample time if discrete time system.
Other uses:
zpk(sys)
: Convertsys
tozpk
form.zpk("s")
: Create the transferfunctions
.
ControlSystemsBase.zpkdata
— Methodz, p, k = zpkdata(sys)
Compute the zeros, poles, and gains of system sys
.
Returns
z
: Matrix{Vector{ComplexF64}}, (ny × nu)p
: Matrix{Vector{ComplexF64}}, (ny × nu)k
: Matrix{Float64}, (ny × nu)
LinearAlgebra.lyap
— Methodlyap(A, Q; kwargs...)
Compute the solution X
to the discrete Lyapunov equation AXA' - X + Q = 0
.
Uses MatrixEquations.lyapc / MatrixEquations.lyapd
. For keyword arguments, see the docstring of ControlSystemsBase.MatrixEquations.lyapc / ControlSystemsBase.MatrixEquations.lyapd
LinearAlgebra.norm
— Functionnorm(sys, p=2; tol=1e-6)
norm(sys)
or norm(sys,2)
computes the H2 norm of the LTI system sys
.
norm(sys, Inf)
computes the H∞ norm of the LTI system sys
. The H∞ norm is the same as the L∞ for stable systems, and Inf for unstable systems. If the peak gain frequency is required as well, use the function hinfnorm
instead. See hinfnorm
for further documentation.
tol
is an optional keyword argument, used only for the computation of L∞ norms. It represents the desired relative accuracy for the computed L∞ norm (this is not an absolute certificate however).
sys
is first converted to a StateSpace
model if needed.
RecipesBase.apply_recipe
— Methodfig = marginplot(sys::LTISystem [,w::AbstractVector]; balance=true, kwargs...)
marginplot(sys::Vector{LTISystem}, w::AbstractVector; balance=true, kwargs...)
Plot all the amplitude and phase margins of the system(s) sys
.
- A frequency vector
w
can be optionally provided. balance
: Callbalance_statespace
on the system before plotting.
kwargs
is sent as argument to RecipesBase.plot.
ControlSystemsBase.@autovec
— Macro@autovec (indices...) f() = (a, b, c)
A macro that helps in creating versions of functions where excessive dimensions are removed automatically for specific outputs. indices
contains each index for which the output tuple should be flattened. If the function only has a single output it (not a tuple with a single item) it should be called as @autovec () f() = ...
. f()
is the original function and fv()
will be the version with flattened outputs.