What is PID Controller and Why Does It Matter?
PID (Proportional-Integral-Derivative) is the most common control algorithm in engineering. From temperature control in ovens to maintaining drone balance, from cruise control in cars to position control in robot arms -- PID is everywhere.
The reason is simple: PID is simple, effective, and good enough for ~90% of control problems in robotics. Before jumping into MPC (Model Predictive Control) or Reinforcement Learning, you need to master PID.
This tutorial will take you from basic theory to implementing a PID controller in Python, tuning using the Ziegler-Nichols method, handling anti-windup, and real-world application to DC motor control.
PID Theory -- 3 Components
Basic Control Loop
Setpoint (r) → [+] → e(t) → [PID Controller] → u(t) → [Plant/Motor] → y(t)
[-] |
↑ |
└───────────────── Feedback ────────────────────────────┘
- Setpoint r(t): Desired value (example: 100 RPM speed)
- Error e(t) = r(t) - y(t): Difference between setpoint and actual output
- Control signal u(t): Signal sent to actuator
- Plant output y(t): Output measured from sensor
P -- Proportional (Proportional Term)
The P component creates output proportional to current error:
u_P(t) = Kp * e(t)
- Large Kp: Fast response, but prone to oscillation
- Small Kp: Slow response, but more stable
- Problem: Always has steady-state error. A P-only controller never reaches setpoint exactly.
I -- Integral (Integral Term)
The I component accumulates error over time:
u_I(t) = Ki * integral(e(t) dt)
- Main role: Eliminates steady-state error. When error is small but persistent, I accumulates and produces additional output.
- Large Ki: Removes error quickly, but causes overshoot
- Small Ki: Removes error slowly, but less overshoot
- Problem: Integral windup -- when actuator saturates (e.g., motor at max speed), I keeps accumulating → large overshoot when constraint is released.
D -- Derivative (Derivative Term)
The D component responds to rate of change of error:
u_D(t) = Kd * d(e(t))/dt
- Main role: Predicts future error, reduces overshoot. When error is decreasing rapidly, D reduces output to prevent exceeding setpoint.
- Large Kd: Reduces overshoot well, but sensitive to noise
- Small Kd: Less effective but more stable
- Problem: Derivative kick -- when setpoint changes suddenly, derivative of error spikes very high.
Combined Formula
u(t) = Kp * e(t) + Ki * integral(e(t) dt) + Kd * d(e(t))/dt
Implementing PID in Python
Basic PID Class
import time
import numpy as np
class PIDController:
def __init__(self, kp: float, ki: float, kd: float,
output_min: float = -1.0, output_max: float = 1.0,
anti_windup: bool = True):
self.kp = kp
self.ki = ki
self.kd = kd
self.output_min = output_min
self.output_max = output_max
self.anti_windup = anti_windup
# Internal state
self._integral = 0.0
self._prev_error = 0.0
self._prev_time = None
self._prev_measurement = 0.0 # For derivative-on-measurement
def reset(self):
"""Reset internal state."""
self._integral = 0.0
self._prev_error = 0.0
self._prev_time = None
self._prev_measurement = 0.0
def compute(self, setpoint: float, measurement: float,
dt: float = None) -> float:
"""
Compute PID output.
Args:
setpoint: Desired value
measurement: Current measured value
dt: Time step (seconds). Auto-calculated if None.
Returns:
Control signal (clamped to output_min/output_max)
"""
current_time = time.monotonic()
if dt is None:
if self._prev_time is None:
dt = 0.01 # Default 10ms
else:
dt = current_time - self._prev_time
self._prev_time = current_time
# Error
error = setpoint - measurement
# Proportional
p_term = self.kp * error
# Integral
self._integral += error * dt
i_term = self.ki * self._integral
# Derivative (on measurement, not error -- avoid derivative kick)
d_measurement = (measurement - self._prev_measurement) / dt if dt > 0 else 0.0
d_term = -self.kd * d_measurement # Negative because we use measurement
# Total output
output = p_term + i_term + d_term
# Anti-windup: clamp integral when output saturates
if self.anti_windup:
if output > self.output_max:
self._integral -= (output - self.output_max) / self.ki if self.ki != 0 else 0
output = self.output_max
elif output < self.output_min:
self._integral -= (output - self.output_min) / self.ki if self.ki != 0 else 0
output = self.output_min
else:
output = np.clip(output, self.output_min, self.output_max)
# Save state
self._prev_error = error
self._prev_measurement = measurement
return output
Explaining Anti-Windup
Anti-windup using the back-calculation method: when output is clamped (saturated), we subtract the excess from the integral term. This prevents integral from "accumulating" when the actuator cannot increase further.
# Anti-windup back-calculation
if output > self.output_max:
excess = output - self.output_max
self._integral -= excess / self.ki # "Return" excess to integral
output = self.output_max
Explaining Derivative-on-Measurement
Instead of computing derivative of error, we compute derivative of measurement:
# Derivative kick (BAD -- error spike when setpoint changes)
d_term = self.kd * (error - self._prev_error) / dt
# Derivative on measurement (GOOD -- smooth, no spike)
d_term = -self.kd * (measurement - self._prev_measurement) / dt
When setpoint changes suddenly (step change), error jumps immediately → very large derivative spike (derivative kick). Using derivative on measurement avoids this because measurement changes continuously, smoothly.
PID Tuning Methods
1. Ziegler-Nichols (Oscillation Method)
The classical method, invented in 1942 but still widely used:
Step 1: Set Ki = 0, Kd = 0 (use only P controller)
Step 2: Increase Kp gradually until system oscillates steadily (sustained oscillation). Record:
- Ku (Ultimate gain): Kp value at oscillation point
- Tu (Ultimate period): Oscillation period
Step 3: Calculate PID gains using table:
| Controller | Kp | Ki | Kd |
|---|---|---|---|
| P only | 0.5 * Ku | - | - |
| PI | 0.45 * Ku | 1.2 * Kp / Tu | - |
| PID | 0.6 * Ku | 2 * Kp / Tu | Kp * Tu / 8 |
def ziegler_nichols_pid(ku: float, tu: float) -> tuple:
"""
Calculate PID gains using Ziegler-Nichols method.
Args:
ku: Ultimate gain (Kp at sustained oscillation)
tu: Ultimate period (oscillation period in seconds)
Returns:
(kp, ki, kd) tuple
"""
kp = 0.6 * ku
ki = 2.0 * kp / tu
kd = kp * tu / 8.0
return kp, ki, kd
# Example: Ku = 2.0, Tu = 0.5s
kp, ki, kd = ziegler_nichols_pid(ku=2.0, tu=0.5)
print(f"Kp={kp:.2f}, Ki={ki:.2f}, Kd={kd:.2f}")
# Output: Kp=1.20, Ki=4.80, Kd=0.075
2. Manual Tuning -- Practical Rules
If Ziegler-Nichols gives aggressive results (much overshoot), tune manually in this order:
- Start with P only: Increase Kp until response is "just fast enough" but has steady-state error.
- Add I: Gradually increase Ki to eliminate steady-state error. Stop when overshoot < 10%.
- Add D: Increase Kd to reduce overshoot. Be careful with noise -- if sensor is noisy, keep Kd small.
# Effect of each parameter
# Increase Kp: Faster, more overshoot, smaller steady-state error
# Increase Ki: Eliminates steady-state error, more overshoot, slower settle
# Increase Kd: Reduces overshoot, faster response, sensitive to noise
Simulation and Visualization with Matplotlib
import numpy as np
import matplotlib.pyplot as plt
class DCMotorSimulation:
"""Simple DC motor simulation."""
def __init__(self, inertia=0.01, damping=0.1, kt=0.01,
resistance=1.0, inductance=0.5):
self.J = inertia # Moment of inertia (kg*m^2)
self.b = damping # Damping ratio (N*m*s)
self.Kt = kt # Torque constant (N*m/A)
self.R = resistance # Resistance (Ohm)
self.L = inductance # Inductance (H)
self.omega = 0.0 # Angular velocity (rad/s)
self.current = 0.0 # Motor current (A)
def step(self, voltage: float, dt: float) -> float:
"""Simulate one timestep, return angular velocity."""
# Electrical: L * di/dt = V - R*i - Kt*omega
di_dt = (voltage - self.R * self.current - self.Kt * self.omega) / self.L
self.current += di_dt * dt
# Mechanical: J * domega/dt = Kt*i - b*omega
domega_dt = (self.Kt * self.current - self.b * self.omega) / self.J
self.omega += domega_dt * dt
return self.omega
def simulate_pid(kp, ki, kd, setpoint=100.0, duration=5.0, dt=0.001):
"""Run PID simulation on DC motor."""
motor = DCMotorSimulation()
pid = PIDController(kp, ki, kd, output_min=-12.0, output_max=12.0)
times = np.arange(0, duration, dt)
velocities = []
setpoints = []
controls = []
for t in times:
# Step change at t=0 and t=2.5s
sp = setpoint if t < 2.5 else setpoint * 0.5
setpoints.append(sp)
velocity = motor.omega
velocities.append(velocity)
control = pid.compute(sp, velocity, dt=dt)
controls.append(control)
motor.step(control, dt)
return times, velocities, setpoints, controls
# Compare 3 parameter sets
fig, axes = plt.subplots(3, 1, figsize=(12, 10), sharex=True)
configs = [
{"kp": 0.5, "ki": 0.0, "kd": 0.0, "label": "P only (Kp=0.5)"},
{"kp": 0.5, "ki": 2.0, "kd": 0.0, "label": "PI (Kp=0.5, Ki=2.0)"},
{"kp": 0.8, "ki": 3.0, "kd": 0.01, "label": "PID (Kp=0.8, Ki=3.0, Kd=0.01)"},
]
for cfg in configs:
t, vel, sp, ctrl = simulate_pid(cfg["kp"], cfg["ki"], cfg["kd"])
axes[0].plot(t, vel, label=cfg["label"])
axes[1].plot(t, [s - v for s, v in zip(sp, vel)], label=cfg["label"])
axes[2].plot(t, ctrl, label=cfg["label"])
axes[0].plot(t, sp, "k--", label="Setpoint", alpha=0.5)
axes[0].set_ylabel("Velocity (rad/s)")
axes[0].set_title("PID Response Comparison")
axes[0].legend()
axes[1].set_ylabel("Error")
axes[1].set_title("Error Over Time")
axes[1].legend()
axes[2].set_ylabel("Control Signal (V)")
axes[2].set_xlabel("Time (s)")
axes[2].set_title("Control Effort")
axes[2].legend()
plt.tight_layout()
plt.savefig("pid_comparison.png", dpi=150)
plt.show()
Real-World Application: DC Motor + Encoder
Hardware Setup
A typical setup for PID motor control:
- DC Motor: 12V, 200 RPM (example JGA25-370)
- Encoder: 11 PPR (Pulses Per Revolution), quadrature -> 44 counts/rev
- Motor Driver: L298N H-bridge
- Controller: Arduino Uno or ESP32
Arduino Code (Reading Encoder + PID)
// Arduino PID Motor Control
#include <PID_v1.h>
// Encoder pins
#define ENCODER_A 2 // Interrupt pin
#define ENCODER_B 3
#define MOTOR_PWM 9
#define MOTOR_DIR 8
volatile long encoderCount = 0;
double setpoint = 100.0; // Target RPM
double input = 0.0; // Measured RPM
double output = 0.0; // PWM output
// PID gains (tuned via Ziegler-Nichols)
double Kp = 2.0, Ki = 5.0, Kd = 0.1;
PID myPID(&input, &output, &setpoint, Kp, Ki, Kd, DIRECT);
unsigned long prevTime = 0;
long prevCount = 0;
void setup() {
Serial.begin(115200);
pinMode(ENCODER_A, INPUT_PULLUP);
pinMode(ENCODER_B, INPUT_PULLUP);
pinMode(MOTOR_PWM, OUTPUT);
pinMode(MOTOR_DIR, OUTPUT);
attachInterrupt(digitalPinToInterrupt(ENCODER_A), readEncoder, RISING);
myPID.SetMode(AUTOMATIC);
myPID.SetOutputLimits(-255, 255);
myPID.SetSampleTime(10); // 10ms = 100Hz
}
void loop() {
unsigned long now = millis();
if (now - prevTime >= 10) {
// Calculate RPM from encoder counts
long counts = encoderCount;
double rpm = (double)(counts - prevCount) / 44.0 * 60000.0 / (now - prevTime);
input = rpm;
prevCount = counts;
prevTime = now;
// Compute PID
myPID.Compute();
// Apply output
if (output >= 0) {
digitalWrite(MOTOR_DIR, HIGH);
analogWrite(MOTOR_PWM, (int)output);
} else {
digitalWrite(MOTOR_DIR, LOW);
analogWrite(MOTOR_PWM, (int)(-output));
}
// Debug
Serial.print(setpoint);
Serial.print(",");
Serial.println(input);
}
}
void readEncoder() {
if (digitalRead(ENCODER_B) == HIGH) encoderCount++;
else encoderCount--;
}
ROS 2 Integration
In ROS 2, PID controller is typically implemented in the ros2_control framework:
# ROS 2 PID node (simplified)
import rclpy
from rclpy.node import Node
from std_msgs.msg import Float64
class PIDNode(Node):
def __init__(self):
super().__init__('pid_controller')
# Parameters
self.declare_parameter('kp', 1.0)
self.declare_parameter('ki', 0.5)
self.declare_parameter('kd', 0.01)
self.declare_parameter('setpoint', 0.0)
kp = self.get_parameter('kp').value
ki = self.get_parameter('ki').value
kd = self.get_parameter('kd').value
self.pid = PIDController(kp, ki, kd)
self.setpoint = self.get_parameter('setpoint').value
# Subscribers & Publishers
self.sub = self.create_subscription(
Float64, '/motor/velocity', self.feedback_callback, 10)
self.pub = self.create_publisher(
Float64, '/motor/command', 10)
# 100Hz control loop
self.timer = self.create_timer(0.01, self.control_loop)
self.measurement = 0.0
def feedback_callback(self, msg):
self.measurement = msg.data
def control_loop(self):
output = self.pid.compute(self.setpoint, self.measurement, dt=0.01)
cmd = Float64()
cmd.data = output
self.pub.publish(cmd)
def main():
rclpy.init()
node = PIDNode()
rclpy.spin(node)
With ros2_control, PID controller is already available in the ros2_controllers package as forward_command_controller combined with pid_controller. See the ros2_control hardware interface tutorial for connecting to real hardware.
Practical Tips
1. Always Filter Derivative Term
Sensor noise is amplified by the derivative. Add a low-pass filter:
# Exponential moving average for derivative
alpha = 0.1 # Filter coefficient (0-1, smaller = smoother)
filtered_derivative = alpha * raw_derivative + (1 - alpha) * prev_filtered
2. Derivative-on-Measurement, Not Error
As explained earlier, always compute derivative from measurement instead of error to avoid derivative kick.
3. Integral Clamping
Beyond anti-windup, limit the absolute value of the integral term:
max_integral = 100.0
self._integral = np.clip(self._integral, -max_integral, max_integral)
4. Consistent Sample Time
PID works best with consistent dt. On microcontroller, use timer interrupt instead of delay().
5. Feed-Forward for Better Performance
Combine PID with feed-forward term when system model is known:
# Feed-forward + PID
ff_term = setpoint * feed_forward_gain # Open-loop estimate
pid_term = pid.compute(setpoint, measurement)
output = ff_term + pid_term # Combine
Moving Beyond PID
PID is the first step. As systems become more complex, you will need:
- Cascade PID: Multiple nested PIDs (position -> velocity -> current loop)
- Gain Scheduling: Change PID gains based on operating point
- Model Predictive Control (MPC): Optimal control based on model -- see MPC for Humanoid
- Reinforcement Learning: Learn controller from interaction -- see AI for Robot series
Related Articles
- Kalman Filter for Robot: Practical Sensor Fusion -- Combine IMU, encoder, GPS
- Python for Robots: Basics to ROS 2 -- Robot programming with Python
- Writing Hardware Interface for ros2_control -- Connect controller to real motor
- MPC for Humanoid Robot: Theory to Practice -- Next step after PID
- ROS 2 Series Part 4: ros2_control -- Control framework in ROS 2