Digital Control


By Prof. Seungchul Lee
http://iai.postech.ac.kr/
Industrial AI Lab at POSTECH

Table of Contents

1. Control Systems

Goal: to understand the concept of control

  • Microcomputers are widely employed in control systems:

    • automotive ABS, ignition and fuel systems
    • household appliances
    • smart weapons
    • industrial robots
  • Human-in-the-loop

    • many examples in our life


Strategy

  • plant is a system that is intended to be controlled

  • collect information concerning the plant - data acquisition system (DAQ)

  • compare with desired performance

  • generate outputs to bring plant closer to desired performance


Performance metrics

  • steady-state controller error

    • an average value of the difference between desired and actual performance
  • transient response

    • how quickly the system responds to change
  • stability

    • system output changes smoothly without too much oscillation or unlimited excursions


Open-loop control

  • state estimator eliminated

    • not well suited for a complex plant
  • assumes disturbing forces have little effect on the plant

  • less expensive than closed-loop control

    • example: electric toaster


Closed-loop control

  • feedback loop implementation

    • suitable for a complex plant
  • sensors and state estimator produce representaiton/estimation of state variables

  • these values are compared to desired values

  • control software generates control commands based upon the differences between estimated and desired values

In [12]:
%%html
<center><iframe src="https://www.youtube.com/embed/UVAn6sGnQ38?start=0&end=400"
width="420" height="315" frameborder="0" allowfullscreen></iframe></center>

2. PID Control

2.1. What is PID control ?

Goal: To understand the PID control (the most common and popular control method)


$$ \begin{align*} e &= x^* - x\\ u &= K_p \, e + K_i \int e \,dt + K_d \, \frac{de}{dt} \end{align*} $$


PID lectures from 'Control of Mobile Robots' by Prof. Magnus Egerstedt (Georgia Tech)

  • Must watch the below 3 video lectures to understand the basic concept of PID control
In [13]:
%%html
<center><iframe src="https://www.youtube.com/embed/DJuo9kLdr4M?list=PLp8ijpvp8iCvFDYdcXqqYU5Ibl_aOqwjr" 
width="560" height="315" frameborder="0" allowfullscreen></iframe></center>
In [14]:
%%html
<center><iframe src="https://www.youtube.com/embed/cQhqx65kLfM?list=PLp8ijpvp8iCvFDYdcXqqYU5Ibl_aOqwjr" 
width="560" height="315" frameborder="0" allowfullscreen></iframe></center>
In [15]:
%%html
<center><iframe src="https://www.youtube.com/embed/Mk1ygHj4zxw?list=PLp8ijpvp8iCvFDYdcXqqYU5Ibl_aOqwjr" 
width="560" height="315" frameborder="0" allowfullscreen></iframe></center>

2.2. Digital PID control

Goal: from continuous to digital control


$$ \begin{array}{lcl} & e & = & x^* - x \\ \\ & u & = & u_p + u_i + u_d\\ \\ \text{Proportional} \qquad & u_p & = & K_p e \\ \\ \text{Integral} & u_i & = & K_i \int e \,dt \\ \\ \text{Derivative} & u_d & = & K_d \frac{de}{dt} \end{array} $$ $$ \begin{array}{lcl} & E & = & X^{*} - X\\ \\ & U & = & U_p + U_i + U_d \\ \\ & U_p & = & K_p E \\ \\ & U_i & = & U_i + K_i \, E \, \Delta t \\ \\ & U_d & = & K_d \, \frac{E[n] - E[n-1]}{\Delta t} \end{array} $$

  • Rule of thumb
    • Run 10 times faster than a plant time constant
    • Run slower or equal to sensor sampling rate
    • if sensor signals are too noisy, do not use a derivative term in a feedback control
    • if there is a delay in a closed-loop, the system tends to be unstable
    • lifesaver: $\min \leq U \leq \max$

PID lectures from 'Design of Embedded Systems' by Prof. Jonathan W. Valvano (UT, Austin)

  • Brief introduction to PID control and digital control
In [16]:
%%html
<center><iframe src="https://www.youtube.com/embed/UVAn6sGnQ38?start=400"
width="420" height="315" frameborder="0" allowfullscreen></iframe></center>

3. Implementation of PID Control

Goal: PID implementation with Arduino

  • Position-stabilizing a propeller-levitated arm
  • Example from 'Introduction to Control System Design - A First Look' by Prof. Jacob White (MIT)
  • The control testbed shown below is made by iSystems, UNIST

3.1. Unicopter overview

PID DC motor control examples

In [11]:
%%html
<center><iframe src="https://www.youtube.com/embed/N8UX_TDMn-Y?list=PLBD_gON7g_m3th-gxjQRma1z-1Cc8M7t4" 
width="560" height="315" frameborder="0" allowfullscreen></iframe></center>
In [10]:
%%html
<center><iframe src="https://www.youtube.com/embed/5yaVvEfKF84" 
width="560" height="315" frameborder="0" allowfullscreen></iframe></center>

Equations of Motion

3.2. Electronic components and circuit

3.3. Arduino PID codes

$$ \begin{align*} E &= X^{*} - X\\ \\ U &= U_p + U_i + U_d \end{align*} $$


$$ \begin{align*} \text{Proportional} \qquad & U_p = K_p E \\ \\ \text{Integral} \qquad & U_i = U_i + K_i \, E \, \Delta t \\ \\ \text{Derivative} \qquad & U_d = K_d \, \frac{E[n] - E[n-1]}{\Delta t} \end{align*} $$

In [17]:
%%html
<center><iframe src="https://www.youtube.com/embed/B5OVCONRZP0?start=387" 
width="560" height="315" frameborder="0" allowfullscreen></iframe></center>

Arduino 1

  • kP, kI, kD values are given
const int pin_motorPwm = 3;
const int pin_analogRead = A0;

float dt = 0.01;          // (sec)
float targetAngle = 180;  // (degree)
float target = 0;

float kP = 0.45;
float kI = 0.9;
float kD = 0.12;

float P, I, D = 0;
float actual = 0.;
float error = 0.;
float error_last = 0.;

int U = 0;

unsigned long lPrevMillis = 0;
unsigned long lCurrMillis = 0;

void setup() {
  pinMode(pin_analogRead, INPUT);
  pinMode(pin_motorPwm, OUTPUT);
  target = targetAngle * 943 / 360 + 39;
}

void loop() {

  ///////////////////////////////////////////////////////////
  //                  PID Control
  ///////////////////////////////////////////////////////////

  lCurrMillis = millis();

  if (lCurrMillis - lPrevMillis >= dt * 1000) {
    lPrevMillis = lCurrMillis;

    actual = analogRead(pin_analogRead);
    error = target - actual;

    P = kP * error;
    I += kI * error * dt;
    D = kD * (error - error_last) / dt;

    U = (int)(P + I + D);

    if (U < 0)
      U = 0;
    else if (U > 255)
      U = 255;

    analogWrite(pin_motorPwm, U);
    error_last = error;
  }
}

Arduino 2

  • Changeable kP, kI, kD values through serial communication
  • Input kP, kI, kD values through serial monitor window
  • Note that the values have to be in order (kP, kI, kD) and must be separated by commas and a space. (example: 0.45, 0.90, 0.12)
const int pin_motorPwm = 3;
const int pin_analogRead = A0;

float dt = 0.01;          // (sec)
float targetAngle = 180;  // (degree)
float target = 0;

float kP = 0.45;
float kI = 0.90;
float kD = 0.12;

float P, I, D = 0;
float actual = 0.;
float error = 0.;
float error_last = 0.;

int U = 0;

unsigned long lPrevMillis = 0;
unsigned long lCurrMillis = 0;

void setup() {
  pinMode(pin_analogRead, INPUT);
  pinMode(pin_motorPwm, OUTPUT);
  target = targetAngle * 943 / 360 + 39;
  Serial.begin(9600);
}

void loop() {

  ///////////////////////////////////////////////////////////
  //             kP, kI, kD Values Input
  ///////////////////////////////////////////////////////////

  if (Serial.available()) {
    String firstVal  = Serial.readStringUntil(',');
    Serial.read();  //next character is comma, so skip it using this
    String secondVal = Serial.readStringUntil(',');
    Serial.read();
    String thirdVal  = Serial.readStringUntil('\n');

    kP = firstVal.toFloat();
    kI = secondVal.toFloat();
    kD = thirdVal.toFloat();
  }

  ///////////////////////////////////////////////////////////
  //                  PID Control
  ///////////////////////////////////////////////////////////

  lCurrMillis = millis();

  if (lCurrMillis - lPrevMillis >= dt * 1000) {
    lPrevMillis = lCurrMillis;

    actual = analogRead(pin_analogRead);
    error = target - actual;

    P = kP * error;
    I += kI * error * dt;
    D = kD * (error - error_last) / dt;

    U = (int)(P + I + D);

    if (U < 0)
      U = 0;
    else if (U > 255)
      U = 255;

    analogWrite(pin_motorPwm, U);
    error_last = error;
  }
}

3.4. Arduino PID and Python

Goal: PID control with Python and Arduino

Arduino 3

  • The slide bars can be adjusted to find better kP, kI, and kD values
  • The target and encoder values are plotted on the first graph, and the control input values for P,I, and D are plotted subsequently


Arduino code

const int pin_motorPwm = 3;
const int pin_analogRead = A0;

float dt = 0.01;          // (sec)
float targetAngle = 180;  // (degree)
float target = 0;

float kP = 0.45;
float kI = 0.90;
float kD = 0.12;

float P, I, D = 0;
float actual = 0.;
float error = 0.;
float error_last = 0.;

int U = 0;
int cnt = 0;

unsigned long lPrevMillis = 0;
unsigned long lCurrMillis = 0;

void setup() {
  pinMode(pin_analogRead, INPUT);
  pinMode(pin_motorPwm, OUTPUT);
  target = targetAngle * 943 / 360 + 39;
  Serial.begin(9600);
  Serial.setTimeout(5);
}

void loop() {

  ///////////////////////////////////////////////////////////
  //             kP, kI, kD Values Input
  ///////////////////////////////////////////////////////////

  if (Serial.available()) {
    String firstVal  = Serial.readStringUntil(',');
    Serial.read();  //next character is comma, so skip it using this
    String secondVal = Serial.readStringUntil(',');
    Serial.read();
    String thirdVal  = Serial.readStringUntil('\n');

    kP = firstVal.toFloat();
    kI = secondVal.toFloat();
    kD = thirdVal.toFloat();
  }

  ///////////////////////////////////////////////////////////
  //                  PID Control
  ///////////////////////////////////////////////////////////

  lCurrMillis = millis();

  if (lCurrMillis - lPrevMillis >= dt * 1000) {
    lPrevMillis = lCurrMillis;

    actual = analogRead(pin_analogRead);

    error = target - actual;

    P = kP * error;
    I += kI * error * dt;
    D = kD * (error - error_last) / dt;

    U = (int)(P + I + D);

    if (U < 0)
      U = 0;
    else if (U > 255)
      U = 255;

    analogWrite(pin_motorPwm, U);
    error_last = error;

    cnt++;
  }

  ///////////////////////////////////////////////////////////
  //                  Serial out at every dt * cnt
  ///////////////////////////////////////////////////////////

  if ( cnt >= 5 ) {
    Serial.print(actual); Serial.print(",");    
    Serial.print(P); Serial.print(",");   
    Serial.print(I); Serial.print(",");    
    Serial.println(D);
    cnt = 0;
  }
}

Python code

import serial
import numpy as np
from matplotlib import pyplot as plt
from matplotlib import animation
from matplotlib.widgets import Slider, Button, CheckButtons

#################################################################
##                    setup 
#################################################################

ser = serial.Serial('COM4', 9600)

leng = 101
fig = plt.figure(figsize=(12, 8))
ax1 = fig.add_subplot(4, 1, 1)
ax2 = fig.add_subplot(4, 1, 2)
ax3 = fig.add_subplot(4, 1, 3)
ax4 = fig.add_subplot(4, 1, 4)
plt.subplots_adjust(bottom=0.225)

ax1.set_title('Real-time System Response with PID')
ax1.set_ylabel('Angle [Degree]')
ax1.set_xlim(0, leng - 1)
ax1.set_ylim(130, 230)
ax1.grid(True)

angleR, = ax1.plot([], [], 'b',  label = 'angleR')
angleD, = ax1.plot([], [], 'k--', label = 'angleD')

errorP, = ax2.plot([], [], 'r',  label = 'P')
errorI, = ax3.plot([], [], 'g',  label = 'I')
errorD, = ax4.plot([], [], 'b',  label = 'D')

axes = [ax2, ax3, ax4]
axel = ['P', 'I', 'D']

for i in range(3):
    axes[i].set_ylabel(axel[i])
    axes[i].set_xlim(0, leng - 1)    
    axes[i].grid(True)
    axes[i].legend(loc='upper left')

ax2.set_ylim(-100, 100)
ax3.set_ylim(-20, 180)
ax4.set_ylim(-100, 100)

ax1.legend(loc='upper left')

t = list(range(0, leng))
angle = []
dataP = []
dataI = []
dataD = []

for i in range(0, leng):
    angle.append(180)
    dataP.append(0)
    dataI.append(0)
    dataD.append(0)

#################################################################
##                    Adjust kP, kI, kD
#################################################################

kP = 0.45
kI = 0.90
kD = 0.10

axcolor = 'lightgoldenrodyellow'
axP = plt.axes([0.125, 0.15, 0.775, 0.025], axisbg=axcolor)
axI = plt.axes([0.125, 0.10, 0.775, 0.025], axisbg=axcolor)
axD = plt.axes([0.125, 0.05, 0.775, 0.025], axisbg=axcolor)

sP = Slider(axP, 'kP', 0.09, 0.90, valinit=kP)
sI = Slider(axI, 'kI', 0.18, 1.80, valinit=kI)
sD = Slider(axD, 'kD', 0.02, 0.20, valinit=kD)

def update(val):
    global kP, kI, kD
    kP = sP.val
    kI = sI.val
    kD = sD.val

sP.on_changed(update)
sI.on_changed(update)
sD.on_changed(update)

#################################################################
##                    Animation Loop
#################################################################

def init():
    angleR.set_data([], [])
    angleD.set_data([0, leng], [180, 180])
    errorP.set_data([], [])
    errorI.set_data([], [])
    errorD.set_data([], [])
    return angleR, angleD, errorP, errorI, errorD,

def animate(i):
    global t, angle, dataP, dataI, dataD, kP, kI, kD

    while (ser.inWaiting() == 0):
        pass

    try:
        arduinoString = ser.readline().decode("utf-8")
        dataArray = (arduinoString.split(','))

        angle.append((float(dataArray[0]) - 39) * 360 / 943)
        angle.pop(0)
        dataP.append(float(dataArray[1]))
        dataP.pop(0)
        dataI.append(float(dataArray[2]))
        dataI.pop(0)
        dataD.append(float(dataArray[3]))
        dataD.pop(0)

        PIDcoeff = str(kP) + ', ' + str(kI) + ', ' + str(kD) + '\n'
        ser.write(PIDcoeff.encode('utf-8'))

        angleR.set_data(t, angle)
        errorP.set_data(t, dataP)
        errorI.set_data(t, dataI)
        errorD.set_data(t, dataD)
    except:
        pass

    return angleR, angleD, errorP, errorI, errorD,

delay = 50    # dt * cnt
anim = animation.FuncAnimation(fig, animate, init_func=init,
                               interval=delay, blit=True)

plt.show()
In [19]:
ser.close()
In [1]:
%%javascript
$.getScript('https://kmahelona.github.io/ipython_notebook_goodies/ipython_notebook_toc.js')