227  PID Control Simulation Lab

227.1 Learning Objectives

By the end of this chapter, you will be able to:

  • Simulate PID Controllers: Build Python simulations to experiment with control systems
  • Tune P, I, D Gains: Understand how each parameter affects system response
  • Analyze Control Performance: Measure overshoot, settling time, and steady-state error
  • Apply to IoT Systems: Design temperature, motor, and position control for smart devices
  • Handle Disturbances: Design controllers robust to external environmental changes
  • Validate Control Designs: Use simulation to test before hardware implementation

227.2 Prerequisites

Required Chapters: - Processes and Systems - Process control basics - Sensor Fundamentals - Sensors - Actuators - Actuators

Technical Background: - Control loop concepts - PID controllers - System response characteristics

Control System Elements:

Element Function Example
Sensor Measurement Temperature probe
Controller Decision PID algorithm
Actuator Action Valve, motor
Process System HVAC, tank

Lab Requirements: - Arduino/ESP32 board - Temperature sensor - LED or motor for actuation

Estimated Time: 1.5 hours

NoteCross-Hub Connections

This labs chapter connects to multiple learning resources:

Interactive Tools: - Simulations Hub - PID controller simulators and interactive control system tools - Try the online PID tuner before hardware implementation

Concept Reinforcement: - Quizzes Hub - Test control system understanding with targeted quizzes - Knowledge Gaps Hub - Address common PID misconceptions

Video Tutorials: - Videos Hub - Watch PID tuning demonstrations and real-world examples - Visual explanations of P, I, and D effects on system response

Knowledge Map: - Knowledge Map - See how control systems connect to networking, sensing, and data management

What is this chapter? Practical labs and review for IoT processes and system integration.

When to use: - After studying IoT architecture processes - When implementing end-to-end systems - For hands-on experience

Process Types:

Process Description
Data Collection Sensor to gateway flow
Data Processing Edge and cloud analytics
Control Actuator commands
Management Device provisioning

Lab Focus: - Process flow implementation - Integration patterns - Debugging techniques - Performance optimization

Recommended Path: 1. Review architecture processes fundamentals 2. Work through labs sequentially 3. Complete review questions

227.3 Hands-On Lab: PID Control Simulation

In this lab, you’ll experiment with a simulated PID controller to understand how each parameter affects system behavior.

Flowchart diagram

Flowchart diagram
Figure 227.1: Complete IoT Process Flow showing four layers: Data Acquisition (temperature, humidity, pressure sensors generating analog signals), Processing Layer (ADC conversion, signal filtering, PID controller calculating control signal), Control Action Layer (PWM generation driving heater and fan), and Feedback Loop (measuring output and comparing to setpoint, feeding error back to PID controller in closed loop)

%% fig-alt: "Comparison diagram showing the effects of different PID parameter tuning: high P causes fast response with oscillation, high I eliminates steady-state error but may overshoot, high D provides damping but is noise-sensitive"
%%{init: {'theme': 'base', 'themeVariables': {'primaryColor': '#2C3E50', 'primaryTextColor': '#fff', 'primaryBorderColor': '#16A085', 'lineColor': '#16A085', 'secondaryColor': '#E67E22', 'tertiaryColor': '#7F8C8D', 'fontSize': '11px'}}}%%
graph TB
    subgraph P_TERM["P (Proportional)"]
        P_HIGH["High Kp<br/>━━━━━━━━━<br/>Fast response<br/>May oscillate<br/>Residual error"]
        P_LOW["Low Kp<br/>━━━━━━━━━<br/>Slow response<br/>Stable<br/>Large error"]
    end

    subgraph I_TERM["I (Integral)"]
        I_HIGH["High Ki<br/>━━━━━━━━━<br/>Eliminates error<br/>May overshoot<br/>Slow recovery"]
        I_LOW["Low Ki<br/>━━━━━━━━━<br/>Steady-state error<br/>Stable<br/>Fast settling"]
    end

    subgraph D_TERM["D (Derivative)"]
        D_HIGH["High Kd<br/>━━━━━━━━━<br/>Predicts change<br/>Noise sensitive<br/>Smooth approach"]
        D_LOW["Low Kd<br/>━━━━━━━━━<br/>Simple control<br/>May overshoot<br/>Fast but bouncy"]
    end

    START([System<br/>Response])
    START --> P_TERM
    START --> I_TERM
    START --> D_TERM

    style P_HIGH fill:#E67E22,stroke:#2C3E50,color:#fff
    style I_HIGH fill:#16A085,stroke:#2C3E50,color:#fff
    style D_HIGH fill:#2C3E50,stroke:#16A085,color:#fff
    style P_LOW fill:#7F8C8D,stroke:#2C3E50,color:#fff
    style I_LOW fill:#7F8C8D,stroke:#2C3E50,color:#fff
    style D_LOW fill:#7F8C8D,stroke:#2C3E50,color:#fff

This comparison shows how each PID term affects system behavior. P provides immediate response, I eliminates steady-state error over time, and D predicts and dampens changes. Proper tuning balances these three effects for optimal control.

%%{init: {'theme': 'base', 'themeVariables': { 'primaryColor': '#2C3E50', 'primaryTextColor': '#fff', 'primaryBorderColor': '#16A085', 'lineColor': '#16A085', 'secondaryColor': '#E67E22', 'tertiaryColor': '#7F8C8D'}}}%%
sequenceDiagram
    participant SP as Setpoint<br/>(25°C Target)
    participant PID as PID Controller
    participant ACT as Actuator<br/>(Heater/Fan)
    participant ENV as Environment
    participant SEN as Sensor

    Note over SP,SEN: Cycle 1: Large Error

    SP->>PID: Target = 25°C
    SEN->>PID: Current = 18°C
    PID->>PID: Error = 7°C<br/>P=14, I=0.7, D=2.1<br/>Output = 16.8
    PID->>ACT: High power (84%)
    ACT->>ENV: Heat applied
    ENV->>SEN: Temp rising

    Note over SP,SEN: Cycle N: Approaching Target

    SEN->>PID: Current = 24°C
    PID->>PID: Error = 1°C<br/>P=2, I=2.5, D=-1.5<br/>Output = 3.0
    PID->>ACT: Low power (15%)
    Note over ACT,ENV: D-term slows approach<br/>to prevent overshoot

    Note over SP,SEN: Steady State

    SEN->>PID: Current = 25°C
    PID->>PID: Error ≈ 0<br/>I-term maintains output
    PID->>ACT: Maintain (12%)

Figure 227.2: Alternative view: Temporal sequence showing PID behavior across control cycles. Initial large error drives strong P-term response. As temperature approaches setpoint, D-term applies “braking” to prevent overshoot. At steady state, I-term accumulation maintains output to compensate for heat loss. This dynamic view illustrates how P, I, and D contribute at different phases.

Complete IoT Process Flow: From Data Acquisition to Control Action

Stage Component Function Output
Data Acquisition Temperature Sensor Measure ambient temperature Analog signal
Humidity Sensor Measure moisture level Analog signal
Pressure Sensor Measure atmospheric pressure Analog signal
Processing Layer ADC Conversion Convert analog to digital Digital values
Signal Filtering Remove noise, smooth data Clean measurements
PID Controller Calculate control output Control signal
Control Action PWM Generation Create pulse-width signal Duty cycle
Heater Heat the environment Temperature change
Fan Cool/ventilate Airflow
Feedback Loop Measure Output Read current state Measured value
Compare to Setpoint Calculate error Error signal → PID

Process Flow: Sensors → ADC → Filter → PID Controller → PWM → Actuators → Measure → Compare → (back to PID)

WarningCommon Misconception: “Higher Gains Always Mean Better Performance”

The Myth: Many engineers believe that increasing PID gains (especially Kp) will always improve system response and accuracy.

The Reality: A 2018 industrial IoT deployment at a chemical processing plant learned this lesson the hard way. Engineers increased Kp from 2.0 to 8.0 hoping to reduce temperature settling time from 60s to 20s.

What Actually Happened: - Before (Kp=2.0): Settling time 60s, overshoot 2%, oscillation period ~10s (damped in 3 cycles) - After (Kp=8.0): System became unstable with continuous oscillation ±5°C - Production Impact: 12 batches ($180,000 value) rejected due to temperature excursions - Root Cause: Aggressive Kp exceeded stability margin, causing sustained oscillations

The Fix: Ziegler-Nichols tuning identified critical gain Kp_crit = 4.5 (oscillation threshold). Final tuning used Kp = 0.6 × 4.5 = 2.7, Ki = 0.3, Kd = 0.8.

Results: Settling time 35s (vs. 60s original, 42% improvement), zero overshoot, stable operation.

Lesson: There’s an optimal gain range. Below it, response is sluggish. Above it, system becomes unstable. The sweet spot requires systematic tuning, not guessing higher numbers. In control systems, stability always trumps speed.

227.3.1 Lab Objective

Tune P, I, and D gains to achieve optimal control of a simulated temperature system, observing the effects of each parameter.

227.3.2 Simulated System

Consider a smart thermostat controlling room temperature: - Process: Room heating/cooling - Set Point: 22°C - Initial Temperature: 18°C - Disturbance: External temperature changes

227.3.3 Python PID Simulator

Mermaid diagram

Mermaid diagram
Figure 227.3: PID Control Loop State Machine showing control flow from initialization through continuous measurement, error calculation, P/I/D term computation, output limiting, actuator control, and feedback loop with anti-windup protection

PID Control Loop State Machine and Operational Flow

State Action Formula/Notes Next State
Initialize System Startup Set Kp, Ki, Kd, Setpoint Measure
Measure Read Sensor Temperature, Position, Speed Calculate Error
Calculate Error Compute error error = setpoint - measured Compute P
Compute P Proportional term P = Kp × error (fast response) Compute I
Compute I Integral term I = Ki × ∫error·dt (eliminates steady-state) Compute D
Compute D Derivative term D = Kd × (Δerror/Δt) (reduces overshoot) Sum Output
Sum Output Combine terms output = P + I + D Limit Output
Limit Output Clamp value Constrain to [min, max] Apply Control
Apply Control Update Actuator PWM, Valve, Motor Measure (loop)
Check Setpoint New setpoint? If changed → Reset Integral Calculate Error
Shutdown Exit command Stop control loop End

Anti-Windup: Integral term is reset when setpoint changes significantly to prevent overshoot from accumulated error.

227.3.4 Lab Tasks

NoteTask 1: P-Only Control

Set Kp=2.0, Ki=0.0, Kd=0.0 and run the simulation.

Observe: - How quickly does temperature rise initially? - Does the system reach exactly 22°C? - What happens at t=50s when the disturbance occurs? - Is there steady-state error?

Expected Results: - Fast initial response - Settles with offset (steady-state error ~0.5-1°C) - Disturbance causes permanent offset increase - Some oscillation possible

NoteTask 2: PI Control

Set Kp=2.0, Ki=0.5, Kd=0.0 and run the simulation.

Observe: - Does the system now reach exactly 22°C? - How does the response compare to P-only? - What happens to the disturbance-induced offset? - Is there any overshoot?

Expected Results: - Eliminates steady-state error - Reaches exactly 22°C eventually - Recovers from disturbance automatically - Possible overshoot and longer settling time

NoteTask 3: Full PID Control

Set Kp=2.0, Ki=0.5, Kd=1.0 and run the simulation.

Observe: - How does overshoot compare to PI? - Is settling time improved? - How does the system respond to the disturbance? - Look at the D term plot - when is it most active?

Expected Results: - Minimal overshoot - Faster settling time - Quick disturbance rejection - D term most active during rapid changes

NoteTask 4: Parameter Tuning Exploration

Experiment with different gain values:

Test these scenarios:

  1. Aggressive P: Kp=5.0, Ki=0.5, Kd=1.0
    • What happens?
  2. Too Much I: Kp=2.0, Ki=2.0, Kd=0.0
    • Does it overshoot significantly?
  3. Excessive D: Kp=2.0, Ki=0.5, Kd=5.0
    • Does response become sluggish?
  4. Balanced Tuning: Find optimal values for:
    • Minimal overshoot (<0.5°C)
    • Fast settling (<30s)
    • Zero steady-state error

Flowchart diagram

Flowchart diagram
Figure 227.4: PID Tuning Lab Workflow showing progressive experimentation from P-only control through PI and full PID, with exploration of parameter variations and final optimization before hardware implementation

PID Tuning Lab Workflow and Experimental Process

Task Parameters Expected Observations Next Step
Setup System parameters Configure simulation Task 1
Task 1: P-Only Kp=2.0, Ki=0, Kd=0 Error ~1°C, fast initial response, possible oscillation Task 2
Task 2: PI Control Kp=2.0, Ki=0.5, Kd=0 Zero steady-state error, some overshoot, longer settling Task 3
Task 3: Full PID Kp=2.0, Ki=0.5, Kd=1.0 Minimal overshoot, fast settling, zero SS error Task 4
Task 4: Exploration Various test cases Compare different configurations Optimize

Exploration Tests:

Test Parameters What to Observe
Aggressive P Kp=5.0, Ki=0.5, Kd=1.0 Increased oscillation, faster response
Excessive I Kp=2.0, Ki=2.0, Kd=0 Significant overshoot, slow settling
High D Kp=2.0, Ki=0.5, Kd=5.0 Sluggish response, noise sensitivity

Performance Metrics to Measure: 1. Rise Time - Time to reach 90% of setpoint 2. Settling Time - Time to stay within ±2% of setpoint 3. Overshoot % - Maximum deviation above setpoint 4. Steady-State Error - Final offset from setpoint

Final Step: Hardware Implementation on ESP32 → Validate on Real System → Lab Complete

227.3.5 Arduino PID Implementation

For real hardware implementation with ESP32:

// ESP32 PID Temperature Controller
#include <Arduino.h>

class PIDController {
private:
    float kp, ki, kd;
    float setpoint;
    float integral;
    float previous_error;
    unsigned long last_time;

public:
    PIDController(float Kp, float Ki, float Kd, float sp)
        : kp(Kp), ki(Ki), kd(Kd), setpoint(sp),
          integral(0), previous_error(0), last_time(0) {}

    float update(float measured_value) {
        unsigned long current_time = millis();
        float dt = (current_time - last_time) / 1000.0; // Convert to seconds

        if (last_time == 0) dt = 0; // First call

        // Calculate error
        float error = setpoint - measured_value;

        // Proportional
        float P = kp * error;

        // Integral (with anti-windup)
        integral += error * dt;
        integral = constrain(integral, -100, 100); // Limit integral
        float I = ki * integral;

        // Derivative
        float derivative = (error - previous_error) / dt;
        float D = kd * derivative;

        // Update state
        previous_error = error;
        last_time = current_time;

        // Calculate output
        return P + I + D;
    }

    void setSetpoint(float sp) {
        setpoint = sp;
    }

    void reset() {
        integral = 0;
        previous_error = 0;
        last_time = 0;
    }
};

// Pin definitions
#define TEMP_SENSOR_PIN 34  // ADC pin for temperature sensor
#define HEATER_PWM_PIN 25   // PWM output for heater control

// PID parameters
const float KP = 2.0;
const float KI = 0.5;
const float KD = 1.0;
const float SETPOINT = 22.0; // Target temperature in °C

PIDController pid(KP, KI, KD, SETPOINT);

// PWM configuration
const int pwmFreq = 5000;
const int pwmChannel = 0;
const int pwmResolution = 8; // 8-bit: 0-255

void setup() {
    Serial.begin(115200);

    // Configure PWM for heater control
    ledcSetup(pwmChannel, pwmFreq, pwmResolution);
    ledcAttachPin(HEATER_PWM_PIN, pwmChannel);

    Serial.println("ESP32 PID Temperature Controller");
    Serial.println("Time(s),Setpoint,Temperature,Output,P,I,D");
}

float readTemperature() {
    // Read analog value from temperature sensor
    int adcValue = analogRead(TEMP_SENSOR_PIN);

    // Convert ADC to temperature (example for TMP36)
    // TMP36: 10mV/°C, 500mV offset at 0°C
    float voltage = adcValue * (3.3 / 4095.0); // ESP32 12-bit ADC
    float temperature = (voltage - 0.5) * 100.0;

    return temperature;
}

void loop() {
    // Read current temperature
    float current_temp = readTemperature();

    // Calculate PID output
    float pid_output = pid.update(current_temp);

    // Convert to PWM duty cycle (0-255)
    int pwm_value = constrain((int)pid_output, 0, 255);

    // Apply to heater
    ledcWrite(pwmChannel, pwm_value);

    // Log data
    Serial.print(millis() / 1000.0);
    Serial.print(",");
    Serial.print(SETPOINT);
    Serial.print(",");
    Serial.print(current_temp);
    Serial.print(",");
    Serial.println(pwm_value);

    delay(100); // Update every 100ms
}

227.4 Summary

This lab provided hands-on experience with PID control simulation and implementation:

Key Accomplishments: 1. P-Only Control: Demonstrated fast response but persistent steady-state error 2. PI Control: Showed how integral action eliminates steady-state error 3. PID Control: Achieved optimal response with minimal overshoot 4. Parameter Exploration: Learned the effects of aggressive tuning

Performance Metrics Learned: - Rise time, settling time, overshoot percentage, steady-state error

Hardware Implementation: - Complete ESP32 PID controller code ready for deployment - Anti-windup protection for real-world robustness

Next Steps: - Understanding Checks - Test your understanding with real-world scenarios - Decision Guidance - Apply decision frameworks for control system design

Prerequisites: - Processes and Systems - Control theory fundamentals - Sensor Fundamentals - Measurement principles - Actuators - Control action mechanisms

Continue Learning: - Understanding Checks - Scenario-based learning - Decision Guidance - Practical decision frameworks

227.5 What’s Next?

Now that you’ve gained hands-on experience with PID simulation, continue to the understanding checks to test your knowledge with real-world scenarios.

Continue to Understanding Checks →