YAPID (Yet Another PID Library for Arduino)


About YAPID

YAPID is another PID library for Arduino. In YAPID, we focus on more accurate implementations through detailed discretization techniques and result comparisons against MATLAB Simulink.

Details on the PID implementation are as follows:

  • Bilinear transform (trapezoidal or Tustin) method for the discretization technique
  • A derivative filter for the derivative term of the PID control
  • Simple integral windup prevention method with clamping technique

Besides PID, YAPID also has two low-pass filter implementations:

  • 1st order (time constant) low-pass filter
  • 2nd order (Butterworth) low-pass filter
Author(s) information:
Auralius Manurung - Universitas Telkom, Bandung
✉ auralius.manurung@ieee.org

Control algorithm derivations

YAPID uses bilinear transform to discretize both the PID and the filter transfer functions. Additionally, YAPID also has a clamping method implemented to prevent the integrator windup.

Mathematical details can be found in the following links:


How to use YAPID

These are the main functions that we can use:

  • float YAPID::Compute0(float set_value, float process_value)

    • This simply sends set_value as control output.
    • There is no feedback control happening here.
    • This function is useful to testing system's open-loop respose.
  • float YAPID::Compute1(float set_value, float process_value)

    • D-term is computed from the filtered errors.
    • With derivative kicks.
    • Simple integral windup prevention with clamping technique.
  • float YAPID::Compute2(float set_value, float process_value)

    • D-term is computed from the filtered process values.
    • No derivative kicks.
    • Simple integral windup prevention with clamping technique .
  • float YAPID::FOLP(float tau, float in)

    • First-order low-pass filter (time-constant filter).
  • float YAPID::SOLP(float tau, float in)

    • Second-order low-pass filter (Butterworth filter).

YAPID DOES NOT measure the elapsed time every iteration. It simply uses the provided sampling time during the setup. Therefore, to guarantee control determinism, it is easier if we use a timer interrupt handler to run the control periodically. All provided examples use timer interrupts.

To use YAPID library, first, we need to include the header file:

#include "yapid.h"

Next, we create a global YAPID object and several global variables:

// Create the PID controller
float kp = 100.;  // kp
float ki = 10.0;  // ki
float kd = 1.0;   // kd
float N  = 1.0;   // derivative filter coefficient (Hz)
float Ts = 1e-3;
YAPID pid(Ts, kp, ki, kd, N);

Within the Arduino's setup() function, we define the limits for the control's output. The default limit is . Since we use a timer interrupt, we setup out timer interrupt also in this setup() function.

#define TIMER2_INTERVAL_MS 1  // 1kHz

void setup()
{
  // Setup the timer interrupt (we use NANO, timer-1, and
  // https://github.com/khoih-prog/TimerInterrupt)
  ITimer1.init();
  ITimer1.attachInterruptInterval(TIMER1_INTERVAL_MS, Timer1Handler);

  // Define the control output limits
  // Here, the output becomes PWM signals (0 to 255)
  pid.SetOutputLimits(0., 255)

  // ...
  // ...
}

Finally, in the timer interrupt function handler, we can put our PID control. The steps are:

  • read the sensor (pv)
  • compute the PID (co)
  • apply the output to the actuator/plant
  • measure the elapsed time
void Timer1Handler()
{ 
  float pv = (float)analogRead(A0) * 5.0 / 1024.0;

  float co = pid.Compute1(SV, pv);

  analogWrite(pwm_port, (int)co);

  pid.UpdateTime();
}

RC-system

Here, our task is to use YAPID to control by modulating .

The following code listing is the Arduino Nano's implementation where we set , , and . The PID control is executed periodically (every 1 ms or 1kHz) by Timer-1.

#define TIMER_INTERRUPT_DEBUG         0
#define _TIMERINTERRUPT_LOGLEVEL_     0
#define USE_TIMER_1                   true 

#include "TimerInterrupt.h"
#include "yapid.h"

#define TIMER1_INTERVAL_MS             1

const int pwm_port = 3;  // TIMER-2   

// Create the PID controller
float kp = 100.;  // kp
float ki = 100.0; // ki
float kd = 10.0;  // kd
float N  = 100.0; // derivative filter constant (Hz)
float Ts = 1e-3;
YAPID pid(Ts, kp, ki, kd, N);

volatile float SV = 0.0;  // set value

//------------------------------------------------------------------
void setup() {
  ITimer1.init();
  ITimer1.attachInterruptInterval(TIMER1_INTERVAL_MS, Timer1Handler);

  pinMode(pwm_port, OUTPUT);  
  analogWrite(pwm_port, 0);     

  pid.SetOutputLimits(0., 255.)  ;
  Serial.begin(1000000);
}

void rx()
{
  while(Serial.available()){
    int StringCount = 0;
    String input = Serial.readString();
    SV = input.toFloat();
  }
}

inline void tx()
{
  Serial.print(pid.Now(), 3);
  Serial.print(",");
  Serial.print(pid.SV());
  Serial.print(",");
  Serial.print(pid.PV());
  Serial.print(",");
  Serial.print(pid.P());
  Serial.print(",");
  Serial.print(pid.I());
  Serial.print(",");
  Serial.print(pid.D());
  Serial.print(",");
  Serial.print(pid.CO());
  Serial.print(",");
  Serial.print(pid.SAT_CO());
  Serial.print("\n");
}

void Timer1Handler()
{ 
  float pv = (float)analogRead(A0) * 5.0 / 1024.0;
  float co = pid.Compute1(SV, pv);
  analogWrite(pwm_port, (int)co);
  pid.UpdateTime();
}

void loop()
{
  // Serial receive
  rx();
  // Serial transmit
  tx();

  if (pid.Now() < 15.0)
    SV = 0.0;
  else if ((pid.Now() > 15.0) && (pid.Now() < 30.0)) 
    SV = 4.0;
  else if (pid.Now() > 30.0) 
    SV = 1.0;
}

The next figure shows similar implementation in MATLAB Simulink with identical control parameters and sampling rate. For this, we use the Simulink® Support Package for Arduino®. The Simulink file can be downloaded here (R2024b).

Finally, the results are shown in the following plots.

As shown by the plots, YAPID gives results that are very close to MATLAB Simulink.

DC-motor control (with quadrature encoder)

The first picture below is the cheap N20 DC motor (purchase link) that comes with a magnetic quadrature encoder that generate 7 pulses per rotation. As for the second and third pictures below, they show the overall system with an Arduino Uno and an Arduino Motor Shield rev. 3 (purchase link).

150 300 400

The following code listing is the Arduino Uno's implementation where we set , , , and . The PID control is executed periodically (every 1000 us or 1kHz) in the Arduino's loop() function.

/**
 * N20 DC-motor with rotary encoder. 
 * The quadrature encoder generates 7 pulses per rotation.
 * The encoder readings will be set to x1 mode, thus, only channel A 
 * will trigger the external interrupt. Motor gear ratio is 210:1.
 */

#include "yapid.h"

#define PID_LOOP_INTERVAL_US    1000

// Pin/port configurations
int encoderA_pin   = 2;  // Digital pin #2, INT0
int encoderB_pin   = 3;  // Digital pin #4
const int pwm_port = 11; // PWM of motor, Timer 2
const int dir_port = 13; // Direction of the motor.

// Create the PID controller
float kp = 10.;   // kp
float ki = 4.0;   // ki
float kd = 0.01;  // kd
float N  = 100.0; // derivative filter constant (Hz)
float Ts = 1e-3;
YAPID pid(Ts, kp, ki, kd, N);

volatile float SV      = 0.0;     // set value
volatile long pulses   = 0;       // Output pulses.
const float ppr        = 7*210-1; // Pulses per rotation 

static unsigned long lastLoop = 0;


//------------------------------------------------------------------------
void setup() {
  Serial.begin(921600);

  pinMode(pwm_port, OUTPUT);
  pinMode(dir_port, OUTPUT);
  pinMode(encoderA_pin, INPUT);
  pinMode(encoderB_pin, INPUT);

  analogWrite(pwm_port, 0);     
  digitalWrite(dir_port, HIGH);

  attachInterrupt(0, A_CHANGE, RISING); 

  pid.SetOutputLimits(-254., 254.);
}

void rx()
{
  while(Serial.available()){
    int StringCount = 0;
    String input = Serial.readString();
    SV = input.toFloat();
  }
}

inline void tx()
{
  Serial.print(pid.Now(), 3);
  Serial.print(",");
  Serial.print(pid.SV());
  Serial.print(",");
  Serial.print(pid.PV());
  Serial.print("\n");
}

inline void runPID()
{
  float pv =  (float)pulses / ppr * 360.; // in degs

  float co = pid.Compute1(SV, pv);
  analogWrite(pwm_port, (int)abs(co));

  if (co > 0.0)
    digitalWrite(dir_port, HIGH);
  else
    digitalWrite(dir_port, LOW);

  pid.UpdateTime();
}

void loop()
{    
  runPID();

  // --------------------------------------------------------------------------
  // wait and do something else!
    while(micros()-lastLoop < PID_LOOP_INTERVAL_US) {
    rx();
    tx();

    // Experiment routines
    float now = pid.Now();
    if (now < 5.0)
      SV = 0.0;
    else if ((now > 5.0) && (now < 8.0)) 
      SV = 180.0;
    else if (now > 8.0 && (now < 11.0)) 
      SV = -180.0;
    else if (now > 11.0) 
      SV = 0.0;
  }
  lastLoop = micros();
}

void A_CHANGE()
{
  if( digitalRead(encoderA_pin) == digitalRead(encoderB_pin) )
    pulses--; // moving reverse
  else 
    pulses++; // moving forward
}  

Since the quadrature encoder is serviced by an external interrupt handler, we found the readings to be more robust if we put the PID loop in the Arduino's loop() function instead of as a timer interrupt service.

The next figure shows similar implementation in MATLAB Simulink with identical control parameters and sampling rate. The Simulink file can be downloaded here (R2024b).

Note that to read the quadrature encoder, we create our own Simulink block since the shipped quadrature encoder block only allows -mode readings. As for the custom quadrature encoder block, it allows -mode readings. Thus, it is necessary to first make sure that MATLAB is configured properly for running/building C MEX function (refer to this link).

Finally, the results are shown in the following plots.

As shown by the plots, YAPID gives results that are very close to MATLAB Simulink.


Derivative kicks

Derivative control causes a spike in the control output when set value changes abruptly. To eliminate this spike, the derivative term is computed from the process value instead of from the set value. See the figure below.

The implementation in YAPID can be found in compute2(). The several following plots show the derivative terms of compute1() and compute2(). As shown in the center plot, spikes occur every time the set values are changed abruptly. In the bottom plot, there are no spikes since the derivative term now takes the smooth process value. Finally, the control process value by compute2() is smoother then by compute1(). The data was taken by using the same RC-system as in the earlier section.


Using the low-pass filter

In order to use the filter, we first create a YAPID object by using the following codes.

float Ts = 0.001;
YAPID pid(Ts);

After that, we can run the filter periodically by calling the filter function. For first order low-pass filter:

// float signal = ....
float filt_signal = pid1.FOLP(0.1, signal); // time-constant = 0.1 seconds

For second order low-pass filter:

// float signal = ....
float filt_signal = pid1.SOLP(10, signal); // cut-off frequency = 10Hz

The following code listing shows a complete program for using the low-pass filter in the previous RC-system. We are going to run two filters for comparison purposes. Thus, we need to create two YAPID object for each filter. There is no PID control here.

/**
 * A simple serial RC system with R = 20kΩ and C = 100uF
 * PWM signal from D3 (Timer-2) is applied to the RC system.
 * Voltage across the capacitor is measured by A0.
 */

#define TIMER_INTERRUPT_DEBUG         0
#define _TIMERINTERRUPT_LOGLEVEL_     0
#define USE_TIMER_1                   true 

#include "TimerInterrupt.h"
#include "yapid.h"

#define TIMER1_INTERVAL_MS             1

const int pwm_port = 3;  // TIMER-2   

// Create the PID controller
float Ts = 1e-3;
YAPID pid1(Ts); // for first-order filter demo
YAPID pid2(Ts); // for second-order filter demo

volatile float SV = 0.0;  // set value from 0 to 5 

// -----------------------------------------------------------------
void setup() {
  ITimer1.init();
  ITimer1.attachInterruptInterval(TIMER1_INTERVAL_MS, Timer1Handler);

  pinMode(pwm_port, OUTPUT); 
  analogWrite(pwm_port, 0);     

  Serial.begin(250000);
}

inline void tx()
{
  Serial.print(pid1.Now(), 3);
  Serial.print(",");

  Serial.print(pid1.X());
  Serial.print(",");

  Serial.print(pid1.Y());
  Serial.print(",");

  Serial.print(pid2.Y());
  Serial.print("\n");
}

void Timer1Handler()
{ 
  float pv = (float)analogRead(A0) * 5.0 / 1024.0;
  float pv_filtered1 = pid1.FOLP(0.1, pv);
  float pv_filtered2 = pid2.SOLP(10.0, pv);

  // Sinusoid, f=0.5Hz, peak-to-peak values: 0 to 1 volt
  float pwm = (sin(2*3.1415*0.5*pid1.Now()) + 1.0) / 5.0 * 255.0;
  analogWrite(pwm_port, (int)pwm);

  pid1.UpdateTime(); // just pid1, no need for pid2
}

void loop()
{
  // Serial transmit
  tx();
}

The results are shown in the plot below: value 2: original signal, value 3: filtered signal with first order low-pass filter, value 4: filtered signal with second order low-pass filter.