Synthesis
For and synthesis as well as more advanced LQG design, see RobustAndOptimalControl.
#
ControlSystemsBase.kalman
— Method
kalman(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. direct = false
is sometimes referred to as a "delayed" estimator, while direct = true
is a "current" estimator.
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.
To obtain an LTISystem that represents the Kalman filter, pass the obtained Kalman feedback gain into observer_filter
. To obtain an LQG controller, pass the obtained Kalman feedback gain as well as a state-feedback gain computed using lqr
into observer_controller
.
The args...; kwargs...
are sent to the Riccati solver, allowing specification of cross-covariance etc. See ?MatrixEquations.arec/ared
for more help.
#
ControlSystemsBase.lqr
— Method
lqr(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.place
— Function
place(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
.
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.place_knvd
— Method
place_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.c2d
— Function
sysd = 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
).
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
Extended help
ZoH sampling is exact for linear systems with piece-wise constant inputs (step invariant), i.e., the solution obtained using lsim
is not approximative (modulu machine precision). ZoH sampling is commonly used to discretize continuous-time plant models that are to be controlled using a discrete-time controller.
FoH sampling is exact for linear systems with piece-wise linear inputs (ramp invariant), this is a good choice for simulation of systems with smooth continuous inputs.
To approximate the behavior of a continuous-time system well in the frequency domain, the :tustin
(trapezoidal / bilinear) method may be most appropriate. In this case, the pre-warping argument can be used to ensure that the frequency response of the discrete-time system matches the continuous-time system at a given frequency. The tustin transformation alters the meaning of the state components, while ZoH and FoH preserve the meaning of the state components. The Tustin method is commonly used to discretize a continuous-tiem controller.
The forward-Euler method generally requires the sample time to be very small relative to the time constants of the system, and its use is generally discouraged.
Classical rules-of-thumb for selecting the sample time for control design dictate that Ts
should be chosen as where is the gain-crossover frequency (rad/s).
#
ControlSystemsBase.c2d
— Method
Qd = 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 |
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
— Method
c2d_poly2poly(ro, Ts)
returns the polynomial coefficients in discrete time given polynomial coefficients in continuous time
#
ControlSystemsBase.c2d_roots2poly
— Method
c2d_roots2poly(ro, Ts)
returns the polynomial coefficients in discrete time given a vector of roots in continuous time
#
ControlSystemsBase.c2d_x0map
— Function
sysd, 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.d2c
— Function
d2c(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.d2c
— Function
Qc = 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.dab
— Method
X,Y = dab(A,B,C)
Solves the Diophantine-Aryabhatta-Bezout identity
, where and are polynomials and .
See Computer-Controlled Systems: Theory and Design, Third Edition Karl Johan Åström, Björn Wittenmark
#
ControlSystemsBase.rstc
— Method
See ?rstd
for the discrete case
#
ControlSystemsBase.rstd
— Method
R,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
Inputs:
-
BPLUS
: Part of open loop numerator -
BMINUS
: Part of open loop numerator -
A
: Open loop denominator -
BM1
: Additional zeros -
AM
: Closed loop denominator -
AO
: Observer polynomial -
AR
: 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.zpconv
— Method
zpc(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.laglink
— Method
laglink(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
#
ControlSystemsBase.leadlink
— Function
leadlink(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.
See also leadlinkat
laglink
#
ControlSystemsBase.leadlinkat
— Function
leadlinkat(ω, 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
— Function
leadlinkcurve(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.loopshapingPI
— Method
C, 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
- -
:series
- -
:parallel
-
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
— Method
C, 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 at the frequency ω
is tangent to the circle where the magnitude of 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
- -
:series
- -
:parallel
-
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.pid
— Function
C = 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
— Method
pidplots(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.placePI
— Method
C, 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
- -
:series
- (equivalent to above for PI controllers) -
:parallel
-
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.stabregionPID
— Function
kp, 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
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.sminreal
— Method
sminreal(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.add_input
— Function
add_input(sys::AbstractStateSpace, B2::AbstractArray, D2 = 0)
Add inputs to sys
by forming
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
— Function
add_output(sys::AbstractStateSpace, C2::AbstractArray, D2 = 0)
Add outputs to sys
by forming
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
— Method
append(systems::StateSpace...), append(systems::TransferFunction...)
Append systems in block diagonal form
#
ControlSystemsBase.array2mimo
— Method
array2mimo(M::AbstractArray{<:LTISystem})
Take an array of LTISystem
s and create a single MIMO system.
#
ControlSystemsBase.feedback
— Method
feedback(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
— Method
feedback(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
— Method
feedback2dof(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
— Method
feedback2dof(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.lft
— Function
lft(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.parallel
— Method
parallel(sys1::LTISystem, sys2::LTISystem)
Connect systems in parallel, equivalent to sys2+sys1
#
ControlSystemsBase.series
— Method
series(sys1::LTISystem, sys2::LTISystem)
Connect systems in series, equivalent to sys2*sys1
#
ControlSystemsBase.starprod
— Method
starprod(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.G_CS
— Method
G_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)⁻¹CP -
output_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PC -
G_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹P -
G_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
#
ControlSystemsBase.G_PS
— Method
G_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)⁻¹CP -
output_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PC -
G_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹P -
G_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
#
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)⁻¹CP -
output_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PC -
G_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹P -
G_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
#
ControlSystemsBase.extended_gangoffour
— Function
extended_gangoffour(P, C, pos=true)
Returns a single statespace system that maps
-
w1
reference or measurement noise -
w2
load disturbance
to
-
z1
control error -
z2
control input
z1 z2 ▲ ┌─────┐ ▲ ┌─────┐ │ │ │ │ │ │ w1──+─┴─►│ C ├──┴───+─►│ P ├─┐ │ │ │ │ │ │ │ │ └─────┘ │ └─────┘ │ │ w2 │ └────────────────────────────┘
The returned system has the transfer-function matrix
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.input_comp_sensitivity
— Method
input_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)⁻¹CP -
output_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PC -
G_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹P -
G_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
#
ControlSystemsBase.input_sensitivity
— Method
input_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)⁻¹CP -
output_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PC -
G_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹P -
G_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
#
ControlSystemsBase.output_comp_sensitivity
— Method
output_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)⁻¹CP -
output_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PC -
G_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹P -
G_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
#
ControlSystemsBase.output_sensitivity
— Method
output_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)⁻¹CP -
output_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PC -
G_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹P -
G_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
#
ControlSystemsBase.sensitivity
— Method
The output sensitivity function is the transfer function from a reference input to control error, while the input sensitivity function 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, . The peak magnitude of is the inverse of the distance between the open-loop Nyquist curve and the critical point -1. Upper bounding the sensitivity peak gives lower-bounds on phase and gain margins according to
Generally, bounding 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)⁻¹CP -
output_comp_sensitivity
is the transfer function from d₂ to e₄, (I + PC)⁻¹PC -
G_PS
is the transfer function from d₁ to e₄, (1 + PC)⁻¹P -
G_CS
is the transfer function from d₂ to e₂, (1 + CP)⁻¹C
#
ControlSystemsBase.bodev
— Method
bodev(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
— Method
bodev(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.freqrespv
— Method
freqrespv(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
— Method
freqrespv(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.
386#W"}, Tuple{LTISystem, AbstractVector{var"#386#W"}}} where var"#386#W"<:Real">
ControlSystemsBase.freqrespv
— Method
freqrespv(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.nyquistv
— Method
nyquistv(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
— Method
nyquistv(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.sigmav
— Method
sigmav(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
— Method
sigmav(sys::LTISystem; )
For use with SISO systems where it acts the same as sigma
but with the extra dimensions removed in the returned values.