The PIDController class provides a production-ready PID (Proportional-Integral-Derivative) controller with automatic tuning capabilities, anti-windup protection, and parameter persistence.
Features
Auto-Tuning Ziegler-Nichols Type 1 & 2, Cohen-Coon methods for automatic parameter optimization
Anti-Windup Configurable integral limits prevent windup in saturated conditions
Derivative Filtering Low-pass filter reduces noise in derivative term
EEPROM Persistence Save and load tuned parameters across power cycles
Basic Usage
Initialization
#define ENABLE_MODULE_PID_CONTROLLER
#include "Kinematrix.h"
// Constructor: PIDController(Kp, Ki, Kd, dt, min_output, max_output)
PIDController pid ( 2.0 , 1.0 , 0.5 , 0.1 , 0.0 , 255.0 );
void setup () {
Serial . begin ( 115200 );
// Set target value
pid . setSetPoint ( 60.0 );
// Calculate optimal integral limit automatically
pid . calculateOptimalIntegralLimit ();
}
Basic Control Loop
void loop () {
// Read current value from sensor
float currentTemp = readTemperature ();
// Compute control output (handles timing internally)
float output = pid . compute (currentTemp);
// Apply output to actuator
analogWrite (HEATER_PIN, ( int )output);
// Monitor PID components
Serial . print ( "P: " );
Serial . print ( pid . getProportionalComponent ());
Serial . print ( ", I: " );
Serial . print ( pid . getIntegralComponent ());
Serial . print ( ", D: " );
Serial . println ( pid . getDerivativeComponent ());
}
Auto-Tuning Methods
The PIDController includes three automatic tuning methods to identify optimal PID parameters.
Ziegler-Nichols Method 1 (Step Response)
Best for systems with clear step response characteristics. Applies a step input and analyzes the response curve.
// Auto-tune parameters
const float STEP_AMPLITUDE = 50.0 ;
const unsigned long MAX_TUNING_TIME = 180000 ; // 3 minutes
void startAutoTuneZN1 () {
float currentValue = readSensor ();
if ( pid . autoTuneZN1 (currentValue, STEP_AMPLITUDE, MAX_TUNING_TIME)) {
Serial . println ( "Auto-tuning started..." );
// Keep computing during tuning
while ( pid . isTuning ()) {
float value = readSensor ();
float output = pid . compute (value);
applyOutput (output);
delay ( 100 );
}
Serial . println ( "Tuning complete!" );
Serial . print ( "Kp: " ); Serial . println ( pid . getKp ());
Serial . print ( "Ki: " ); Serial . println ( pid . getKi ());
Serial . print ( "Kd: " ); Serial . println ( pid . getKd ());
// Save to EEPROM
pid . setEEPROMAddress ( 0 );
pid . saveParametersToEEPROM ();
}
}
Ziegler-Nichols Method 2 (Ultimate Gain)
Finds the ultimate gain (Ku) and period (Pu) by increasing Kp until sustained oscillation occurs.
void startAutoTuneZN2 () {
float currentValue = readSensor ();
float initialKp = 1.0 ;
float kpStep = 0.5 ;
if ( pid . autoTuneZN2 (currentValue, initialKp, kpStep, 300000 )) {
Serial . println ( "ZN2 tuning in progress..." );
while ( pid . isTuning ()) {
float value = readSensor ();
float output = pid . compute (value);
applyOutput (output);
delay ( 100 );
}
Serial . println ( "Ultimate Gain Method Complete:" );
Serial . print ( "Ku: " ); Serial . println ( pid . getUltimateGain ());
Serial . print ( "Pu: " ); Serial . println ( pid . getUltimatePeriod ());
Serial . print ( "Tuned Kp: " ); Serial . println ( pid . getKp ());
}
}
Cohen-Coon Method
Ideal for processes with significant dead time (delay between input and response).
void startAutoTuneCohenCoon () {
float currentValue = readSensor ();
float stepAmplitude = 40.0 ;
if ( pid . autoTuneCohenCoon (currentValue, stepAmplitude, 300000 )) {
Serial . println ( "Cohen-Coon tuning started..." );
Serial . println ( "Analyzing step response and dead time..." );
while ( pid . isTuning ()) {
float value = readSensor ();
float output = pid . compute (value);
applyOutput (output);
delay ( 100 );
}
Serial . println ( "Cohen-Coon tuning complete!" );
}
}
Advanced Features
Derivative Filtering
Reduce noise in the derivative term using a low-pass filter:
void setup () {
// Enable derivative filter with alpha = 0.2
// Lower alpha = more filtering (0.0 - 1.0)
pid . enableDerivativeFilter ( 0.2 );
}
// Disable when not needed
void disableFilter () {
pid . disableDerivativeFilter ();
}
Setpoint Ramping
Gradually transition to new setpoints to avoid sudden changes:
void setup () {
// Ramp at 5 units per second
pid . enableSetpointRamping ( 5.0 );
}
void updateSetpoint () {
// Setpoint will ramp smoothly from current to 80.0
pid . setSetPoint ( 80.0 );
// Check current ramped value
float current = pid . getCurrentRampedSetpoint ();
}
Output Rate Limiting
Limit how fast the output can change to protect actuators:
void setup () {
// Limit output change to 50 units per second
pid . setOutputRateLimit ( 50.0 );
}
Deadband
Ignore small errors to reduce oscillation around setpoint:
void setup () {
// Ignore errors smaller than 0.5
pid . setDeadband ( 0.5 );
// Get current deadband
float band = pid . getDeadband ();
}
Reverse Control Direction
For cooling systems where output decreases as input increases:
void setup () {
// true = reverse (cooling), false = direct (heating)
pid . setControllerDirection ( true );
}
Integral Limit Management
void setup () {
// Manual integral limit
pid . setIntegralLimit ( 50.0 );
// Or calculate automatically based on output range
pid . calculateOptimalIntegralLimit ();
// Check current limit
float limit = pid . getIntegralLimit ();
}
EEPROM Persistence
Save and load tuned parameters across power cycles:
void saveParameters () {
pid . setEEPROMAddress ( 0 ); // Starting address
if ( pid . saveParametersToEEPROM ()) {
Serial . println ( "Parameters saved successfully" );
} else {
Serial . println ( "Failed to save parameters" );
}
}
void loadParameters () {
pid . setEEPROMAddress ( 0 );
if ( pid . loadParametersFromEEPROM ()) {
Serial . println ( "Parameters loaded successfully" );
Serial . print ( "Kp: " ); Serial . println ( pid . getKp ());
Serial . print ( "Ki: " ); Serial . println ( pid . getKi ());
Serial . print ( "Kd: " ); Serial . println ( pid . getKd ());
} else {
Serial . println ( "No saved parameters found" );
}
}
Monitor control performance in real-time:
void setup () {
// Set settling threshold (5% of setpoint)
pid . setSettlingThreshold ( 0.05 );
// Reset metrics when changing setpoint
pid . resetPerformanceMetrics ();
}
void checkPerformance () {
// Check if system has settled
if ( pid . isSystemSettled ()) {
float settlingTime = pid . getSettlingTime ();
float overshoot = pid . getOvershoot ();
Serial . print ( "Settling time: " );
Serial . print (settlingTime);
Serial . println ( " seconds" );
Serial . print ( "Overshoot: " );
Serial . print (overshoot);
Serial . println ( "%" );
}
}
Complete Example: Temperature Control
#define ENABLE_MODULE_PID_CONTROLLER
#include "Kinematrix.h"
const int TEMP_SENSOR_PIN = 33 ;
const int HEATER_PIN = 9 ;
const float SETPOINT = 60.0 ;
// Kp, Ki, Kd, dt, min, max
PIDController pid ( 2.0 , 0.1 , 0.5 , 0.1 , 0.0 , 255.0 );
void setup () {
Serial . begin ( 115200 );
pinMode (HEATER_PIN, OUTPUT);
// Configure PID
pid . setSetPoint (SETPOINT);
pid . calculateOptimalIntegralLimit ();
pid . enableDerivativeFilter ( 0.2 );
// Try to load saved parameters
pid . setEEPROMAddress ( 0 );
if ( ! pid . loadParametersFromEEPROM ()) {
Serial . println ( "No saved parameters, using defaults" );
}
Serial . println ( "PID Temperature Controller Ready" );
}
void loop () {
// Read sensor
float temp = readTemperature ();
// Compute output
float output = pid . compute (temp);
// Apply to heater
analogWrite (HEATER_PIN, ( int )output);
// Print status every second
static unsigned long lastPrint = 0 ;
if ( millis () - lastPrint >= 1000 ) {
lastPrint = millis ();
printStatus (temp, output);
}
}
float readTemperature () {
int raw = analogRead (TEMP_SENSOR_PIN);
return (raw * 0.0048828125 * 100.0 ); // LM35 conversion
}
void printStatus ( float temp , float output ) {
Serial . print ( "Temp: " );
Serial . print (temp);
Serial . print ( "°C, Output: " );
Serial . print (output);
Serial . print ( ", Error: " );
Serial . print ( pid . getSetPoint () - temp);
if ( pid . isSystemSettled ()) {
Serial . print ( ", Settled in " );
Serial . print ( pid . getSettlingTime ());
Serial . print ( "s" );
}
Serial . println ();
}
API Reference
Constructor
PIDController ( float kp, float ki, float kd, float dt,
float min_output, float max_output)
Tuning Parameters
Method Description setTunings(kp, ki, kd)Set all PID gains setKp(float p)Set proportional gain setKi(float i)Set integral gain setKd(float d)Set derivative gain getKp()Get proportional gain getKi()Get integral gain getKd()Get derivative gain
Control Operations
Method Description compute(float input)Calculate control output setSetPoint(float sp)Set target value getSetPoint()Get current setpoint reset()Reset controller state
Auto-Tuning
Method Description autoTuneZN1(input, amplitude, timeout)Ziegler-Nichols step response autoTuneZN2(input, initialKp, kpStep, timeout)Ziegler-Nichols ultimate gain autoTuneCohenCoon(input, amplitude, timeout)Cohen-Coon method isTuning()Check if tuning is in progress cancelTuning()Stop auto-tuning getUltimateGain()Get identified ultimate gain getUltimatePeriod()Get identified ultimate period
Advanced Features
Method Description enableDerivativeFilter(alpha)Enable derivative low-pass filter disableDerivativeFilter()Disable derivative filter setDeadband(band)Set error deadband enableSetpointRamping(rate)Enable gradual setpoint changes disableSetpointRamping()Disable setpoint ramping setOutputRateLimit(maxChange)Limit output change rate disableOutputRateLimit()Remove output rate limit setControllerDirection(reverse)Set direct/reverse control setIntegralLimit(limit)Set max integral value calculateOptimalIntegralLimit()Auto-calculate integral limit
Method Description getSettlingTime()Time to reach steady state getOvershoot()Maximum overshoot percentage isSystemSettled()Check if settled setSettlingThreshold(threshold)Set settling criteria resetPerformanceMetrics()Reset metrics tracking
Component Access
Method Description getProportionalComponent()Get P term value getIntegralComponent()Get I term value getDerivativeComponent()Get D term value
EEPROM Operations
Method Description setEEPROMAddress(address)Set storage address saveParametersToEEPROM()Save parameters loadParametersFromEEPROM()Load parameters
The PID controller handles timing internally based on the dt parameter. You don’t need to manage control loop timing manually.
When using auto-tuning, ensure your system is safe to operate with potentially oscillating outputs. Always implement safety limits and monitoring.