PID Autotuning

The PID controller is a classical control method that is widely used due to its simplicity and ability to control many practically occurring systems. The parameters of a PID controller can be tuned in multiple different ways:

  • Trial and error, in simulation or on the real system
  • Loop shaping
  • Automatic tuning

This page details the automatic tuning features offered by JuliaSimControl. Automatic tuning offers the possibility of achieving an optimal response, subject to constraints on closed-loop robustness with respect to uncertainty and noise amplification. While this page refers to the automatic tuning of PID controllers in isolation, we refer the reader to Automatic tuning of structured controllers for tuning of more general structured controllers.

The PID autotuning in JuliaSimControl is based on disturbance step-response optimization, subject to robustness constraints on closed-loop sensitivity functions. We currently implement two methods, one that optimizes a PID controller on the form

\[K(s) = (k_p + k_i/s + k_d s)\]

by solving

\[\operatorname{minimize}_K \int e(t) dt\]

\[\text{subject to} \\ ||S(s)||_\infty \leq M_S \\ ||T(s)||_\infty \leq M_T \\ ||KS(s)||_\infty \leq M_{KS}\]

where $e(t) = r(t) - y(t)$ is the control error.

The second method performs joint optimization of a PID controller and a measurement filter on the form

\[K(s) = C(s) F(s) = (k_p + k_i/s + k_d s) \dfrac{1}{(sT)^2 + 2ζTs + 1}, ζ = 1/√2\]

by solving

\[\operatorname{minimize}_{C, F} \int |e(t)| dt\]

\[\text{subject to} \\ ||S(s)||_\infty \leq M_S \\ ||T(s)||_\infty \leq M_T\\ ||KS(s)||_\infty \leq M_{KS}\]

The autotuning functions operate on SISOLTISystems from ControlSystems.jl. If you have a ModelingToolkit model, you may obtain a linear system model using linearization. The general workflow for autotuning is

  1. Define a plant model, $P$
  2. Define desired constraints on the maximum magnitudes $M_S, M_T, M_{KS}$ of the sensitivity functions $S = \dfrac{1}{1+ PK}$, $T = \dfrac{PK}{1+ PK}$ and $KS = \dfrac{K}{1+ PK}$.
  3. Choose problem and solver parameters and create an AutoTuningProblem.
  4. Call solve.
  5. Plot the result.

If you want to use the optimized controller in a ModelingToolkit simulation, see OptimizedPID.

Examples of this are shown below.

Functions:

Getting started

JuliaSimControl contains a Pluto-based graphical app (GUI) for PID-controller tuning using the two methods below, usage of this app is documented under PID autotuning GUI. This example demonstrates the non-graphical interface.

Integrated absolute error (IAE)

The following example optimizes a PID controller with a low-pass filter using the method from

K. Soltesz, C. Grimholt, S. Skogestad. Simultaneous design of proportional–integral–derivative controller and measurement filter by optimisation. Control Theory and Applications. 11(3), pp. 341-348. IET. 2017.

using JuliaSimControl, Plots
# Process model (continuous time LTI SISO system).
T = 4 # Time constant
L = 1 # Delay
K = 1 # Gain
P = tf(K, [T, 1.0])*delay(L) # process dynamics
Ts = 0.1 # Discretization time
Tf = 25  # Simulation time

# Robustness constraints
Ms = 1.2   # Maximum allowed sensitivity function magnitude
Mt = Ms    # Maximum allowed complementary sensitivity function magnitude
Mks = 10.0 # Maximum allowed magnitude of transfer function from process output to control signal, sometimes referred to as noise sensitivity.
w = 2π .* exp10.(LinRange(-2, 2, 200)) # frequency grid

prob = AutoTuningProblem(; P, Ms, Mt, Mks, w, Ts, Tf, metric = :IAE)

# p0 = Float64[1, 1, 0, 0.001] # Initial parameter guess can be optionally supplied, kp, ki, kd, T_filter
res = solve(prob)
plot(res)
Example block output

The figure shows the Nyquist curve of the loop-transfer function $P(s)K(s)$ using the optimized controller, as well as circles corresponding to the chosen constraints. The top figures show Bode plots of the closed-loop sensitivity functions together with the constrains, and the lower left figure shows the response to a unit load-disturbance step as well as a reference-step response. Note, the response to a reference step is not part of the optimization criterion, and optimized suppression of load disturbances often leads to a suboptimal response to reference steps. If steps are expected in the reference signal, reference shaping using a pre-filter is recommended (called a 2-DOF design, realized, for example, by the introduction of $W_r$ in the diagram of the following design example).

Integrated error (IE)

The following example optimizes a PID controller using the method from

M. Hast, K. J. Astrom, B. Bernhardsson, S. Boyd. PID design by convex-concave optimization. European Control Conference. IEEE. Zurich, Switzerland. 2013.

This method optimizes integrated error (not integrated absolute error). This problem is relatively easy to solve and corresponds well to IAE if the system is well damped. If convergence of the above method (IAE) appears difficult, this method can be used as initialization by choosing metric = :IEIAE.

using JuliaSimControl, Plots
T = 4 # Time constant
K = 1 # Gain
P = tf(K, [T, 1.0]) # process dynamics

## Robustness constraints
Ms  = 1.2  # Maximum allowed sensitivity function magnitude
Mt  = Ms   # Maximum allowed complementary sensitivity function magnitude
Mks = 10.0 # Maximum allowed magnitude of transfer function from process output to control signal, sometimes referred to as noise sensitivity.
w   = 2π .* exp10.(LinRange(-2, 2, 50)) # frequency vector

p0 = Float64[1, 1, 0.1] # Initial guess. Use only two parameters to tune a PI instead of PID controller
prob = AutoTuningProblem(; P, Ms, Mt, Mks, w, Ts=0.1, Tf=25.0, metric = :IE) # Set the metric here

res = solve(prob, p0)
plot(res)
Example block output

Choosing metric

The metric = :IE problem optimizes integrated error $\int e(t) dt$ (not integrated absolute error). This problem is relatively easy and fast to solve and corresponds well to IAE if the system is well damped. If this metric is chosen, a PI or PID controller is tuned, determined by the number of parameters in the initial guess. The method requires a stabilizing controller as an initial guess. If the plant is stable, the zero controller is okay. If the initial guess is not stabilizing, an attempt at automatically finding a feasible initial guess is made.

If the response is oscillatory, the metric = :IE metric is expected to perform poorly and metric = :IAE is recommended. If metric = :IAE is chosen, a PID controller with a low-pass filter is tuned by minimizing $\int |e(t)| dt$. This problem is nonconvex and can be difficult to solve. This method can be initialized with the IE method by selecting metric = :IEIAE.

Index

JuliaSimControl.AutoTuningProblemType
AutoTuningProblem{S, W}

Optimizes a controller on the form

K(s) = C(s) * F(s) = (kp + ki/s + kd*s) * 1/((s*T)^2+2*ζ*T*s+1), ζ = 1/√2

\[K(s) = C(s) F(s) = (k_p + k_i/s + k_d s) \dfrac{1}{(sT)^2 + 2ζTs + 1}, ζ = 1/√2\]

Can be plotted after optimization by using Plots; plot(prob, C) where C is obtained from the optimization.

See also OptimizedPID

Keyword arguments:

  • P::LTISystem: Plant model
  • w::AbstractVector: Frequency grid vector
  • Ts::Float64: Discretization time (sample time, arbitrary time unit)
  • Tf::Float64: Simulation duration in the same time unit as Ts.
  • Ms::Float64: Maximum allowed sensitivity
  • Mt::Float64: Maximum allowed complimentary sensitivity
  • Mks::Float64: Maximum allowed noise sensitivity (controller times sensitivity)
  • pmax::Vector{Float64}: An optional vector of the same length as the number of estimated parameters that contains upper bounds on parameters, the default is fill(Inf, 4) (no bounds).
  • metric = :IAE: The metric to optimize. Choices are :IAE, :IE, :IEIAE.
  • disc: The discretization method to use when optimizinf metric = :IAE. Choices are :zoh, :foh, :tustin (delay systems only support :zoh).
source
CommonSolve.solveMethod
res = solve(prob::AutoTuningProblem, p0; kwargs...)
res = solve(prob::AutoTuningProblem; kwargs...)

Computes PID parameters, that minimize load step IAE, and filter for noise attenuation.

\[K(s) = C(s) F(s) = (k_p + k_i/s + k_d s) \dfrac{1}{(sT)^2 + 2 ζ Ts + 1}\]

  • p0 Parameter vector guess: [kp; ki; kd; T]. If p0 is not provied, attempts will be made to find one automatically.

See AutoTuningProblem for arguments. res is of type AutoTuningResult and can be plotted plot(res). It contains the optimized parameters as well as an ODESystem representing an optimized controller.

Based on K. Soltesz, C. Grimholt, S. Skogestad. Simultaneous design of proportional–integral–derivative controller and measurement filter by optimisation. Control Theory and Applications. 11(3), pp. 341-348. IET. 2017.

Solver options for metric :IAE include

  • maxeval = 500
  • maxtime = 20
  • xtol_rel = 1e-3
  • alg = :LD_CCSAQ, other local-search options are :LD_CCSAQ, :LD_MMA, :LD_SLSQP. LD_CCSAQ is the slowest algorithm, but usually produces the best result. LD_SLSQP is by far the fastest algorithm, but can be less accurate. LD_MMA is somewhere inbetween the previous two. Global algorithms include :GN_ISRES, :GN_AGS, :GN_DIRECT_L
  • random_start = 0 A positive integer indicates a number of random starts to try in order to find a good soluiton. If random_start = 0, only the provided initial guess is used.

Solver options for metric :IE include

  • maxiter = 15: Maximum number of convex-concave optimization iterations.
  • tol = 1e-3: Tolerance for the convex-concave procedure.
  • solver = Hypatia.Optimizer: Any MOI compatible solver.
  • verbose = false:

Extended help

The autotuner optimizes the reponse to load disturbances appearing on the process input. This typically leads to good regulation performance, but may result in a controller that produces large overshoots for step changes in the reference. If step changes in the reference are expected, we advice using one of the following strategies

  • Prefilter the reference using aditional lowpass filters.
  • If the system is a force/torque controlled servo system, generate a feasible reference trajectory with a continuous acceleration profile and make use of computed force/torque feedforward.
  • Let the proportional and derivative terms of the PID controller act on the measurement only. This can be achieved by setting the wp and wd keyword arguments to ModelingToolkitStandardLibrary.Blocks.LimPID (and similar to OptimizedPID).
source
JuliaSimControl.OptimizedPIDMethod
OptimizedPID(popt; name, kwargs...)
OptimizedPID(res::AutoTuningResult; name, kwargs...)

Takes optimized parameters popt and returns the following system

          ┌───┐
     ────►│ F ├───────┐ ┌─────┐
reference └───┘       └►│     │   ctr_output
                        │ PID ├─────►
          ┌───┐       ┌►│     │
       ┌─►│ F ├───────┘ └─────┘
       │  └───┘
       │
       └───── measurement

Arguments:

  • popt: Obtained by solving an AutoTuningProblem
  • kwargs: Are passed to ModelingToolkitStandardLibrary.Blocks.LimPID
source
JuliaSimControl.AutoTuningResultType
AutoTuningResult

A structure containing the results of performing PID autotuning.

This structure can be plotted plot(res; stepsize = 1), where stepsize controls the size of the reference step to show (turn off by setting to 0). See also OptimizedPID.

Fields:

  • prob::AutoTuningProblem
  • p::Vector: The optimal parameter vector.
  • K::ControlSystemsBase.StateSpace: The optimal controller.
source