Automatic Fan Speed Control - shalan/CSCE4301-WiKi GitHub Wiki
Traditional laptop and computer cooling systems often operate with simple on/off control or fixed speed profiles that do not adapt efficiently to varying thermal loads. This results in:
- Inadequate cooling during high thermal loads
- Unnecessary noise when running at full speed in low-load scenarios
- Wasted energy from inefficient operation
- Component wear from constant high-speed operation
We propose an intelligent embedded temperature control system that continuously adjusts fan speed based on real-time temperature feedback using PWM (Pulse Width Modulation) and PID (Proportional-Integral-Derivative) control algorithms. This closed-loop system provides:
- Precise temperature regulation at a configurable setpoint
- Reduced acoustic noise through variable speed control
- Improved energy efficiency by running the fan only as fast as needed
- Extended component life through reduced wear
- Real-time monitoring and data logging for analysis and optimization
The system must satisfy the following functional requirements:
-
Temperature Sensing: Accurately measure ambient/system temperature using the DS18B20 digital temperature sensor with Β±0.5Β°C accuracy and 0.0625Β°C resolution
-
PID Control: Implement a closed-loop PID controller with:
- Configurable proportional, integral, and derivative gains
- Anti-windup protection to prevent integral accumulation
- Smooth response to setpoint changes
-
PWM Fan Control: Generate a variable PWM signal at 25kHz frequency to control standard 4-pin PWM fans with duty cycle range of 0-100%
-
RPM Feedback: Read the fan tachometer signal to monitor actual fan speed in real-time and detect fan stall conditions
-
User Interface: Provide UART-based command interface for:
- Starting/stopping the system
- Adjusting temperature setpoint (18-35Β°C range)
- Switching between automatic PID and manual fan control modes
- Setting manual fan speed percentage
-
Data Logging: Output real-time telemetry in JSON format including:
- Current temperature reading
- Target setpoint temperature
- Fan speed percentage
- Actual fan RPM
- Individual PID term values (P, I, D)
- System state (running/stopped, auto/manual)
-
Safety Features:
- Sensor fault detection with automatic failsafe mode (50% fan speed)
- Integral term clamping to prevent windup
- Output saturation limiting (0-100%)
-
Configurable Parameters: Allow runtime adjustment of:
- Temperature setpoint
- Operating mode (auto/manual)
- Manual fan speed
- System enable/disable
This section details the hardware and software architecture of the temperature control system.
The complete hardware architecture is shown in the block diagram below:

| Component | Part Number | Description | Justification |
|---|---|---|---|
| Microcontroller | STM32L432KC | 32-bit ARM Cortex-M4, 80MHz, low-power | Provides sufficient processing power, built-in timers for PWM, and extensive GPIO for sensor interfacing |
| Temperature Sensor | DS18B20 | Digital 1-Wire temperature sensor | Β±0.5Β°C accuracy, 0.0625Β°C resolution, simple 1-wire interface requiring only one GPIO pin |
| Fan | 4-Pin PWM PC Fan | Standard computer cooling fan | Industry-standard 25kHz PWM control, built-in tachometer for speed feedback |
| Pull-up Resistor | 4.7kΞ© | For DS18B20 data line | Required by 1-Wire protocol to pull bus high when idle |
| External Power | 12V DC | Fan power supply | Standard voltage for PC fans |
| Function | STM32 Pin | Arduino Pin | Notes |
|---|---|---|---|
| DS18B20 Data | PA11 | D10 | GPIO with open-drain output for 1-Wire |
| Fan PWM Output | PA9 (TIM1_CH2) | D1 | Hardware PWM at 25kHz |
| Fan Tachometer | PB3 | A4 | External interrupt on rising edge |
| UART TX | PA2 | D1 | Connected to ST-Link USB |
| UART RX | PA3 | D0 | Connected to ST-Link USB |
| DS18B20 VCC | 3.3V | 3.3V | Power supply |
| DS18B20 GND | GND | GND | Ground |
DS18B20 Wiring (TO-92 Package):
βββββββββ
β βββ β
βββββ¬β¬β¬ββ
βββ
1 2 3
β β β
GNDβVCC
Data
β
4.7kΞ© to VCC
| DS18B20 Pin | Connection | STM32 Pin |
|---|---|---|
| 1 (GND) | Ground | GND |
| 2 (Data) | Data + 4.7kΞ© pull-up to VCC | PA11 |
| 3 (VCC) | Power | 3.3V |
4-Pin Fan Wiring:
| Fan Wire | Color | Connection |
|---|---|---|
| GND | Black | External PSU Ground |
| +12V | Yellow | External PSU +12V |
| Tach | Green | PB3 (STM32) |
| PWM | Blue | PA9 (TIM1_CH2) |
Why PA11 for DS18B20 Data?
- General-purpose I/O pin with full GPIO capabilities
- Supports open-drain output mode required for 1-Wire bidirectional communication
- Available on Arduino-compatible header for easy breadboard access
- No conflicts with USART2 or other critical peripherals
Why 4.7kΞ© Pull-up Resistor? The DS18B20 uses the 1-Wire protocol with open-drain communication where:
- Both master (STM32) and slave (DS18B20) can only pull the line LOW or release to high-impedance
- An external pull-up resistor is required to pull the line HIGH when both devices release it
-
4.7kΞ© is optimal because:
- Smaller values (1kΞ©) waste power and may prevent proper LOW signals
- Larger values (47kΞ©) cause slow rise times and timing errors
- 4.7kΞ© balances speed and power per the DS18B20 datasheet recommendation
Why USART2?
- Pre-configured on NUCLEO board and connected to ST-Link USB interface
- Provides virtual COM port for PC communication without external USB-to-serial adapter
- Pins PA2 (TX) and PA3 (RX) are dedicated to this function
- Enables real-time monitoring and debugging over USB
Why TIM1 Channel 2 for PWM?
- Hardware timer provides accurate 25kHz PWM frequency required by 4-pin fans
- Frees CPU from software timing responsibilities
- Provides jitter-free PWM signal
- Channel 2 mapped to PA9 which is available on Arduino header
The software is organized into several functional modules:
βββββββββββββββββββββββββββββββββββββββββββββββββββββββ
β Main Control Loop (2s cycle) β
β ββββββββββββ ββββββββββββ βββββββββββββββββββββ β
β β Command β β Temp β β Fan Control β β
β βProcessingββ β Reading ββ β (PID/Manual) β β
β ββββββββββββ ββββββββββββ βββββββββββββββββββββ β
β β β β β
β β β β β
β ββββββββββββ ββββββββββββ βββββββββββββββββββββ β
β β UART β β DS18B20 β β PWM + Tach RPM β β
β β RX (ISR) β β Driver β β Monitoring β β
β ββββββββββββ ββββββββββββ βββββββββββββββββββββ β
βββββββββββββββββββββββββββββββββββββββββββββββββββββββ
System Clock: 80 MHz derived from:
- MSI: 4 MHz (default system oscillator)
- PLL Configuration:
- Source: MSI
- PLLM: Γ·1 (no pre-division)
- PLLN: Γ40 (multiply by 40)
- PLLR: Γ·2 (divide by 2)
- Result: 4 MHz Γ 40 Γ· 2 = 80 MHz
- All bus clocks (AHB, APB1, APB2): 80 MHz (no division)
GPIO Configuration (PA11 - DS18B20 Data):
| Parameter | Setting | Justification |
|---|---|---|
| Mode | GPIO Output | Dynamically switched between output and input for 1-Wire |
| Output Type | Open Drain | Required for bidirectional 1-Wire communication |
| Pull-up/Pull-down | No Pull | External 4.7kΞ© resistor provides pull-up |
| Speed | High | Ensures fast transitions for timing-critical 1-Wire protocol |
TIM1 Configuration (PWM Generation):
| Parameter | Value | Calculation |
|---|---|---|
| Prescaler | 0 | No prescaling |
| Counter Mode | Up | Standard counting mode |
| Period (ARR) | 3199 | Sets PWM frequency |
| PWM Frequency | 25 kHz | 80 MHz Γ· (0+1) Γ· (3199+1) = 25 kHz |
| Channel 2 Mode | PWM Mode 1 | Active when counter < CCR2 |
| Polarity | High | Standard polarity for PC fans |
USART2 Configuration:
| Parameter | Setting | Notes |
|---|---|---|
| Baud Rate | 115200 | Standard high-speed rate for terminal |
| Word Length | 8 bits | Standard data frame |
| Parity | None | Error detection not critical |
| Stop Bits | 1 | Standard configuration |
| Flow Control | None | Simple point-to-point communication |
| Mode | Asynchronous | Standard UART |
External Interrupt (EXTI3 - Fan Tachometer):
| Parameter | Setting | Notes |
|---|---|---|
| GPIO | PB3 | Fan tachometer input |
| Mode | External Interrupt | Rising edge trigger |
| Pull | Pull-up | Ensures clean signal |
| Priority | 0 | High priority for accurate pulse counting |
1. DS18B20 Temperature Sensor Driver
Implements the 1-Wire protocol in software for communication with the DS18B20:
- Dynamic GPIO Mode Switching: Reconfigures PA11 between output (for writing) and input (for reading)
- Microsecond Delay: Calibrated busy-wait loop for precise timing (1-480 Β΅s)
-
1-Wire Protocol Primitives:
- Initialization/Presence detection
- Bit-level read/write operations
- Byte-level read/write operations
- Temperature Conversion: Reads 16-bit raw value and converts to Celsius (Γ·16)
2. PID Controller
Implements discrete PID algorithm with anti-windup:
Error = Measured_Temp - Setpoint
P_term = Kp Γ Error
D_term = Kd Γ (Error - Prev_Error) / dt
I_term = Ki Γ Integral
Output = clamp(P_term + I_term + D_term, 0, 100)
Anti-windup Strategy:
- Only integrates error when output is not saturated
- If saturated high, only integrates when error is negative (helps unsaturate)
- If saturated low, only integrates when error is positive (helps unsaturate)
- Clamps integral term to Β±300 to prevent excessive accumulation
PID Parameters (Tuned experimentally):
- Kp = 20.0: Proportional gain for fast response to errors
- Ki = 0.3: Integral gain for eliminating steady-state error
- Kd = 0.3: Derivative gain for damping oscillations
- Setpoint = 28.0Β°C: Default target temperature
3. PWM Fan Control
- Hardware PWM via TIM1 Channel 2
- Frequency: 25 kHz (standard for 4-pin PC fans)
- Duty cycle: 0-100% (0 = off, 100 = full speed)
- Minimum speed enforcement: Ensures fan starts reliably
4. Tachometer RPM Measurement
Interrupt-driven pulse counting with time-windowed calculation:
Pulses_per_revolution = 2 (typical 4-pin fan)
RPM = (Pulse_count Γ 60000) / (Pulses_per_rev Γ Time_ms)
Features:
- 1-second averaging windows for stable readings
- Timeout detection (returns 0 RPM if no pulse for 2 seconds)
- Handles fan stopped and low-speed conditions
5. UART Command Interface
Interrupt-based, non-blocking command processing:
| Command | Function | Example |
|---|---|---|
S |
Start system in auto mode | S |
X |
Stop system (fan off) | X |
A |
Switch to automatic PID mode | A |
T<value> |
Set temperature setpoint | T26.5 |
M<value> |
Manual fan speed (0-100%) | M75 |
6. Data Logging
Real-time JSON telemetry output every 2 seconds:
{
"temperature": 28.25,
"setpoint": 28.0,
"fanSpeed": 45,
"rpm": 1850,
"pTerm": 5.0,
"iTerm": 38.5,
"dTerm": 0.15,
"running": 1,
"manual": 0
}This enables:
- Real-time monitoring and visualization
- PID tuning analysis
- Performance logging for optimization
- Integration with Python dashboard (dashboard_cyberpunk.py)
This section documents how the project was built, including key challenges encountered and the solutions implemented.
GitHub Repository: Embedding-Fanning-System
- IDE: Keil MDK-ARM (Β΅Vision)
- Configuration Tool: STM32CubeMX
- Debugger: ST-Link (integrated on NUCLEO board)
- Language: C (HAL library)
- Version Control: Git/GitHub
The complete system implementation is contained in main.c, organized into the following functional sections:
- DS18B20 Temperature Sensor Driver (Lines 123-223)
- Fan Control Functions (Lines 225-287)
- PID Controller (Lines 289-368)
- UART Command Handler (Lines 370-460)
- Main Control Loop (Lines 462-550)
Problem: The DS18B20 requires precise microsecond-level timing (1-480 Β΅s) for the 1-Wire protocol. The STM32 HAL library only provides HAL_Delay() which has millisecond resolution.
Attempted Solutions:
- Hardware timer-based delays (too complex, adds overhead)
- DWT (Data Watchpoint and Trace) cycle counter (initialization issues on L432KC)
Final Solution: Implemented a calibrated busy-wait loop using CPU cycles:
void delay_us(uint32_t us) {
us *= (SystemCoreClock / 1000000) / 5;
while(us--);
}Rationale:
- Self-calibrating based on
SystemCoreClock(portable across different clock speeds) - Division by 5 accounts for loop overhead (~5 CPU cycles per iteration)
- At 80 MHz: 80 cycles = 1 microsecond
- Simple implementation with no external dependencies
- Sufficient accuracy for 1-Wire protocol tolerance margins
Testing: Verified timing using logic analyzer showed Β±5% accuracy, well within DS18B20 specifications.
Problem: When the fan is stopped, the integral term continues to accumulate error, leading to:
- Large overshoot when system restarts
- Aggressive initial fan speed
- Extended settling time
- Unstable temperature control
Example:
Temperature = 30Β°C, Setpoint = 28Β°C, System stopped
Error = 2Β°C accumulated for 60 seconds
Integral = 2 Γ 60 = 120
When system starts: Huge integral term drives fan to 100% immediately
Solution: Implemented conditional integration (anti-windup) that only accumulates the integral when it can actually help:
// Calculate tentative output before integration
float i_before = PID_KI * pid_integral;
float out_raw = p + i_before + d;
// Integrate only when it helps (anti-windup)
if ((out_raw > PID_MIN_OUTPUT && out_raw < PID_MAX_OUTPUT) ||
(out_raw >= PID_MAX_OUTPUT && error < 0.0f) ||
(out_raw <= PID_MIN_OUTPUT && error > 0.0f))
{
pid_integral += error * dt;
pid_integral = clampf(pid_integral, -PID_INTEGRAL_MAX, PID_INTEGRAL_MAX);
}Logic:
- Normal operation (output not saturated): Always integrate
- Saturated HIGH (output β₯ 100%): Only integrate if error is negative (helps reduce output)
- Saturated LOW (output β€ 0%): Only integrate if error is positive (helps increase output)
- Hard limit: Clamp integral to Β±300 to prevent excessive accumulation
Additional Technique:
- Preserve the integral term (don't reset it)
- Only reset
pid_last_timeto prevent dt calculation errors - Allows smooth restart with control history intact
Results: Reduced overshoot from ~3Β°C to <0.5Β°C on system restart.
Problem: Fan tachometer provides 2 pulses per revolution. Measuring RPM accurately requires:
- Counting pulses over time
- Handling variable fan speeds (0-3000 RPM)
- Detecting when fan is stopped
- Avoiding division by zero
Naive Approach (failed):
// Calculate RPM on every call - causes jitter and noise
uint16_t rpm = (pulse_count * 60) / (PPR * dt_seconds);Issues:
- High jitter in readings due to variable pulse intervals
- Division errors at low speeds
- No timeout detection for stopped fan
Solution: Implemented time-window based RPM calculation with timeout detection:
uint16_t Fan_GetRPM(void) {
static uint32_t last_count = 0;
static uint32_t last_time_ms = 0;
static uint16_t last_rpm = 0;
uint32_t now = HAL_GetTick();
// Timeout detection - if no pulse in 2 seconds, fan is stopped
if ((uint32_t)(now - tach_last_time) > 2000U) {
last_rpm = 0;
return 0;
}
// Calculate RPM over 1-second windows
uint32_t dt_ms = (uint32_t)(now - last_time_ms);
if (dt_ms >= 1000U) {
uint32_t pulse_diff = tach_pulse_count - last_count;
uint32_t rpm = (pulse_diff * 60000U) / (PPR * dt_ms);
// Update for next window
last_rpm = (uint16_t)rpm;
last_count = tach_pulse_count;
last_time_ms = now;
}
return last_rpm; // Return cached value until next update
}Key Features:
- 1-second averaging windows: Smooths out pulse timing variations
- Timeout detection: Returns 0 RPM if no pulse received for 2 seconds (fan stopped)
- Cached value: Returns last calculated RPM between updates (reduces jitter)
- Overflow safe: Uses unsigned 32-bit arithmetic to prevent overflow
- PPR (Pulses Per Revolution): Configurable constant (2 for standard PC fans)
Calculation:
RPM = (Pulses Γ 60,000 ms/min) / (PPR Γ Time_ms)
Example: 30 pulses in 1000 ms with PPR=2
RPM = (30 Γ 60,000) / (2 Γ 1000) = 900 RPM
Results: Stable RPM readings with <1% jitter, reliable zero detection.
Problem: Reading commands from UART in the main loop using blocking calls would freeze temperature control:
// BLOCKING - BAD!
HAL_UART_Receive(&huart2, buffer, 1, HAL_MAX_DELAY);
// System frozen until character receivedThis prevents:
- Continuous temperature monitoring
- Real-time fan control
- Responsive PID updates
Solution: Implemented interrupt-based line buffering with complete command detection:
// Global buffers
static uint8_t uart_rx_byte = 0;
static volatile uint8_t uart_line_ready = 0;
static volatile uint8_t uart_rx_idx = 0;
static char uart_line[32];
// Interrupt callback (runs on each received character)
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) {
char c = (char)uart_rx_byte;
if (c == '\r' || c == '\n') {
// End of line detected
if (uart_rx_idx > 0) {
uart_line[uart_rx_idx] = '\0'; // Null-terminate
uart_line_ready = 1; // Signal main loop
}
uart_rx_idx = 0;
} else if (uart_rx_idx < (sizeof(uart_line) - 1)) {
// Accumulate characters
uart_line[uart_rx_idx++] = c;
} else {
// Buffer overflow - reset
uart_rx_idx = 0;
}
// Re-enable interrupt for next character
HAL_UART_Receive_IT(&huart2, &uart_rx_byte, 1);
}
// Main loop (non-blocking check)
if (uart_line_ready) {
__disable_irq();
uart_line_ready = 0;
strncpy(cmd, uart_line, sizeof(cmd));
__enable_irq();
ProcessCommand(cmd); // Handle command
}Benefits:
- Non-blocking: Main loop continues running regardless of UART activity
- Complete lines: Only processes commands after Enter key pressed
- Buffer overflow protection: Resets on overflow instead of crashing
- Thread-safe: Uses critical section for flag/buffer access
- Minimal latency: Interrupt responds immediately to incoming data
Command Set:
S - Start system (automatic PID mode)
X - Stop system (fan off, all control disabled)
A - Auto mode (re-enable PID after manual)
T25.5 - Set temperature setpoint to 25.5Β°C (range: 18-35Β°C)
M75 - Manual mode, set fan to 75% speed
Systematic tuning was performed to determine optimal PID parameters.
#define PID_KP 20.0f // Proportional gain
#define PID_KI 0.3f // Integral gain
#define PID_KD 0.3f // Derivative gainThe tuning experiments are visualized in the graph below showing temperature response over time for different parameter sets:

Key Observations:
- Blue (Kd=0.3): Minimal fan cycling but Β±1.0Β°C temperature variation
- Green (Ki=0.3): Good steady-state accuracy with acceptable overshoot
- Purple (Kp=20): Fast response but steady-state error
Final Performance Metrics:
- Steady-state error: <0.05Β°C
- Overshoot: <0.5Β°C
- Settling time: ~60 seconds
- Temperature stability: Β±0.1Β°C
- Fan cycling frequency: ~1-2 cycles/minute
Tuning data files are available in the Tuning/ directory for further analysis.
float DS18B20_ReadTemperature(void) {
// Initiate conversion
DS18B20_Init();
DS18B20_Write(0xCC); // Skip ROM command
DS18B20_Write(0x44); // Convert temperature
HAL_Delay(750); // Wait for conversion (12-bit: 750ms)
// Read scratchpad
DS18B20_Init();
DS18B20_Write(0xCC); // Skip ROM
DS18B20_Write(0xBE); // Read scratchpad
uint8_t temp_lsb = DS18B20_Read();
uint8_t temp_msb = DS18B20_Read();
// Convert to temperature
int16_t raw = (int16_t)((temp_msb << 8) | temp_lsb);
return (float)raw / 16.0f; // 12-bit resolution: 0.0625Β°C per LSB
}void Fan_ControlByTemp(float temperature) {
static uint8_t fan_enabled = 0;
float fan = 0.0f;
if (!system_running) {
// System stopped - turn off fan and reset PID
fan_enabled = 0;
Fan_SetSpeed(0);
PID_Reset();
}
else if (manual_mode) {
// Manual override - direct speed control
fan_enabled = 1;
fan = clampf((float)manual_fan_speed, 0.0f, 100.0f);
Fan_SetSpeed((uint8_t)fan);
}
else {
// Automatic PID control
float err = temperature - user_setpoint;
if (!fan_enabled) {
if (err >= FAN_ON_BAND) {
fan_enabled = 1;
pid_last_time = 0U; // Re-init PID timing
}
} else {
if (err <= -FAN_OFF_BAND) {
fan_enabled = 0;
Fan_SetSpeed(0);
pid_last_time = 0U; // Pause PID (preserve integral)
}
}
// Compute PID output if fan enabled
if (fan_enabled) {
fan = PID_Compute(user_setpoint, temperature);
fan = clampf(fan, 0.0f, 100.0f);
Fan_SetSpeed((uint8_t)fan);
}
}
// Log telemetry
uint16_t rpm = Fan_GetRPM();
snprintf(msg, sizeof(msg),
"{\"temperature\":%.2f,\"setpoint\":%.2f,\"fanSpeed\":%.0f,"
"\"rpm\":%u,\"pTerm\":%.2f,\"iTerm\":%.2f,\"dTerm\":%.2f,"
"\"running\":%u,\"manual\":%u}\r\n",
temperature, user_setpoint, fan, rpm,
pid_last_p_term, pid_last_i_term, pid_last_d_term,
system_running, manual_mode);
HAL_UART_Transmit(&huart2, (uint8_t*)msg, strlen(msg), HAL_MAX_DELAY);
}int main(void) {
// Initialize hardware
HAL_Init();
SystemClock_Config();
MX_GPIO_Init();
MX_USART2_UART_Init();
MX_TIM1_Init();
// Start PWM and UART
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2);
HAL_UART_Receive_IT(&huart2, &uart_rx_byte, 1);
// Welcome message
snprintf(msg, sizeof(msg),
"==========================================\r\n"
"DS18B20 + PID Fan Control (L432KC)\r\n"
"Commands: S(start) X(stop) A(auto) T25.5(setpoint) M50(manual%%)\r\n"
"==========================================\r\n");
HAL_UART_Transmit(&huart2, (uint8_t*)msg, strlen(msg), HAL_MAX_DELAY);
// Fan startup test (3 seconds at 100%)
Fan_SetSpeed(100);
HAL_Delay(3000);
uint16_t test_rpm = Fan_GetRPM();
snprintf(msg, sizeof(msg), "Fan test RPM: %u\r\n\r\n", test_rpm);
HAL_UART_Transmit(&huart2, (uint8_t*)msg, strlen(msg), HAL_MAX_DELAY);
Fan_SetSpeed(0);
// Main control loop (2-second cycle)
while (1) {
// Process UART commands (non-blocking)
if (uart_line_ready) {
// ... process command ...
}
// Read temperature
if (DS18B20_Init()) {
float temperature = DS18B20_ReadTemperature();
Fan_ControlByTemp(temperature);
} else {
// Sensor fault - failsafe mode
Fan_SetSpeed(50); // 50% for safety
}
HAL_Delay(2000); // 2-second update cycle
}
}The implementation includes multiple safety mechanisms:
- Sensor Fault Detection: If DS18B20 fails presence check, enter failsafe mode (50% fan speed)
- Integral Clamping: PID integral term limited to Β±300 to prevent excessive windup
- Output Saturation: PID output hard-limited to 0-100% range
- RPM Timeout: Returns 0 RPM if no tachometer pulse for 2 seconds (detects stalled fan)
- UART Error Recovery: Automatic recovery from UART overrun errors
- Buffer Overflow Protection: UART receive buffer resets on overflow instead of corrupting memory
Unit Testing:
- DS18B20 communication verified with multiple sensors
- PWM output verified with oscilloscope (25kHz confirmed)
- RPM measurement verified against benchtop tachometer (Β±1% accuracy)
Integration Testing:
- Temperature control tested with hotplate for heating
- Setpoint changes tested for smooth transitions
- Manual override verified for all speed settings (0-100%)
- Sensor fault detection confirmed by disconnecting DS18B20
Knzy:
- Hardware Design: Circuit design, breadboard assembly, pin mapping, component testing
- Visualization: Python scripts, dashboard development, data plotting
Nadine:
- PID Control: Algorithm implementation
- Visualization: Python scripts, dashboard development, data plotting
Ziad:
- PID Control: Algorithm implementation
- Tuning: PID parameter optimization, data collection, performance analysis
-
STM32L432KC Datasheet
STMicroelectronics. (2024). STM32L432KC Ultra-low-power Arm Cortex-M4 32-bit MCU.
Retrieved from: https://www.st.com/resource/en/datasheet/stm32l432kc.pdf -
DS18B20 Temperature Sensor Datasheet
Maxim Integrated. (2019). DS18B20 Programmable Resolution 1-Wire Digital Thermometer.
Retrieved from: https://www.analog.com/media/en/technical-documentation/data-sheets/DS18B20.pdf -
STM32 HAL User Manual
STMicroelectronics. (2024). Description of STM32L4 HAL and low-layer drivers.
UM1884 Rev 10. -
4-Wire PWM Fan Specification
Intel Corporation. (2005). 4-Wire Pulse Width Modulation (PWM) Controlled Fans.
Retrieved from: https://www.intel.com/content/www/us/en/support/articles/000005859/processors.html
-
1-Wire Communication Through Software
Maxim Integrated. (2002). Using the DS18B20 Digital Thermometer.
Application Note 162. -
PID Controller Tuning
Γ strΓΆm, K. J., & HΓ€gglund, T. (2001). The Future of PID Control.
Control Engineering Practice, 9(11), 1163-1175. -
Anti-Windup for PID Controllers
Visioli, A. (2006). Anti-windup strategies for PID controllers.
In Practical PID Control (pp. 35-60). Springer.
-
STM32CubeMX Software
STMicroelectronics. https://www.st.com/en/development-tools/stm32cubemx.html -
DS18B20 Arduino Tutorial (Reference for wiring)
Random Nerd Tutorials. Guide for DS18B20 Temperature Sensor with Arduino.
https://randomnerdtutorials.com/guide-for-ds18b20-temperature-sensor-with-arduino/
-
Keil MDK-ARM
Arm Limited. Keil Β΅Vision IDE and Debugger.
https://www.keil.com/product/ -
STM32 ST-Link Utility
STMicroelectronics. STM32 ST-LINK Utility Software.
https://www.st.com/en/development-tools/stsw-link004.html
Project Repository: https://github.com/ziadmhassan/Embedding-Fanning-System