Mastering PID Control with ESP32|Build Your Own Powerful Smart Control System
PID Control is one of the most common and practical methods in modern control systems, appearing everywhere from industrial automation to DIY robotics. PID stands for Proportional, Integral, and Derivative. This control approach enables systems to respond in real-time to environmental changes—for example, regulating motor speed, stabilizing temperature, or even helping a robot balance on two wheels.
Using the ESP-IDF development framework, developers can now build intelligent control systems with precise response and stability directly on the ESP32. In this article, we’ll guide you step-by-step on how to design, implement, and tune a PID controller on the ESP32 using C and FreeRTOS, allowing you to build your own smart applications. Whether you’re controlling a fan, motor, or temperature system, PID control gives you a stable and flexible core technology.

Contents
What is a PID Controller?
A PID controller is a feedback control system based on “error.” In simple terms, it calculates the difference (error) between a desired setpoint and the actual output value (measurement) and dynamically adjusts the output to stabilize the system at the target state.
The basic formula for PID control is:
u(t) = Kp * e(t) + Ki * ∫e(t)dt + Kd * de(t)/dt
Where:
- u(t): Controller output (e.g., PWM, DAC control signal)
- e(t): Error between setpoint and actual value (Setpoint – Measurement)
- Kp: Proportional gain – reacts to the current error
- Ki: Integral gain – accumulates past errors to eliminate steady-state error
- Kd: Derivative gain – predicts future error to reduce overshoot and oscillations
Role and Implementation on ESP32
- Create a PID task (using FreeRTOS Task)
- Read actual input values (e.g., temperature, speed)
- Output control signal (PWM for motors, fans, or heaters)
- Control loop timing (precise via Timer or
vTaskDelayUntil()
)
Development Environment
Before starting your programming, make sure to complete the following preparations:
- Install ESP-IDF (version 5.x or higher): ESP-IDF is the official development framework for programming the ESP32, and it supports multiple operating systems such as Windows, macOS, and Linux.
- ESP32 Development Board: An ESP32 board is required.
- Use an SPI interface TFT LCD (e.g., ST7789).
Project Structure
Create a clean ESP-IDF PID control project as follows:
esp32_pid_control/
├── main/
│ ├── main.c # Application entry (PWM/ADC init, PID task launcher)
│ ├── pid_controller.c # PID core algorithm implementation
│ ├── pid_controller.h # PID API header (structs/macros)
│ └── CMakeLists.txt # Main component build rules
│
├── components/ # (Optional) Shared modules
│ └── sensor_drivers/ # Sensor abstraction layer
│ ├── temperature.c # Temp sensor interface
│ ├── temperature.h # Sensor calibration macros
│ └── CMakeLists.txt # Component-specific linking
│
├── sdkconfig # ESP-IDF config (auto-generated)
└── CMakeLists.txt # Top-level project config
To simplify the learning curve, this example consolidates the PID algorithm, ADC reading, and PWM control into a single main.c
file for clarity and ease of demonstration.
PID Task and Control Code
pid_controller.h
typedef struct {
float Kp;
float Ki;
float Kd;
float setpoint;
float integral;
float prev_error;
float output_min;
float output_max;
} PIDController;
void pid_init(PIDController* pid, float Kp, float Ki, float Kd, float min_out, float max_out);
float pid_compute(PIDController* pid, float input, float dt);
pid_controller.c
#include "pid_controller.h"
void pid_init(PIDController* pid, float Kp, float Ki, float Kd, float min_out, float max_out) {
pid->Kp = Kp;
pid->Ki = Ki;
pid->Kd = Kd;
pid->integral = 0;
pid->prev_error = 0;
pid->output_min = min_out;
pid->output_max = max_out;
}
float pid_compute(PIDController* pid, float input, float dt) {
float error = pid->setpoint - input;
pid->integral += error * dt;
float derivative = (error - pid->prev_error) / dt;
float output = pid->Kp * error + pid->Ki * pid->integral + pid->Kd * derivative;
if (output > pid->output_max) output = pid->output_max;
if (output < pid->output_min) output = pid->output_min;
pid->prev_error = error;
return output;
}
Code
main.c
#include "pid_controller.h"
#include "driver/ledc.h" // ESP32 LED PWM controller
#include "driver/adc.h" // ESP32 ADC driver
#include "freertos/FreeRTOS.h" // FreeRTOS core
#include "freertos/task.h" // FreeRTOS task control
/* PWM Configuration */
#define FAN_PWM_CHANNEL LEDC_CHANNEL_0 // Use PWM channel 0
#define FAN_PWM_FREQ 25000 // 25kHz PWM frequency (inaudible for fans)
#define FAN_PWM_RES LEDC_TIMER_10_BIT // 10-bit resolution (0-1023)
#define FAN_GPIO 18 // GPIO pin for fan control
PIDController fan_pid; // PID controller instance
float read_temperature() {
int raw = adc1_get_raw(ADC1_CHANNEL_0); // 12-bit ADC read
// Simplified conversion - replace with actual sensor calibration
return (float)raw * 0.1f; // 0.1°C per LSB
}
void set_fan_speed(float speed_percent) {
// Convert percentage to duty cycle value
int duty = (int)((speed_percent / 100.0f) * ((1 << FAN_PWM_RES) - 1));
ledc_set_duty(LEDC_HIGH_SPEED_MODE, FAN_PWM_CHANNEL, duty);
ledc_update_duty(LEDC_HIGH_SPEED_MODE, FAN_PWM_CHANNEL); // Apply new duty
}
void pid_task(void* arg) {
const TickType_t xInterval = pdMS_TO_TICKS(100); // 100ms control loop
TickType_t xLastWakeTime = xTaskGetTickCount();
// Initialize PID with Kp=2.0, Ki=0.5, Kd=1.0
// Output limits: 0-100% (fan speed range)
pid_init(&fan_pid, 2.0, 0.5, 1.0, 0.0, 100.0);
fan_pid.setpoint = 30.0f; // Target temperature: 30°C
while (1) {
vTaskDelayUntil(&xLastWakeTime, xInterval); // Precise timing
float temp = read_temperature();
// Compute PID output with 0.1s time delta (matches 100ms loop)
float output = pid_compute(&fan_pid, temp, 0.1f);
set_fan_speed(output); // Apply control signal
}
}
void app_main(void) {
/* ADC Configuration */
adc1_config_width(ADC_WIDTH_BIT_12); // 12-bit resolution
adc1_config_channel_atten(ADC1_CHANNEL_0, ADC_ATTEN_DB_11); // 0-3.1V range
/* PWM Timer Setup */
ledc_timer_config_t ledc_timer = {
.speed_mode = LEDC_HIGH_SPEED_MODE,
.timer_num = LEDC_TIMER_0,
.duty_resolution = FAN_PWM_RES, // 10-bit resolution
.freq_hz = FAN_PWM_FREQ, // 25kHz
.clk_cfg = LEDC_AUTO_CLK // Automatic clock source
};
ledc_timer_config(&ledc_timer);
/* PWM Channel Setup */
ledc_channel_config_t ledc_channel = {
.channel = FAN_PWM_CHANNEL,
.duty = 0, // Initial duty cycle (fan off)
.gpio_num = FAN_GPIO,
.speed_mode = LEDC_HIGH_SPEED_MODE,
.hpoint = 0, // Phase offset (not used)
.timer_sel = LEDC_TIMER_0
};
ledc_channel_config(&ledc_channel);
/* Create PID Control Task */
xTaskCreate(pid_task, // Task function
"pid_task", // Task name
4096, // Stack size (bytes)
NULL, // Parameters
5, // Priority (higher = more urgent)
NULL); // Task handle (not used)
}
Explanation
pid_compute()
is the core algorithm, computing the new control output.- Uses
adc1_get_raw()
for a simplified temperature read (can be replaced with actual sensor logic). set_fan_speed()
maps PID output (0–100%) to PWM duty cycle.vTaskDelayUntil()
ensures stable loop intervals, crucial for consistentdt
in PID.
Compile and Flash
After writing the code, you can use the ESP-IDF tools to build, flash, and monitor:
In the VS Code lower-left ESP-IDF toolbar:
- Click Build project
- Click Flash device
- Click Monitor device
When running, you should see output like:
Current Temp: 28.7 °C
Setpoint: 30.0 °C
PID Output: 52.3 % (Fan speed)
This indicates:
- The sensor continuously reports the current temperature
- The PID controller calculates control output based on the setpoint and measurement
- The output (e.g., fan speed) adjusts automatically to reach the target temperature
As the temperature approaches the setpoint, the output slows down, achieving a smooth control response—this is the real-world impact of a PID controller!
Conclusion
Through this implementation, we built a complete PID controller and successfully integrated it with ESP32 hardware features (PWM, ADC, FreeRTOS) to drive a controllable output system. Whether for temperature or speed control—or even integrating more complex sensing and networking modules in the future—this architecture provides a solid foundation for your IoT or embedded applications.
While PID is a classic algorithm, when combined with the flexible resources of a modern MCU, it enables powerful and practical solutions.