PRINCESS LAURONHEART LAHOYLAHOY
Published

RT-Spark AHT21 Real Time Operating System using STM32

We built a real-time system on the RT-Spark STM32 using FreeRTOS to read temperature and humidity, control an RGB LED, update a counter.

IntermediateWork in progress7 hours46
RT-Spark AHT21 Real Time Operating System using STM32

Things used in this project

Hardware components

STM32F7 Series
STMicroelectronics STM32F7 Series
×1
Jumper wires (generic)
Jumper wires (generic)
×1
RGB Diffused Common Cathode
RGB Diffused Common Cathode
×1
Resistor 220 ohm
Resistor 220 ohm
×1
Breadboard (generic)
Breadboard (generic)
×1
Rotary potentiometer (generic)
Rotary potentiometer (generic)
×1

Story

Read more

Schematics

sch_spark-1_v1_0_dnetgjxbia_Evh8yNzV77.pdf

Code

Main.c

C/C++
/* USER CODE BEGIN Header */
/**
  * Laboratory Activity 5: RTOS on STM32 (RT-Spark)
  * FINAL FIX: HYBRID TIMER SOLUTION
  * ------------------------------------------------
  * Problem: PA7 causes Matrix interference.
  * Solution: Avoid PA7. Use PA6 (TIM3) and PE11/PE13 (TIM1).
  *
  * Wiring:
  * - Red:   PA6  (TIM3_CH1)
  * - Green: PE11 (TIM1_CH2)
  * - Blue:  PE13 (TIM1_CH3)
  */
/* USER CODE END Header */

#include "main.h"
#include "cmsis_os.h"
#include "drv_lcd.h"
#include "drv_aht21.h"
#include <stdlib.h>
#include <math.h>

/* Private variables */
ADC_HandleTypeDef hadc1;
SRAM_HandleTypeDef hsram1;
TIM_HandleTypeDef htim1; // Controls Green/Blue
TIM_HandleTypeDef htim3; // Controls Red

/* RTOS Handles */
osThreadId_t TempTaskHandle;
osThreadId_t RGBTaskHandle;
osThreadId_t CounterTaskHandle;
osThreadId_t BlinkTaskHandle;
osMutexId_t  lcdMutexHandle;

/* Prototypes */
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_ADC1_Init(void);
static void MX_TIM3_Init(void);
static void MX_TIM1_Init(void);
static void MX_FSMC_Init(void);

void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
void Kill_Onboard_Hardware(void);

void StartTempTask(void *argument);
void StartRGBTask(void *argument);
void StartCounterTask(void *argument);
void StartBlinkTask(void *argument);

/* --- HELPER FUNCTIONS --- */
void LCD_DrawRect(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t color) {
    LCD_DrawPixel(x1, y1, color); LCD_DrawPixel(x2, y2, color);
    for (uint16_t x = x1; x <= x2; x++) { LCD_DrawPixel(x, y1, color); LCD_DrawPixel(x, y2, color); }
    for (uint16_t y = y1; y <= y2; y++) { LCD_DrawPixel(x1, y, color); LCD_DrawPixel(x2, y, color); }
}
void LCD_ShowNum(uint16_t x, uint16_t y, int num, uint16_t color, uint16_t back_color) {
    char buf[12]; int i = 0;
    if (num == 0) { LCD_ShowChar(x, y, '0', color, back_color); return; }
    if (num < 0) { LCD_ShowChar(x, y, '-', color, back_color); x += 8; num = -num; }
    while (num > 0) { buf[i++] = (num % 10) + '0'; num /= 10; }
    while (--i >= 0) { LCD_ShowChar(x, y, buf[i], color, back_color); x += 8; }
}
void LCD_ShowFloatManual(uint16_t x, uint16_t y, float val, uint16_t color, uint16_t back_color) {
    int intPart = (int)val;
    LCD_ShowNum(x, y, intPart, color, back_color);
    int offset = 8 + (intPart<0?8:0) + (abs(intPart)>9?8:0) + (abs(intPart)>99?8:0);
    LCD_ShowChar(x + offset, y, '.', color, back_color);
    int decPart = (int)((val - (float)intPart) * 100.0f);
    if (decPart < 0) decPart = -decPart;
    if (decPart < 10) { LCD_ShowChar(x+offset+8, y, '0', color, back_color); LCD_ShowNum(x+offset+16, y, decPart, color, back_color); }
    else { LCD_ShowNum(x+offset+8, y, decPart, color, back_color); }
}
#define FILTER_SIZE 10
float Filter_Value(float new_val, float *buffer, uint8_t *index, uint8_t *count) {
    if (new_val > 100.0f || new_val < -40.0f) {
        if (*count > 0) { float sum=0; for(int i=0; i<*count; i++) sum+=buffer[i]; return sum / *count; }
        return new_val;
    }
    buffer[*index] = new_val;
    *index = (*index + 1) % FILTER_SIZE;
    if (*count < FILTER_SIZE) (*count)++;
    float sum = 0; for (uint8_t i = 0; i < *count; i++) sum += buffer[i];
    return sum / (float)(*count);
}

/* --- MAIN FUNCTION --- */
int main(void)
{
  HAL_Init();
  SystemClock_Config();

  MX_GPIO_Init();
  MX_ADC1_Init();
  MX_TIM3_Init(); // Red (PA6)
  MX_TIM1_Init(); // Green (PE11), Blue (PE13)
  MX_FSMC_Init();

  /* 1. KILL ONBOARD INTERFERENCE */
  Kill_Onboard_Hardware();

  /* 2. START PWM CHANNELS */
  HAL_TIM_PWM_Start(&htim3, TIM_CHANNEL_1); // Red
  HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2); // Green
  HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_3); // Blue

  /* 3. DRIVER INIT */
  LCD_Init();
  LCD_Clear(WHITE);
  LCD_DrawRect(5, 5, 235, 40, BLUE);
  LCD_ShowString(40, 15, "RT-Spark FreeRTOS", BLUE, WHITE);
  LCD_ShowString(20, 60, "Temp:", BLACK, WHITE);
  LCD_ShowString(20, 80, "Hum: ", BLACK, WHITE);
  LCD_ShowString(20, 120, "Counter:", BLACK, WHITE);
  LCD_ShowString(20, 160, "LED Bright:", BLACK, WHITE);

  AHT21_Init();

  /* 4. RTOS INIT */
  osKernelInitialize();

  const osMutexAttr_t lcdMutex_attr = { .name = "LCDMutex" };
  lcdMutexHandle = osMutexNew(&lcdMutex_attr);

  const osThreadAttr_t tempTask_attr = { .name = "TempTask", .stack_size = 1024, .priority = (osPriority_t) osPriorityNormal };
  TempTaskHandle = osThreadNew(StartTempTask, NULL, &tempTask_attr);

  const osThreadAttr_t rgbTask_attr = { .name = "RGBTask", .stack_size = 512, .priority = (osPriority_t) osPriorityNormal };
  RGBTaskHandle = osThreadNew(StartRGBTask, NULL, &rgbTask_attr);

  const osThreadAttr_t countTask_attr = { .name = "CountTask", .stack_size = 256, .priority = (osPriority_t) osPriorityNormal };
  CounterTaskHandle = osThreadNew(StartCounterTask, NULL, &countTask_attr);

  const osThreadAttr_t blinkTask_attr = { .name = "BlinkTask", .stack_size = 128, .priority = (osPriority_t) osPriorityLow };
  BlinkTaskHandle = osThreadNew(StartBlinkTask, NULL, &blinkTask_attr);

  osKernelStart();
  while (1) { __WFI(); }
}

void Kill_Onboard_Hardware(void) {
    GPIO_InitTypeDef GPIO_InitStruct = {0};

    // 1. Force PF2 (Matrix Power) LOW
    HAL_GPIO_WritePin(GPIOF, GPIO_PIN_2, GPIO_PIN_RESET);
    GPIO_InitStruct.Pin = GPIO_PIN_2;
    GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
    GPIO_InitStruct.Pull = GPIO_PULLDOWN;
    GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
    HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);

    // 2. Force PF12 (Red LED) HIGH (OFF)
    HAL_GPIO_WritePin(GPIOF, GPIO_PIN_12, GPIO_PIN_SET);
    GPIO_InitStruct.Pin = GPIO_PIN_12;
    GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
    GPIO_InitStruct.Pull = GPIO_PULLUP;
    HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);

    // 3. Force PA7 (Matrix Data) to Input/PullDown (Safety)
    __HAL_RCC_GPIOA_CLK_ENABLE();
    GPIO_InitStruct.Pin = GPIO_PIN_7;
    GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
    GPIO_InitStruct.Pull = GPIO_PULLDOWN;
    HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
}

void StartRGBTask(void *argument) {
    uint32_t adc_val;
    uint32_t last_adc_val = 9999;
    int brightness_pct;
    uint32_t pwm_val;

    for(;;) {
        HAL_ADC_Start(&hadc1);
        if (HAL_ADC_PollForConversion(&hadc1, 10) == HAL_OK) {
            adc_val = HAL_ADC_GetValue(&hadc1);
        }

        // Deadzone
        if (adc_val < 150) adc_val = 0;

        // Hysteresis
        if (abs((int)adc_val - (int)last_adc_val) > 20) {
            last_adc_val = adc_val;

            pwm_val = (adc_val * 999) / 4095;
            brightness_pct = (adc_val * 100) / 4095;

            // Update Colors (Mixed Timers)
            __HAL_TIM_SET_COMPARE(&htim3, TIM_CHANNEL_1, pwm_val); // Red (PA6)
            __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, pwm_val); // Green (PE11)
            __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, pwm_val); // Blue (PE13)

            if (osMutexAcquire(lcdMutexHandle, 100) == osOK) {
                 LCD_ShowString(120, 160, "    ", WHITE, WHITE);
                 LCD_ShowNum(120, 160, brightness_pct, BLACK, WHITE);
                 LCD_ShowChar(150, 160, '%', BLACK, WHITE);
                 osMutexRelease(lcdMutexHandle);
            }
        }
        osDelay(50);
    }
}

void StartBlinkTask(void *argument) {
    HAL_GPIO_WritePin(GPIOF, GPIO_PIN_12, GPIO_PIN_SET);
    for(;;) {
        HAL_GPIO_TogglePin(GPIOF, GPIO_PIN_11);
        HAL_GPIO_WritePin(GPIOF, GPIO_PIN_12, GPIO_PIN_SET);
        osDelay(200);
    }
}

// ... (StartTempTask, StartCounterTask) ...
void StartTempTask(void *argument) {
    float raw_temp=0, raw_hum=0, final_temp=0, final_hum=0;
    float temp_buf[FILTER_SIZE]={0}, hum_buf[FILTER_SIZE]={0};
    uint8_t t_idx=0, h_idx=0, t_cnt=0, h_cnt=0;
    for(;;) {
        if (AHT21_Read(&raw_temp, &raw_hum) == 1) {
            final_temp = Filter_Value(raw_temp, temp_buf, &t_idx, &t_cnt);
            final_hum  = Filter_Value(raw_hum, hum_buf, &h_idx, &h_cnt);
            if (osMutexAcquire(lcdMutexHandle, 500) == osOK) {
                LCD_ShowString(70, 60, "      ", WHITE, WHITE);
                LCD_ShowFloatManual(70, 60, final_temp, RED, WHITE);
                LCD_ShowChar(130, 60, 'C', RED, WHITE);
                LCD_ShowString(70, 80, "      ", WHITE, WHITE);
                LCD_ShowFloatManual(70, 80, final_hum, BLUE, WHITE);
                LCD_ShowChar(130, 80, '%', BLUE, WHITE);
                osMutexRelease(lcdMutexHandle);
            }
        }
        osDelay(1000);
    }
}
void StartCounterTask(void *argument) {
    int counter = 0;
    for(;;) {
        counter++;
        if (counter > 100) counter = 0;
        if (osMutexAcquire(lcdMutexHandle, 500) == osOK) {
            LCD_ShowString(100, 120, "     ", WHITE, WHITE);
            LCD_ShowNum(100, 120, counter, BLACK, WHITE);
            osMutexRelease(lcdMutexHandle);
        }
        osDelay(500);
    }
}

/* --- PERIPHERAL INIT --- */
static void MX_TIM1_Init(void) {
  TIM_MasterConfigTypeDef sMasterConfig = {0};
  TIM_OC_InitTypeDef sConfigOC = {0};
  TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
  htim1.Instance = TIM1;
  htim1.Init.Prescaler = 15;
  htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
  htim1.Init.Period = 999;
  htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
  htim1.Init.RepetitionCounter = 0;
  htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
  HAL_TIM_PWM_Init(&htim1);
  sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
  sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
  HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig);
  sConfigOC.OCMode = TIM_OCMODE_PWM1;
  sConfigOC.Pulse = 0;
  sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
  sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
  sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
  sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
  // Configure PE11 (CH2) and PE13 (CH3)
  HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_2);
  HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3);
  HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig);
  HAL_TIM_MspPostInit(&htim1);
}

static void MX_TIM3_Init(void) {
  TIM_MasterConfigTypeDef sMasterConfig = {0};
  TIM_OC_InitTypeDef sConfigOC = {0};
  htim3.Instance = TIM3;
  htim3.Init.Prescaler = 15;
  htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
  htim3.Init.Period = 999;
  htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
  htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
  HAL_TIM_PWM_Init(&htim3);
  sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
  sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
  HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig);
  sConfigOC.OCMode = TIM_OCMODE_PWM1;
  sConfigOC.Pulse = 0;
  sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
  sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
  // Configure PA6 (CH1)
  HAL_TIM_PWM_ConfigChannel(&htim3, &sConfigOC, TIM_CHANNEL_1);
  HAL_TIM_MspPostInit(&htim3);
}

/*void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim) {
  GPIO_InitTypeDef GPIO_InitStruct = {0};
  if (htim->Instance == TIM3) {
    __HAL_RCC_GPIOA_CLK_ENABLE();
    GPIO_InitStruct.Pin = GPIO_PIN_6; // PA6 ONLY (No PA7)
    GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
    GPIO_InitStruct.Pull = GPIO_NOPULL;
    GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
    GPIO_InitStruct.Alternate = GPIO_AF2_TIM3;
    HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
  }
  else if (htim->Instance == TIM1) {
    __HAL_RCC_GPIOE_CLK_ENABLE();
    GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_13; // PE11 and PE13
    GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
    GPIO_InitStruct.Pull = GPIO_NOPULL;
    GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
    GPIO_InitStruct.Alternate = GPIO_AF1_TIM1;
    HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
  }
}*/

static void MX_GPIO_Init(void) {
  GPIO_InitTypeDef GPIO_InitStruct = {0};
  __HAL_RCC_GPIOF_CLK_ENABLE(); __HAL_RCC_GPIOA_CLK_ENABLE();
  __HAL_RCC_GPIOG_CLK_ENABLE(); __HAL_RCC_GPIOE_CLK_ENABLE();
  __HAL_RCC_GPIOD_CLK_ENABLE();

  HAL_GPIO_WritePin(GPIOF, GPIO_PIN_11|GPIO_PIN_12, GPIO_PIN_SET);
  HAL_GPIO_WritePin(GPIOF, GPIO_PIN_9|GPIO_PIN_2|GPIO_PIN_13, GPIO_PIN_RESET);

  GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
  GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);

  GPIO_InitStruct.Pin = GPIO_PIN_9|GPIO_PIN_2|GPIO_PIN_13;
  HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
  HAL_GPIO_WritePin(GPIOF, GPIO_PIN_13, GPIO_PIN_SET);

  GPIO_InitStruct.Pin = GPIO_PIN_3;
  HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
  HAL_GPIO_WritePin(GPIOD, GPIO_PIN_3, GPIO_PIN_SET);

  GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1;
  GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD;
  GPIO_InitStruct.Pull = GPIO_PULLUP;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
  HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
  HAL_GPIO_WritePin(GPIOE, GPIO_PIN_0|GPIO_PIN_1, GPIO_PIN_SET);
}

static void MX_ADC1_Init(void) {
  ADC_ChannelConfTypeDef sConfig = {0};
  hadc1.Instance = ADC1;
  hadc1.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
  hadc1.Init.Resolution = ADC_RESOLUTION_12B;
  hadc1.Init.ScanConvMode = DISABLE;
  hadc1.Init.ContinuousConvMode = DISABLE;
  hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
  hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
  hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
  hadc1.Init.NbrOfConversion = 1;
  HAL_ADC_Init(&hadc1);
  sConfig.Channel = ADC_CHANNEL_1;
  sConfig.Rank = 1;
  sConfig.SamplingTime = ADC_SAMPLETIME_3CYCLES;
  HAL_ADC_ConfigChannel(&hadc1, &sConfig);
}

static void MX_FSMC_Init(void) {
  FSMC_NORSRAM_TimingTypeDef Timing = {0};
  hsram1.Instance = FSMC_NORSRAM_DEVICE;
  hsram1.Extended = FSMC_NORSRAM_EXTENDED_DEVICE;
  hsram1.Init.NSBank = FSMC_NORSRAM_BANK3;
  hsram1.Init.DataAddressMux = FSMC_DATA_ADDRESS_MUX_DISABLE;
  hsram1.Init.MemoryType = FSMC_MEMORY_TYPE_SRAM;
  hsram1.Init.MemoryDataWidth = FSMC_NORSRAM_MEM_BUS_WIDTH_8;
  hsram1.Init.WriteOperation = FSMC_WRITE_OPERATION_ENABLE;
  hsram1.Init.ExtendedMode = FSMC_EXTENDED_MODE_DISABLE;
  hsram1.Init.AsynchronousWait = FSMC_ASYNCHRONOUS_WAIT_DISABLE;
  hsram1.Init.WriteBurst = FSMC_WRITE_BURST_DISABLE;
  hsram1.Init.PageSize = FSMC_PAGE_SIZE_NONE;
  Timing.AddressSetupTime = 15;
  Timing.AddressHoldTime = 15;
  Timing.DataSetupTime = 60;
  Timing.BusTurnAroundDuration = 5;
  Timing.CLKDivision = 16;
  Timing.DataLatency = 17;
  Timing.AccessMode = FSMC_ACCESS_MODE_A;
  HAL_SRAM_Init(&hsram1, &Timing, NULL);
}

void SystemClock_Config(void) {
    RCC_OscInitTypeDef RCC_OscInitStruct = {0};
    RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
    __HAL_RCC_PWR_CLK_ENABLE();
    __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
    RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
    RCC_OscInitStruct.HSIState = RCC_HSI_ON;
    RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
    RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
    HAL_RCC_OscConfig(&RCC_OscInitStruct);
    RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
    RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI;
    RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
    RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
    RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
    HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0);
}

void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
  if (htim->Instance == TIM6) HAL_IncTick();
}

void Error_Handler(void) { __disable_irq(); while (1) {} }

drv_lcd.c

C/C++
#include "main.h"
#include "drv_lcd.h"
#include "drv_lcd_font.h"
#include <string.h>

/* * SECTION 1: MEMORY MAPPING FOR PF0 (A0)
 * Base Address: 0x60000000 (Bank 1)
 * RS Pin: PF0 (FSMC_A0)
 * * Logic:
 * - Address 0x60000000 -> A0 is 0 -> LCD Command
 * - Address 0x60000001 -> A0 is 1 -> LCD Data
 * (Note: For 8-bit width, address shifts by 0, so bit 0 maps to A0)
 */
/* BANK 3 (NE3) Address = 0x68000000 */
#define LCD_BASE        ((uint32_t)0x68000000)
#define LCD_REG         (*((volatile uint8_t *)LCD_BASE))
#define LCD_RAM         (*((volatile uint8_t *)(LCD_BASE + 0x40000))) // A18 Offset

/* REMOVE any "LCD_CS_LOW()" calls from your functions.
   Let the hardware handle CS automatically. */
_lcd_dev lcddev;
uint16_t BACK_COLOR = WHITE;
uint16_t FORE_COLOR = BLACK;

/* SECTION 2: GPIO CHIP SELECT CONTROL */
// Since CS is on PF13 (not a hardware NE pin), we control it manually.
// Active Low: 0 = Selected, 1 = Deselected
void LCD_CS_LOW(void)  { HAL_GPIO_WritePin(LCD_CS_GPIO_Port, LCD_CS_Pin, GPIO_PIN_RESET); }
void LCD_CS_HIGH(void) { HAL_GPIO_WritePin(LCD_CS_GPIO_Port, LCD_CS_Pin, GPIO_PIN_SET); }

/* SECTION 3: BUS WRITES */
void LCD_WR_REG(uint8_t reg) {
    LCD_CS_LOW();  // Select LCD
    LCD_REG = reg; // Write Command
    LCD_CS_HIGH(); // Deselect
}

void LCD_WR_DATA8(uint8_t data) {
    LCD_CS_LOW();
    LCD_RAM = data; // Write Data
    LCD_CS_HIGH();
}

void LCD_WR_DATA16(uint16_t data) {
    LCD_CS_LOW();
    LCD_RAM = (data >> 8);   // High Byte
    LCD_RAM = (data & 0xFF); // Low Byte
    LCD_CS_HIGH();
}

void LCD_WriteRAM_Prepare(void) {
    LCD_WR_REG(lcddev.wramcmd);
}

void LCD_WriteRAM(uint16_t color) {
    LCD_WR_DATA16(color);
}

/* SECTION 4: INITIALIZATION */
void LCD_Reset(void) {
    HAL_GPIO_WritePin(LCD_RST_GPIO_Port, LCD_RST_Pin, GPIO_PIN_RESET);
    HAL_Delay(50);
    HAL_GPIO_WritePin(LCD_RST_GPIO_Port, LCD_RST_Pin, GPIO_PIN_SET);
    HAL_Delay(50);
}

void LCD_Init(void) {
    // Ensure CS is high (inactive) initially
    LCD_CS_HIGH();

    LCD_Reset();
    HAL_GPIO_WritePin(LCD_BL_GPIO_Port, LCD_BL_Pin, GPIO_PIN_SET); // Backlight On

    // 1. Sleep Out
    LCD_WR_REG(0x11);
    HAL_Delay(120);

    // 2. Pixel Format (RGB565)
    LCD_WR_REG(0x36); LCD_WR_DATA8(0x00);
    LCD_WR_REG(0x3A); LCD_WR_DATA8(0x05);

    // 3. Power & Gamma (Standard ST7789)
    LCD_WR_REG(0xB2); LCD_WR_DATA8(0x0C); LCD_WR_DATA8(0x0C); LCD_WR_DATA8(0x00); LCD_WR_DATA8(0x33); LCD_WR_DATA8(0x33);
    LCD_WR_REG(0xB7); LCD_WR_DATA8(0x35);
    LCD_WR_REG(0xBB); LCD_WR_DATA8(0x19);
    LCD_WR_REG(0xC0); LCD_WR_DATA8(0x2C);
    LCD_WR_REG(0xC2); LCD_WR_DATA8(0x01);
    LCD_WR_REG(0xC3); LCD_WR_DATA8(0x12);
    LCD_WR_REG(0xC4); LCD_WR_DATA8(0x20);
    LCD_WR_REG(0xC6); LCD_WR_DATA8(0x0F);
    LCD_WR_REG(0xD0); LCD_WR_DATA8(0xA4); LCD_WR_DATA8(0xA1);

    LCD_WR_REG(0xE0); LCD_WR_DATA8(0xD0); LCD_WR_DATA8(0x04); LCD_WR_DATA8(0x0D); LCD_WR_DATA8(0x11); LCD_WR_DATA8(0x13); LCD_WR_DATA8(0x2B); LCD_WR_DATA8(0x3F); LCD_WR_DATA8(0x54); LCD_WR_DATA8(0x4C); LCD_WR_DATA8(0x18); LCD_WR_DATA8(0x0D); LCD_WR_DATA8(0x0B); LCD_WR_DATA8(0x1F); LCD_WR_DATA8(0x23);
    LCD_WR_REG(0xE1); LCD_WR_DATA8(0xD0); LCD_WR_DATA8(0x04); LCD_WR_DATA8(0x0C); LCD_WR_DATA8(0x11); LCD_WR_DATA8(0x13); LCD_WR_DATA8(0x2C); LCD_WR_DATA8(0x3F); LCD_WR_DATA8(0x44); LCD_WR_DATA8(0x51); LCD_WR_DATA8(0x2F); LCD_WR_DATA8(0x1F); LCD_WR_DATA8(0x1F); LCD_WR_DATA8(0x20); LCD_WR_DATA8(0x23);

    // 4. Display On
    LCD_WR_REG(0x21); // Inversion On
    LCD_WR_REG(0x29); // Display On

    // 5. Parameters
    lcddev.width = 240;
    lcddev.height = 240;
    lcddev.setxcmd = 0x2A;
    lcddev.setycmd = 0x2B;
    lcddev.wramcmd = 0x2C;

    LCD_Clear(WHITE);
}

// (Keep LCD_SetWindow, LCD_Clear, LCD_DrawPixel, LCD_ShowChar, LCD_ShowString exactly as they were)
/* ... PASTE SECTION 4 and 5 FROM YOUR PREVIOUS FILE HERE ... */
void LCD_SetWindow(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) {
    LCD_WR_REG(lcddev.setxcmd);
    LCD_WR_DATA8(x1 >> 8); LCD_WR_DATA8(x1 & 0xFF);
    LCD_WR_DATA8(x2 >> 8); LCD_WR_DATA8(x2 & 0xFF);
    LCD_WR_REG(lcddev.setycmd);
    LCD_WR_DATA8(y1 >> 8); LCD_WR_DATA8(y1 & 0xFF);
    LCD_WR_DATA8(y2 >> 8); LCD_WR_DATA8(y2 & 0xFF);
    LCD_WriteRAM_Prepare();
}

void LCD_Clear(uint16_t color) {
    LCD_SetWindow(0, 0, lcddev.width-1, lcddev.height-1);
    uint32_t total = lcddev.width * lcddev.height;
    // Note: We don't toggle CS for every pixel to speed it up
    LCD_CS_LOW();
    for (uint32_t i = 0; i < total; i++) {
        LCD_RAM = (color >> 8);
        LCD_RAM = (color & 0xFF);
    }
    LCD_CS_HIGH();
}

void LCD_DrawPixel(uint16_t x, uint16_t y, uint16_t color) {
    if (x >= lcddev.width || y >= lcddev.height) return;
    LCD_SetWindow(x, y, x, y);
    LCD_WR_DATA16(color);
}

void LCD_ShowChar(uint16_t x, uint16_t y, uint8_t num, uint16_t color, uint16_t back_color) {
    uint8_t temp, t;
    uint16_t pos;
    if (x > lcddev.width - 8 || y > lcddev.height - 16) return;
    num = num - ' ';
    LCD_SetWindow(x, y, x + 7, y + 15);

    LCD_CS_LOW(); // Optimization: Hold CS low for the whole character
    for (pos = 0; pos < 16; pos++) {
        temp = asc2_1608[num * 16 + pos];
        for (t = 0; t < 8; t++) {
            if (temp & 0x80) { LCD_RAM=(color>>8); LCD_RAM=(color&0xFF); }
            else             { LCD_RAM=(back_color>>8); LCD_RAM=(back_color&0xFF); }
            temp <<= 1;
        }
    }
    LCD_CS_HIGH();
}

void LCD_ShowString(uint16_t x, uint16_t y, char *p, uint16_t color, uint16_t back_color) {
    while (*p != '\0') {
        if (x > lcddev.width - 8) { x = 0; y += 16; }
        if (y > lcddev.height - 16) break;
        LCD_ShowChar(x, y, *p, color, back_color);
        x += 8; p++;
    }
}

drv_aht21.c

C/C++
#include "drv_aht21.h"

/*
 * SECTION 1: GPIO DIRECTION CONTROL (The Hardware Layer)
 */

// Switch SDA pin to INPUT mode (Receive)
// We do this when waiting for an ACK or reading data bits from the sensor.
void SDA_IN(void) {
    GPIO_InitTypeDef GPIO_InitStruct = {0};
    GPIO_InitStruct.Pin = AHT_SDA_PIN;
    GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
    GPIO_InitStruct.Pull = GPIO_PULLUP;     // Internal resistor pulls line high when idle
    HAL_GPIO_Init(AHT_SDA_PORT, &GPIO_InitStruct);
}

// Switch SDA pin to OUTPUT mode (Transmit)
// We do this when sending commands (Start, Address, Data) to the sensor.
void SDA_OUT(void) {
    GPIO_InitTypeDef GPIO_InitStruct = {0};
    GPIO_InitStruct.Pin = AHT_SDA_PIN;
    GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD; // Open-Drain is standard for I2C
    GPIO_InitStruct.Pull = GPIO_PULLUP;
    GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
    HAL_GPIO_Init(AHT_SDA_PORT, &GPIO_InitStruct);
}

/* Pin State Macros - Shortcuts for setting pins High/Low */
#define SCL_H HAL_GPIO_WritePin(AHT_SCL_PORT, AHT_SCL_PIN, GPIO_PIN_SET)
#define SCL_L HAL_GPIO_WritePin(AHT_SCL_PORT, AHT_SCL_PIN, GPIO_PIN_RESET)
#define SDA_H HAL_GPIO_WritePin(AHT_SDA_PORT, AHT_SDA_PIN, GPIO_PIN_SET)
#define SDA_L HAL_GPIO_WritePin(AHT_SDA_PORT, AHT_SDA_PIN, GPIO_PIN_RESET)
#define READ_SDA HAL_GPIO_ReadPin(AHT_SDA_PORT, AHT_SDA_PIN)

// Simple delay to control I2C bus speed (Bit-Banging speed limit)
void I2C_Delay(void) {
    volatile int i = 400;
    while(i--);
}

/*
 * SECTION 2: I2C PROTOCOL PRIMITIVES (The Transport Layer)
 * These functions generate the specific electrical signals required by the
 * I2C standard.
 */

// Generate START condition: SDA goes High->Low while SCL is High
void I2C_Start(void) {
    SDA_OUT();    // Ensure we are in control
    SDA_H; SCL_H;
    I2C_Delay();
    SDA_L;        // Pull Data Low (Start Signal)
    I2C_Delay();
    SCL_L;        // Hold Clock Low (Bus Busy)
}

// Generate STOP condition: SDA goes Low->High while SCL is High
void I2C_Stop(void) {
    SDA_OUT();
    SCL_L; SDA_L; // Prepare Data Low
    I2C_Delay();
    SCL_H;        // Release Clock
    I2C_Delay();
    SDA_H;        // Release Data High (Stop Signal)
    I2C_Delay();
}

// Wait for the Sensor to acknowledge (ACK) our command
// Returns 0 if ACK received, 1 if Timeout/Error
uint8_t I2C_WaitAck(void) {
    uint32_t errTime = 0;
    SDA_IN();     // Switch to Input to listen
    SDA_H;        // Release line
    I2C_Delay();
    SCL_H;        // Clock High (Tell sensor to send ACK bit)
    I2C_Delay();

    // Wait for Sensor to pull SDA Low (ACK)
    while(READ_SDA) {
        errTime++;
        // Safety timeout to prevent infinite loop if sensor is missing
        if(errTime > 3000) {
            I2C_Stop();
            return 1;
        }
    }
    SCL_L; // Clock Low (Finish ACK cycle)
    return 0;
}

// Send 8 bits (1 Byte) to the sensor, MSB first
void I2C_SendByte(uint8_t byte) {
    SDA_OUT();
    SCL_L;
    for(int i=0; i<8; i++) {
        // Check if the current bit is 1 or 0
        if(byte & 0x80) SDA_H;
        else            SDA_L;

        byte <<= 1;   // Shift left to next bit
        I2C_Delay();
        SCL_H;        // Clock High (Sensor reads bit)
        I2C_Delay();
        SCL_L;        // Clock Low
        I2C_Delay();
    }
}

// Read 8 bits (1 Byte) from the sensor
uint8_t I2C_ReadByte(unsigned char ack) {
    unsigned char i, receive = 0;
    SDA_IN(); // Switch to Input to read
    for(i=0; i<8; i++) {
        SCL_L;
        I2C_Delay();
        SCL_H;        // Clock High (Data is valid)
        receive <<= 1; // Shift current data left
        if(READ_SDA) receive++; // Read pin, if High add 1
        I2C_Delay();
    }
    SDA_OUT(); // Switch back to Output to send response

    // Send ACK (Low) if we want more data, or NACK (High) to stop
    if (!ack) {
    	SCL_L; SDA_H; SCL_H;
    	I2C_Delay();
    	SCL_L;
    } else {
    	SCL_L; SDA_L; SCL_H;
    	I2C_Delay();
    	SCL_L;
    }
    return receive;
}

/*
 * SECTION 3: AHT21 SPECIFIC LOGIC (The Application Layer)
 */

// Initialize the sensor by sending the 0xBE command
void AHT21_Init(void) {
    GPIO_InitTypeDef GPIO_InitStruct = {0};

    // Enable GPIO Clock
    __HAL_RCC_GPIOE_CLK_ENABLE();

    // Default pin configuration
    GPIO_InitStruct.Pin = AHT_SCL_PIN | AHT_SDA_PIN;
    GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD;
    GPIO_InitStruct.Pull = GPIO_PULLUP;
    GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
    HAL_GPIO_Init(AHT_SCL_PORT, &GPIO_InitStruct);

    SCL_H; SDA_H;
    HAL_Delay(100); // Power-on delay required by datasheet

    // Send Calibration Command
    I2C_Start();
    I2C_SendByte(AHT_ADDR << 1); // Address + Write bit
    if(!I2C_WaitAck()) {
        I2C_SendByte(0xBE); // Init Command
        I2C_WaitAck();
        I2C_SendByte(0x08); // Parameter 1
        I2C_WaitAck();
        I2C_SendByte(0x00); // Parameter 2
        I2C_WaitAck();
        I2C_Stop();
    }
    HAL_Delay(10);
}

// Read Temperature and Humidity
uint8_t AHT21_Read(float *Temperature, float *Humidity) {
    uint8_t data[6];

    // 1. Trigger Measurement Command (0xAC)
    I2C_Start();
    I2C_SendByte(AHT_ADDR << 1);
    if(I2C_WaitAck()) return 0; // Check for device presence
    I2C_SendByte(0xAC); // Trigger Measure
    if(I2C_WaitAck()) return 0;
    I2C_SendByte(0x33); // Param 1
    if(I2C_WaitAck()) return 0;
    I2C_SendByte(0x00); // Param 2
    if(I2C_WaitAck()) return 0;
    I2C_Stop();

    // 2. Wait for Measurement (Sensor needs ~80ms to process)
    HAL_Delay(80);

    // 3. Read Data (6 Bytes)
    I2C_Start();
    I2C_SendByte((AHT_ADDR << 1) | 1); // Address + Read bit
    if(I2C_WaitAck()) return 0;

    for(int i=0; i<6; i++) {
        data[i] = I2C_ReadByte(i < 5); // ACK first 5 bytes, NACK last one
    }
    I2C_Stop();

    // 4. Parse Data (Bit shifting)
    // The sensor sends 20-bit values split across bytes. We assume the data is valid.
    // Humidity: Combined from Byte 1, Byte 2, and top 4 bits of Byte 3
    uint32_t rawHum = ((uint32_t)data[1] << 12) | ((uint32_t)data[2] << 4) | ((data[3] & 0xF0) >> 4);
    // Temperature: Combined from lower 4 bits of Byte 3, Byte 4, and Byte 5
    uint32_t rawTemp = ((uint32_t)(data[3] & 0x0F) << 16) | ((uint32_t)data[4] << 8) | data[5];

    // 5. Convert to Floating Point (Formulas from Datasheet)
    *Humidity = (float)rawHum * 100.0f / 1048576.0f;
    *Temperature = ((float)rawTemp * 200.0f / 1048576.0f) - 50.0f;

    return 1;
}

syscalls.c

C/C++
/**
 ******************************************************************************
 * @file      syscalls.c
 * @author    Auto-generated by STM32CubeIDE
 * @brief     STM32CubeIDE Minimal System calls file
 *
 *            For more information about which c-functions
 *            need which of these lowlevel functions
 *            please consult the Newlib libc-manual
 ******************************************************************************
 * @attention
 *
 * Copyright (c) 2020-2025 STMicroelectronics.
 * All rights reserved.
 *
 * This software is licensed under terms that can be found in the LICENSE file
 * in the root directory of this software component.
 * If no LICENSE file comes with this software, it is provided AS-IS.
 *
 ******************************************************************************
 */

/* Includes */
#include <sys/stat.h>
#include <stdlib.h>
#include <errno.h>
#include <stdio.h>
#include <signal.h>
#include <time.h>
#include <sys/time.h>
#include <sys/times.h>


/* Variables */
extern int __io_putchar(int ch) __attribute__((weak));
extern int __io_getchar(void) __attribute__((weak));


char *__env[1] = { 0 };
char **environ = __env;


/* Functions */
void initialise_monitor_handles()
{
}

int _getpid(void)
{
  return 1;
}

int _kill(int pid, int sig)
{
  (void)pid;
  (void)sig;
  errno = EINVAL;
  return -1;
}

void _exit (int status)
{
  _kill(status, -1);
  while (1) {}    /* Make sure we hang here */
}

__attribute__((weak)) int _read(int file, char *ptr, int len)
{
  (void)file;
  int DataIdx;

  for (DataIdx = 0; DataIdx < len; DataIdx++)
  {
    *ptr++ = __io_getchar();
  }

  return len;
}

__attribute__((weak)) int _write(int file, char *ptr, int len)
{
  (void)file;
  int DataIdx;

  for (DataIdx = 0; DataIdx < len; DataIdx++)
  {
    __io_putchar(*ptr++);
  }
  return len;
}

int _close(int file)
{
  (void)file;
  return -1;
}


int _fstat(int file, struct stat *st)
{
  (void)file;
  st->st_mode = S_IFCHR;
  return 0;
}

int _isatty(int file)
{
  (void)file;
  return 1;
}

int _lseek(int file, int ptr, int dir)
{
  (void)file;
  (void)ptr;
  (void)dir;
  return 0;
}

int _open(char *path, int flags, ...)
{
  (void)path;
  (void)flags;
  /* Pretend like we always fail */
  return -1;
}

int _wait(int *status)
{
  (void)status;
  errno = ECHILD;
  return -1;
}

int _unlink(char *name)
{
  (void)name;
  errno = ENOENT;
  return -1;
}

int _times(struct tms *buf)
{
  (void)buf;
  return -1;
}

int _stat(char *file, struct stat *st)
{
  (void)file;
  st->st_mode = S_IFCHR;
  return 0;
}

int _link(char *old, char *new)
{
  (void)old;
  (void)new;
  errno = EMLINK;
  return -1;
}

int _fork(void)
{
  errno = EAGAIN;
  return -1;
}

int _execve(char *name, char **argv, char **env)
{
  (void)name;
  (void)argv;
  (void)env;
  errno = ENOMEM;
  return -1;
}

drv_lcd_font.c

C/C++
#include "drv_lcd_font.h"

// Define the 16x8 ASCII font table
// This table contains 95 printable ASCII characters (from ' ' to '~')
// Each character is 16 bytes (16x8 pixels, 1 byte per row)
const uint8_t asc2_1608[95 * 16] = {

		0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, /* " " */
		    0x00,0x00,0x00,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x00,0x00,0x18,0x18,0x00,0x00, /* "!" */
		    0x00,0x48,0x6C,0xC4,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, /* """ */
		    0x00,0x00,0x00,0x24,0x24,0x24,0x7F,0x12,0x12,0x12,0x7F,0x12,0x12,0x12,0x00,0x00, /* "#" */
		    0x00,0x00,0x08,0x1C,0x2A,0x2A,0x0A,0x0C,0x18,0x28,0x28,0x2A,0x2A,0x1C,0x08,0x08, /* "$" */
		    0x00,0x00,0x00,0x22,0x25,0x15,0x15,0x15,0x2A,0x58,0x54,0x54,0x54,0x22,0x00,0x00, /* "%" */
		    0x00,0x00,0x00,0x0C,0x12,0x12,0x12,0x0A,0x76,0x25,0x29,0x11,0x91,0x6E,0x00,0x00, /* "&" */
		    0x00,0x06,0x06,0x04,0x03,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, /* "'" */
		    0x00,0x00,0x00,0x1C,0x22,0x41,0x41,0x41,0x41,0x41,0x41,0x22,0x1C,0x00,0x00,0x00, /* "(" */
		    0x00,0x00,0x00,0x38,0x44,0x82,0x82,0x82,0x82,0x82,0x82,0x44,0x38,0x00,0x00,0x00, /* ")" */
		    0x00,0x00,0x00,0x00,0x42,0x24,0x18,0x18,0x18,0x24,0x42,0x00,0x00,0x00,0x00,0x00, /* "*" */
		    0x00,0x00,0x00,0x08,0x08,0x08,0x08,0x7F,0x08,0x08,0x08,0x08,0x00,0x00,0x00,0x00, /* "+" */
		    0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x06,0x06,0x04,0x03, /* "," */
		    0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7E,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, /* "-" */
		    0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x06,0x06,0x00,0x00, /* "." */
		    0x00,0x00,0x00,0x00,0x02,0x04,0x08,0x10,0x20,0x40,0x80,0x00,0x00,0x00,0x00,0x00, /* "/" */
		    0x00,0x00,0x00,0x3E,0x41,0x41,0x41,0x41,0x41,0x41,0x41,0x41,0x3E,0x00,0x00,0x00, /* "0" */
		    0x00,0x00,0x00,0x08,0x0C,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x1C,0x00,0x00,0x00, /* "1" */
		    0x00,0x00,0x00,0x3E,0x41,0x41,0x02,0x04,0x08,0x10,0x20,0x40,0x7F,0x00,0x00,0x00, /* "2" */
		    0x00,0x00,0x00,0x3E,0x41,0x02,0x04,0x0C,0x02,0x02,0x01,0x41,0x3E,0x00,0x00,0x00, /* "3" */
		    0x00,0x00,0x00,0x04,0x0C,0x14,0x24,0x44,0x44,0x7F,0x04,0x04,0x1F,0x00,0x00,0x00, /* "4" */
		    0x00,0x00,0x00,0x7F,0x40,0x40,0x40,0x7C,0x02,0x02,0x02,0x42,0x3C,0x00,0x00,0x00, /* "5" */
		    0x00,0x00,0x00,0x1C,0x22,0x40,0x40,0x5C,0x62,0x42,0x42,0x42,0x3C,0x00,0x00,0x00, /* "6" */
		    0x00,0x00,0x00,0x7F,0x42,0x04,0x08,0x08,0x10,0x10,0x20,0x20,0x20,0x00,0x00,0x00, /* "7" */
		    0x00,0x00,0x00,0x3C,0x42,0x42,0x42,0x3C,0x42,0x42,0x42,0x42,0x3C,0x00,0x00,0x00, /* "8" */
		    0x00,0x00,0x00,0x3C,0x42,0x42,0x42,0x46,0x3A,0x02,0x02,0x44,0x38,0x00,0x00,0x00, /* "9" */
		    0x00,0x00,0x00,0x00,0x00,0x00,0x06,0x06,0x00,0x00,0x00,0x06,0x06,0x00,0x00,0x00, /* ":" */
		    0x00,0x00,0x00,0x00,0x00,0x00,0x06,0x06,0x00,0x00,0x00,0x06,0x06,0x04,0x03,0x00, /* ";" */
		    0x00,0x00,0x00,0x02,0x04,0x08,0x10,0x20,0x10,0x08,0x04,0x02,0x00,0x00,0x00,0x00, /* "<" */
		    0x00,0x00,0x00,0x00,0x00,0x00,0x7E,0x00,0x00,0x7E,0x00,0x00,0x00,0x00,0x00,0x00, /* "=" */
		    0x00,0x00,0x00,0x20,0x10,0x08,0x04,0x02,0x04,0x08,0x10,0x20,0x00,0x00,0x00,0x00, /* ">" */
		    0x00,0x00,0x00,0x3C,0x42,0x42,0x04,0x08,0x08,0x00,0x08,0x08,0x00,0x00,0x00,0x00, /* "?" */
		    0x00,0x00,0x00,0x1C,0x22,0x4A,0x56,0x52,0x52,0x52,0x4C,0x22,0x1C,0x00,0x00,0x00, /* "@" */
		    0x00,0x00,0x00,0x18,0x24,0x42,0x42,0x42,0x7E,0x42,0x42,0x42,0x42,0x00,0x00,0x00, /* "A" */
		    0x00,0x00,0x00,0x7C,0x42,0x42,0x42,0x7C,0x42,0x42,0x42,0x42,0x7C,0x00,0x00,0x00, /* "B" */
		    0x00,0x00,0x00,0x3C,0x42,0x42,0x80,0x80,0x80,0x80,0x42,0x42,0x3C,0x00,0x00,0x00, /* "C" */
		    0x00,0x00,0x00,0x7C,0x42,0x42,0x42,0x42,0x42,0x42,0x42,0x42,0x7C,0x00,0x00,0x00, /* "D" */
		    0x00,0x00,0x00,0x7F,0x40,0x40,0x40,0x7C,0x40,0x40,0x40,0x40,0x7F,0x00,0x00,0x00, /* "E" */
		    0x00,0x00,0x00,0x7F,0x40,0x40,0x40,0x7C,0x40,0x40,0x40,0x40,0x40,0x00,0x00,0x00, /* "F" */
		    0x00,0x00,0x00,0x3C,0x42,0x42,0x80,0x80,0x8F,0x42,0x42,0x42,0x3C,0x00,0x00,0x00, /* "G" */
		    0x00,0x00,0x00,0x42,0x42,0x42,0x42,0x7E,0x42,0x42,0x42,0x42,0x42,0x00,0x00,0x00, /* "H" */
		    0x00,0x00,0x00,0x1C,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x1C,0x00,0x00,0x00, /* "I" */
		    0x00,0x00,0x00,0x0E,0x04,0x04,0x04,0x04,0x04,0x04,0x04,0x44,0x38,0x00,0x00,0x00, /* "J" */
		    0x00,0x00,0x00,0x42,0x44,0x48,0x50,0x60,0x50,0x48,0x44,0x42,0x42,0x00,0x00,0x00, /* "K" */
		    0x00,0x00,0x00,0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x7F,0x00,0x00,0x00, /* "L" */
		    0x00,0x00,0x00,0x63,0x63,0x55,0x55,0x55,0x49,0x49,0x49,0x41,0x41,0x00,0x00,0x00, /* "M" */
		    0x00,0x00,0x00,0x42,0x42,0x62,0x62,0x52,0x52,0x4A,0x4A,0x46,0x46,0x00,0x00,0x00, /* "N" */
		    0x00,0x00,0x00,0x3C,0x42,0x42,0x42,0x42,0x42,0x42,0x42,0x42,0x3C,0x00,0x00,0x00, /* "O" */
		    0x00,0x00,0x00,0x7C,0x42,0x42,0x42,0x7C,0x40,0x40,0x40,0x40,0x40,0x00,0x00,0x00, /* "P" */
		    0x00,0x00,0x00,0x3C,0x42,0x42,0x42,0x42,0x42,0x42,0x4A,0x44,0x3A,0x00,0x00,0x00, /* "Q" */
		    0x00,0x00,0x00,0x7C,0x42,0x42,0x42,0x7C,0x48,0x44,0x42,0x42,0x42,0x00,0x00,0x00, /* "R" */
		    0x00,0x00,0x00,0x3C,0x42,0x40,0x40,0x3C,0x02,0x02,0x42,0x42,0x3C,0x00,0x00,0x00, /* "S" */
		    0x00,0x00,0x00,0x7F,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x00,0x00,0x00, /* "T" */
		    0x00,0x00,0x00,0x42,0x42,0x42,0x42,0x42,0x42,0x42,0x42,0x42,0x3C,0x00,0x00,0x00, /* "U" */
		    0x00,0x00,0x00,0x42,0x42,0x42,0x42,0x42,0x24,0x24,0x18,0x18,0x18,0x00,0x00,0x00, /* "V" */
		    0x00,0x00,0x00,0x41,0x41,0x49,0x49,0x49,0x55,0x55,0x55,0x63,0x63,0x00,0x00,0x00, /* "W" */
		    0x00,0x00,0x00,0x42,0x24,0x24,0x18,0x18,0x18,0x18,0x24,0x24,0x42,0x00,0x00,0x00, /* "X" */
		    0x00,0x00,0x00,0x42,0x42,0x24,0x24,0x18,0x18,0x18,0x18,0x18,0x18,0x00,0x00,0x00, /* "Y" */
		    0x00,0x00,0x00,0x7F,0x02,0x04,0x08,0x10,0x10,0x20,0x40,0x40,0x7F,0x00,0x00,0x00, /* "Z" */
		    0x00,0x00,0x00,0x38,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x38,0x00,0x00,0x00, /* "[" */
		    0x00,0x00,0x00,0x00,0x40,0x20,0x10,0x08,0x04,0x02,0x01,0x00,0x00,0x00,0x00,0x00, /* "\" */
		    0x00,0x00,0x00,0x38,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x38,0x00,0x00,0x00, /* "]" */
		    0x00,0x00,0x00,0x08,0x14,0x22,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, /* "^" */
		    0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xFF, /* "_" */
		    0x00,0x04,0x02,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, /* "`" */
		    0x00,0x00,0x00,0x00,0x00,0x3C,0x02,0x3E,0x42,0x42,0x46,0x3A,0x00,0x00,0x00,0x00, /* "a" */
		    0x00,0x00,0x00,0x40,0x40,0x5C,0x62,0x42,0x42,0x42,0x62,0x5C,0x00,0x00,0x00,0x00, /* "b" */
		    0x00,0x00,0x00,0x00,0x00,0x1C,0x22,0x40,0x40,0x40,0x22,0x1C,0x00,0x00,0x00,0x00, /* "c" */
		    0x00,0x00,0x00,0x02,0x02,0x3A,0x46,0x42,0x42,0x42,0x46,0x3A,0x00,0x00,0x00,0x00, /* "d" */
		    0x00,0x00,0x00,0x00,0x00,0x3C,0x42,0x42,0x7E,0x40,0x42,0x3C,0x00,0x00,0x00,0x00, /* "e" */
		    0x00,0x00,0x00,0x1C,0x22,0x20,0x20,0x7C,0x20,0x20,0x20,0x20,0x00,0x00,0x00,0x00, /* "f" */
		    0x00,0x00,0x00,0x00,0x00,0x3A,0x46,0x42,0x42,0x42,0x46,0x3A,0x02,0x22,0x1C,0x00, /* "g" */
		    0x00,0x00,0x00,0x40,0x40,0x5C,0x62,0x42,0x42,0x42,0x42,0x42,0x00,0x00,0x00,0x00, /* "h" */
		    0x00,0x00,0x00,0x18,0x00,0x38,0x08,0x08,0x08,0x08,0x08,0x3E,0x00,0x00,0x00,0x00, /* "i" */
		    0x00,0x00,0x00,0x06,0x00,0x0E,0x02,0x02,0x02,0x02,0x02,0x02,0x22,0x22,0x1C,0x00, /* "j" */
		    0x00,0x00,0x00,0x40,0x40,0x44,0x48,0x50,0x60,0x50,0x48,0x44,0x00,0x00,0x00,0x00, /* "k" */
		    0x00,0x00,0x00,0x38,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x3E,0x00,0x00,0x00,0x00, /* "l" */
		    0x00,0x00,0x00,0x00,0x00,0x6C,0x52,0x52,0x52,0x52,0x52,0x52,0x00,0x00,0x00,0x00, /* "m" */
		    0x00,0x00,0x00,0x00,0x00,0x5C,0x62,0x42,0x42,0x42,0x42,0x42,0x00,0x00,0x00,0x00, /* "n" */
		    0x00,0x00,0x00,0x00,0x00,0x3C,0x42,0x42,0x42,0x42,0x42,0x3C,0x00,0x00,0x00,0x00, /* "o" */
		    0x00,0x00,0x00,0x00,0x00,0x5C,0x62,0x42,0x42,0x42,0x62,0x5C,0x40,0x40,0x40,0x00, /* "p" */
		    0x00,0x00,0x00,0x00,0x00,0x3A,0x46,0x42,0x42,0x42,0x46,0x3A,0x02,0x02,0x02,0x00, /* "q" */
		    0x00,0x00,0x00,0x00,0x00,0x5C,0x62,0x40,0x40,0x40,0x40,0x40,0x00,0x00,0x00,0x00, /* "r" */
		    0x00,0x00,0x00,0x00,0x00,0x3C,0x42,0x40,0x3C,0x02,0x42,0x3C,0x00,0x00,0x00,0x00, /* "s" */
		    0x00,0x00,0x00,0x00,0x20,0x7C,0x20,0x20,0x20,0x20,0x20,0x18,0x00,0x00,0x00,0x00, /* "t" */
		    0x00,0x00,0x00,0x00,0x00,0x42,0x42,0x42,0x42,0x42,0x44,0x3A,0x00,0x00,0x00,0x00, /* "u" */
		    0x00,0x00,0x00,0x00,0x00,0x42,0x42,0x42,0x24,0x24,0x18,0x18,0x00,0x00,0x00,0x00, /* "v" */
		    0x00,0x00,0x00,0x00,0x00,0x41,0x49,0x49,0x55,0x55,0x63,0x63,0x00,0x00,0x00,0x00, /* "w" */
		    0x00,0x00,0x00,0x00,0x00,0x42,0x24,0x18,0x18,0x18,0x24,0x42,0x00,0x00,0x00,0x00, /* "x" */
		    0x00,0x00,0x00,0x00,0x00,0x42,0x42,0x42,0x42,0x42,0x44,0x3A,0x02,0x22,0x1C,0x00, /* "y" */
		    0x00,0x00,0x00,0x00,0x00,0x7E,0x04,0x08,0x10,0x20,0x40,0x7E,0x00,0x00,0x00,0x00, /* "z" */
		    0x00,0x00,0x00,0x08,0x10,0x10,0x10,0x20,0x10,0x10,0x10,0x08,0x00,0x00,0x00,0x00, /* "{" */
		    0x00,0x00,0x00,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x08,0x00,0x00,0x00,0x00, /* "|" */
		    0x00,0x00,0x00,0x20,0x10,0x10,0x10,0x08,0x10,0x10,0x10,0x20,0x00,0x00,0x00,0x00, /* "}" */
		    0x00,0x00,0x00,0x00,0x14,0x2A,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00  /* "~" */
		};

main.h

C/C++
/* USER CODE BEGIN Header */
/**
  ******************************************************************************
  * @file           : main.h
  * @brief          : Header for main.c file.
  *                   This file contains the common defines of the application.
  ******************************************************************************
  * @attention
  *
  * Copyright (c) 2025 STMicroelectronics.
  * All rights reserved.
  *
  * This software is licensed under terms that can be found in the LICENSE file
  * in the root directory of this software component.
  * If no LICENSE file comes with this software, it is provided AS-IS.
  *
  ******************************************************************************
  */
/* USER CODE END Header */

/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H

#ifdef __cplusplus
extern "C" {
#endif

/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx_hal.h"

/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */

/* USER CODE END Includes */

/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */

/* USER CODE END ET */

/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */

/* USER CODE END EC */

/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */

/* USER CODE END EM */

void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);

/* Exported functions prototypes ---------------------------------------------*/
void Error_Handler(void);

/* USER CODE BEGIN EFP */

/* USER CODE END EFP */

/* Private defines -----------------------------------------------------------*/
#define GPIO_LCD_BL_Pin GPIO_PIN_9
#define GPIO_LCD_BL_GPIO_Port GPIOF
#define LED_Y_Pin GPIO_PIN_11
#define LED_Y_GPIO_Port GPIOF
#define GPIO_LCD_RST_Pin GPIO_PIN_3
#define GPIO_LCD_RST_GPIO_Port GPIOD
#define AHT_SCL_Pin GPIO_PIN_0
#define AHT_SCL_GPIO_Port GPIOE
#define AHT_SDA_Pin GPIO_PIN_1
#define AHT_SDA_GPIO_Port GPIOE

/* USER CODE BEGIN Private defines */

// --- LCD PINS ---
// Chip Select (CS) -> PF13
#define LCD_CS_Pin      GPIO_PIN_13
#define LCD_CS_GPIO_Port GPIOF

// Backlight (BL) -> PF9 (From your previous code)
#define LCD_BL_Pin      GPIO_PIN_9
#define LCD_BL_GPIO_Port GPIOF

// Reset (RST) -> PD3 (From your previous code)
#define LCD_RST_Pin     GPIO_PIN_3
#define LCD_RST_GPIO_Port GPIOD

// --- RGB MATRIX PINS ---
// Power Enable -> PF2
#define RGB_EN_Pin      GPIO_PIN_2
#define RGB_EN_GPIO_Port GPIOF

// --- AHT21 PINS ---
// Software I2C
#define AHT_SCL_Pin     GPIO_PIN_0
#define AHT_SCL_GPIO_Port GPIOE
#define AHT_SDA_Pin     GPIO_PIN_1
#define AHT_SDA_GPIO_Port GPIOE

// --- OTHER PINS ---
#define LED_BLINK_Pin   GPIO_PIN_11 // Yellow/Blue LED
#define LED_BLINK_GPIO_Port GPIOF

/* USER CODE END Private defines */

#ifdef __cplusplus
}
#endif

#endif /* __MAIN_H */

drv_lcd.h

C/C++
#ifndef __DRV_LCD_H
#define __DRV_LCD_H

#include "main.h"

/* LCD Colors */
#define WHITE       0xFFFF
#define BLACK       0x0000
#define BLUE        0x001F
#define RED         0xF800
#define GREEN       0x07E0
#define YELLOW      0xFFE0
#define GRAY        0X8430

/* LCD Parameter Structure */
typedef struct {
    uint16_t width;
    uint16_t height;
    uint16_t id;
    uint8_t  dir;
    uint16_t wramcmd;
    uint16_t setxcmd;
    uint16_t setycmd;
} _lcd_dev;

extern _lcd_dev lcddev;
extern uint16_t BACK_COLOR;
extern uint16_t FORE_COLOR;

/* Function Prototypes */
void LCD_Init(void);
void LCD_Clear(uint16_t color);
void LCD_DrawPixel(uint16_t x, uint16_t y, uint16_t color);
void LCD_ShowString(uint16_t x, uint16_t y, char *p, uint16_t color, uint16_t back_color);
void LCD_ShowChar(uint16_t x, uint16_t y, uint8_t num, uint16_t color, uint16_t back_color);

#endif

stm32f4xx_hal_conf.h

C/C++
/* USER CODE BEGIN Header */
/**
  ******************************************************************************
  * @file    stm32f4xx_hal_conf_template.h
  * @author  MCD Application Team
  * @brief   HAL configuration template file.
  *          This file should be copied to the application folder and renamed
  *          to stm32f4xx_hal_conf.h.
  ******************************************************************************
  * @attention
  *
  * Copyright (c) 2017 STMicroelectronics.
  * All rights reserved.
  *
  * This software is licensed under terms that can be found in the LICENSE file
  * in the root directory of this software component.
  * If no LICENSE file comes with this software, it is provided AS-IS.
  *
  ******************************************************************************
  */
/* USER CODE END Header */

/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F4xx_HAL_CONF_H
#define __STM32F4xx_HAL_CONF_H

#ifdef __cplusplus
 extern "C" {
#endif

/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/

/* ########################## Module Selection ############################## */
/**
  * @brief This is the list of modules to be used in the HAL driver
  */
#define HAL_MODULE_ENABLED

  /* #define HAL_CRYP_MODULE_ENABLED */
#define HAL_ADC_MODULE_ENABLED
/* #define HAL_CAN_MODULE_ENABLED */
/* #define HAL_CRC_MODULE_ENABLED */
/* #define HAL_CAN_LEGACY_MODULE_ENABLED */
/* #define HAL_DAC_MODULE_ENABLED */
/* #define HAL_DCMI_MODULE_ENABLED */
/* #define HAL_DMA2D_MODULE_ENABLED */
/* #define HAL_ETH_MODULE_ENABLED */
/* #define HAL_ETH_LEGACY_MODULE_ENABLED */
/* #define HAL_NAND_MODULE_ENABLED */
/* #define HAL_NOR_MODULE_ENABLED */
/* #define HAL_PCCARD_MODULE_ENABLED */
#define HAL_SRAM_MODULE_ENABLED
/* #define HAL_SDRAM_MODULE_ENABLED */
/* #define HAL_HASH_MODULE_ENABLED */
/* #define HAL_I2C_MODULE_ENABLED */
/* #define HAL_I2S_MODULE_ENABLED */
/* #define HAL_IWDG_MODULE_ENABLED */
/* #define HAL_LTDC_MODULE_ENABLED */
/* #define HAL_RNG_MODULE_ENABLED */
/* #define HAL_RTC_MODULE_ENABLED */
/* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */
/* #define HAL_MMC_MODULE_ENABLED */
/* #define HAL_SPI_MODULE_ENABLED */
#define HAL_TIM_MODULE_ENABLED
/* #define HAL_UART_MODULE_ENABLED */
/* #define HAL_USART_MODULE_ENABLED */
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_SMBUS_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
/* #define HAL_PCD_MODULE_ENABLED */
/* #define HAL_HCD_MODULE_ENABLED */
/* #define HAL_DSI_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
/* #define HAL_CEC_MODULE_ENABLED */
/* #define HAL_FMPI2C_MODULE_ENABLED */
/* #define HAL_FMPSMBUS_MODULE_ENABLED */
/* #define HAL_SPDIFRX_MODULE_ENABLED */
/* #define HAL_DFSDM_MODULE_ENABLED */
/* #define HAL_LPTIM_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED

/* ########################## HSE/HSI Values adaptation ##################### */
/**
  * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
  *        This value is used by the RCC HAL module to compute the system frequency
  *        (when HSE is used as system clock source, directly or through the PLL).
  */
#if !defined  (HSE_VALUE)
  #define HSE_VALUE    25000000U /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */

#if !defined  (HSE_STARTUP_TIMEOUT)
  #define HSE_STARTUP_TIMEOUT    100U   /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */

/**
  * @brief Internal High Speed oscillator (HSI) value.
  *        This value is used by the RCC HAL module to compute the system frequency
  *        (when HSI is used as system clock source, directly or through the PLL).
  */
#if !defined  (HSI_VALUE)
  #define HSI_VALUE    ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */

/**
  * @brief Internal Low Speed oscillator (LSI) value.
  */
#if !defined  (LSI_VALUE)
 #define LSI_VALUE  32000U       /*!< LSI Typical Value in Hz*/
#endif /* LSI_VALUE */                      /*!< Value of the Internal Low Speed oscillator in Hz
                                             The real value may vary depending on the variations
                                             in voltage and temperature.*/
/**
  * @brief External Low Speed oscillator (LSE) value.
  */
#if !defined  (LSE_VALUE)
 #define LSE_VALUE  32768U    /*!< Value of the External Low Speed oscillator in Hz */
#endif /* LSE_VALUE */

#if !defined  (LSE_STARTUP_TIMEOUT)
  #define LSE_STARTUP_TIMEOUT    5000U   /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */

/**
  * @brief External clock source for I2S peripheral
  *        This value is used by the I2S HAL module to compute the I2S clock source
  *        frequency, this source is inserted directly through I2S_CKIN pad.
  */
#if !defined  (EXTERNAL_CLOCK_VALUE)
  #define EXTERNAL_CLOCK_VALUE    12288000U /*!< Value of the External audio frequency in Hz*/
#endif /* EXTERNAL_CLOCK_VALUE */

/* Tip: To avoid modifying this file each time you need to use different HSE,
   ===  you can define the HSE value in your toolchain compiler preprocessor. */

/* ########################### System Configuration ######################### */
/**
  * @brief This is the HAL system configuration section
  */
#define  VDD_VALUE		      3300U /*!< Value of VDD in mv */
#define  TICK_INT_PRIORITY            15U   /*!< tick interrupt priority */
#define  USE_RTOS                     0U
#define  PREFETCH_ENABLE              1U
#define  INSTRUCTION_CACHE_ENABLE     1U
#define  DATA_CACHE_ENABLE            1U

#define  USE_HAL_ADC_REGISTER_CALLBACKS         0U /* ADC register callback disabled       */
#define  USE_HAL_CAN_REGISTER_CALLBACKS         0U /* CAN register callback disabled       */
#define  USE_HAL_CEC_REGISTER_CALLBACKS         0U /* CEC register callback disabled       */
#define  USE_HAL_CRYP_REGISTER_CALLBACKS        0U /* CRYP register callback disabled      */
#define  USE_HAL_DAC_REGISTER_CALLBACKS         0U /* DAC register callback disabled       */
#define  USE_HAL_DCMI_REGISTER_CALLBACKS        0U /* DCMI register callback disabled      */
#define  USE_HAL_DFSDM_REGISTER_CALLBACKS       0U /* DFSDM register callback disabled     */
#define  USE_HAL_DMA2D_REGISTER_CALLBACKS       0U /* DMA2D register callback disabled     */
#define  USE_HAL_DSI_REGISTER_CALLBACKS         0U /* DSI register callback disabled       */
#define  USE_HAL_ETH_REGISTER_CALLBACKS         0U /* ETH register callback disabled       */
#define  USE_HAL_HASH_REGISTER_CALLBACKS        0U /* HASH register callback disabled      */
#define  USE_HAL_HCD_REGISTER_CALLBACKS         0U /* HCD register callback disabled       */
#define  USE_HAL_I2C_REGISTER_CALLBACKS         0U /* I2C register callback disabled       */
#define  USE_HAL_FMPI2C_REGISTER_CALLBACKS      0U /* FMPI2C register callback disabled    */
#define  USE_HAL_FMPSMBUS_REGISTER_CALLBACKS    0U /* FMPSMBUS register callback disabled  */
#define  USE_HAL_I2S_REGISTER_CALLBACKS         0U /* I2S register callback disabled       */
#define  USE_HAL_IRDA_REGISTER_CALLBACKS        0U /* IRDA register callback disabled      */
#define  USE_HAL_LPTIM_REGISTER_CALLBACKS       0U /* LPTIM register callback disabled     */
#define  USE_HAL_LTDC_REGISTER_CALLBACKS        0U /* LTDC register callback disabled      */
#define  USE_HAL_MMC_REGISTER_CALLBACKS         0U /* MMC register callback disabled       */
#define  USE_HAL_NAND_REGISTER_CALLBACKS        0U /* NAND register callback disabled      */
#define  USE_HAL_NOR_REGISTER_CALLBACKS         0U /* NOR register callback disabled       */
#define  USE_HAL_PCCARD_REGISTER_CALLBACKS      0U /* PCCARD register callback disabled    */
#define  USE_HAL_PCD_REGISTER_CALLBACKS         0U /* PCD register callback disabled       */
#define  USE_HAL_QSPI_REGISTER_CALLBACKS        0U /* QSPI register callback disabled      */
#define  USE_HAL_RNG_REGISTER_CALLBACKS         0U /* RNG register callback disabled       */
#define  USE_HAL_RTC_REGISTER_CALLBACKS         0U /* RTC register callback disabled       */
#define  USE_HAL_SAI_REGISTER_CALLBACKS         0U /* SAI register callback disabled       */
#define  USE_HAL_SD_REGISTER_CALLBACKS          0U /* SD register callback disabled        */
#define  USE_HAL_SMARTCARD_REGISTER_CALLBACKS   0U /* SMARTCARD register callback disabled */
#define  USE_HAL_SDRAM_REGISTER_CALLBACKS       0U /* SDRAM register callback disabled     */
#define  USE_HAL_SRAM_REGISTER_CALLBACKS        0U /* SRAM register callback disabled      */
#define  USE_HAL_SPDIFRX_REGISTER_CALLBACKS     0U /* SPDIFRX register callback disabled   */
#define  USE_HAL_SMBUS_REGISTER_CALLBACKS       0U /* SMBUS register callback disabled     */
#define  USE_HAL_SPI_REGISTER_CALLBACKS         0U /* SPI register callback disabled       */
#define  USE_HAL_TIM_REGISTER_CALLBACKS         0U /* TIM register callback disabled       */
#define  USE_HAL_UART_REGISTER_CALLBACKS        0U /* UART register callback disabled      */
#define  USE_HAL_USART_REGISTER_CALLBACKS       0U /* USART register callback disabled     */
#define  USE_HAL_WWDG_REGISTER_CALLBACKS        0U /* WWDG register callback disabled      */

/* ########################## Assert Selection ############################## */
/**
  * @brief Uncomment the line below to expanse the "assert_param" macro in the
  *        HAL drivers code
  */
/* #define USE_FULL_ASSERT    1U */

/* ################## Ethernet peripheral configuration ##################### */

/* Section 1 : Ethernet peripheral configuration */

/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
#define MAC_ADDR0   2U
#define MAC_ADDR1   0U
#define MAC_ADDR2   0U
#define MAC_ADDR3   0U
#define MAC_ADDR4   0U
#define MAC_ADDR5   0U

/* Definition of the Ethernet driver buffers size and count */
#define ETH_RX_BUF_SIZE                ETH_MAX_PACKET_SIZE /* buffer size for receive               */
#define ETH_TX_BUF_SIZE                ETH_MAX_PACKET_SIZE /* buffer size for transmit              */
#define ETH_RXBUFNB                    4U       /* 4 Rx buffers of size ETH_RX_BUF_SIZE  */
#define ETH_TXBUFNB                    4U       /* 4 Tx buffers of size ETH_TX_BUF_SIZE  */

/* Section 2: PHY configuration section */

/* DP83848_PHY_ADDRESS Address*/
#define DP83848_PHY_ADDRESS
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
#define PHY_RESET_DELAY                 0x000000FFU
/* PHY Configuration delay */
#define PHY_CONFIG_DELAY                0x00000FFFU

#define PHY_READ_TO                     0x0000FFFFU
#define PHY_WRITE_TO                    0x0000FFFFU

/* Section 3: Common PHY Registers */

#define PHY_BCR                         ((uint16_t)0x0000U)    /*!< Transceiver Basic Control Register   */
#define PHY_BSR                         ((uint16_t)0x0001U)    /*!< Transceiver Basic Status Register    */

#define PHY_RESET                       ((uint16_t)0x8000U)  /*!< PHY Reset */
#define PHY_LOOPBACK                    ((uint16_t)0x4000U)  /*!< Select loop-back mode */
#define PHY_FULLDUPLEX_100M             ((uint16_t)0x2100U)  /*!< Set the full-duplex mode at 100 Mb/s */
#define PHY_HALFDUPLEX_100M             ((uint16_t)0x2000U)  /*!< Set the half-duplex mode at 100 Mb/s */
#define PHY_FULLDUPLEX_10M              ((uint16_t)0x0100U)  /*!< Set the full-duplex mode at 10 Mb/s  */
#define PHY_HALFDUPLEX_10M              ((uint16_t)0x0000U)  /*!< Set the half-duplex mode at 10 Mb/s  */
#define PHY_AUTONEGOTIATION             ((uint16_t)0x1000U)  /*!< Enable auto-negotiation function     */
#define PHY_RESTART_AUTONEGOTIATION     ((uint16_t)0x0200U)  /*!< Restart auto-negotiation function    */
#define PHY_POWERDOWN                   ((uint16_t)0x0800U)  /*!< Select the power down mode           */
#define PHY_ISOLATE                     ((uint16_t)0x0400U)  /*!< Isolate PHY from MII                 */

#define PHY_AUTONEGO_COMPLETE           ((uint16_t)0x0020U)  /*!< Auto-Negotiation process completed   */
#define PHY_LINKED_STATUS               ((uint16_t)0x0004U)  /*!< Valid link established               */
#define PHY_JABBER_DETECTION            ((uint16_t)0x0002U)  /*!< Jabber condition detected            */

/* Section 4: Extended PHY Registers */
#define PHY_SR                          ((uint16_t))    /*!< PHY status register Offset                      */

#define PHY_SPEED_STATUS                ((uint16_t))  /*!< PHY Speed mask                                  */
#define PHY_DUPLEX_STATUS               ((uint16_t))  /*!< PHY Duplex mask                                 */

/* ################## SPI peripheral configuration ########################## */

/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
* Activated: CRC code is present inside driver
* Deactivated: CRC code cleaned from driver
*/

#define USE_SPI_CRC                     0U

/* Includes ------------------------------------------------------------------*/
/**
  * @brief Include module's header file
  */

#ifdef HAL_RCC_MODULE_ENABLED
  #include "stm32f4xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */

#ifdef HAL_GPIO_MODULE_ENABLED
  #include "stm32f4xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */

#ifdef HAL_EXTI_MODULE_ENABLED
  #include "stm32f4xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */

#ifdef HAL_DMA_MODULE_ENABLED
  #include "stm32f4xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */

#ifdef HAL_CORTEX_MODULE_ENABLED
  #include "stm32f4xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */

#ifdef HAL_ADC_MODULE_ENABLED
  #include "stm32f4xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */

#ifdef HAL_CAN_MODULE_ENABLED
  #include "stm32f4xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */

#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
  #include "stm32f4xx_hal_can_legacy.h"
#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */

#ifdef HAL_CRC_MODULE_ENABLED
  #include "stm32f4xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */

#ifdef HAL_CRYP_MODULE_ENABLED
  #include "stm32f4xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */

#ifdef HAL_DMA2D_MODULE_ENABLED
  #include "stm32f4xx_hal_dma2d.h"
#endif /* HAL_DMA2D_MODULE_ENABLED */

#ifdef HAL_DAC_MODULE_ENABLED
  #include "stm32f4xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */

#ifdef HAL_DCMI_MODULE_ENABLED
  #include "stm32f4xx_hal_dcmi.h"
#endif /* HAL_DCMI_MODULE_ENABLED */

#ifdef HAL_ETH_MODULE_ENABLED
  #include "stm32f4xx_hal_eth.h"
#endif /* HAL_ETH_MODULE_ENABLED */

#ifdef HAL_ETH_LEGACY_MODULE_ENABLED
  #include "stm32f4xx_hal_eth_legacy.h"
#endif /* HAL_ETH_LEGACY_MODULE_ENABLED */

#ifdef HAL_FLASH_MODULE_ENABLED
  #include "stm32f4xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */

#ifdef HAL_SRAM_MODULE_ENABLED
  #include "stm32f4xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */

#ifdef HAL_NOR_MODULE_ENABLED
  #include "stm32f4xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */

#ifdef HAL_NAND_MODULE_ENABLED
  #include "stm32f4xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */

#ifdef HAL_PCCARD_MODULE_ENABLED
  #include "stm32f4xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */

#ifdef HAL_SDRAM_MODULE_ENABLED
  #include "stm32f4xx_hal_sdram.h"
#endif /* HAL_SDRAM_MODULE_ENABLED */

#ifdef HAL_HASH_MODULE_ENABLED
 #include "stm32f4xx_hal_hash.h"
#endif /* HAL_HASH_MODULE_ENABLED */

#ifdef HAL_I2C_MODULE_ENABLED
 #include "stm32f4xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */

#ifdef HAL_SMBUS_MODULE_ENABLED
 #include "stm32f4xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */

#ifdef HAL_I2S_MODULE_ENABLED
 #include "stm32f4xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */

#ifdef HAL_IWDG_MODULE_ENABLED
 #include "stm32f4xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */

#ifdef HAL_LTDC_MODULE_ENABLED
 #include "stm32f4xx_hal_ltdc.h"
#endif /* HAL_LTDC_MODULE_ENABLED */

#ifdef HAL_PWR_MODULE_ENABLED
 #include "stm32f4xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */

#ifdef HAL_RNG_MODULE_ENABLED
 #include "stm32f4xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */

#ifdef HAL_RTC_MODULE_ENABLED
 #include "stm32f4xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */

#ifdef HAL_SAI_MODULE_ENABLED
 #include "stm32f4xx_hal_sai.h"
#endif /* HAL_SAI_MODULE_ENABLED */

#ifdef HAL_SD_MODULE_ENABLED
 #include "stm32f4xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */

#ifdef HAL_SPI_MODULE_ENABLED
 #include "stm32f4xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */

#ifdef HAL_TIM_MODULE_ENABLED
 #include "stm32f4xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */

#ifdef HAL_UART_MODULE_ENABLED
 #include "stm32f4xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */

#ifdef HAL_USART_MODULE_ENABLED
 #include "stm32f4xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */

#ifdef HAL_IRDA_MODULE_ENABLED
 #include "stm32f4xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */

#ifdef HAL_SMARTCARD_MODULE_ENABLED
 #include "stm32f4xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */

#ifdef HAL_WWDG_MODULE_ENABLED
 #include "stm32f4xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */

#ifdef HAL_PCD_MODULE_ENABLED
 #include "stm32f4xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */

#ifdef HAL_HCD_MODULE_ENABLED
 #include "stm32f4xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */

#ifdef HAL_DSI_MODULE_ENABLED
 #include "stm32f4xx_hal_dsi.h"
#endif /* HAL_DSI_MODULE_ENABLED */

#ifdef HAL_QSPI_MODULE_ENABLED
 #include "stm32f4xx_hal_qspi.h"
#endif /* HAL_QSPI_MODULE_ENABLED */

#ifdef HAL_CEC_MODULE_ENABLED
 #include "stm32f4xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */

#ifdef HAL_FMPI2C_MODULE_ENABLED
 #include "stm32f4xx_hal_fmpi2c.h"
#endif /* HAL_FMPI2C_MODULE_ENABLED */

#ifdef HAL_FMPSMBUS_MODULE_ENABLED
 #include "stm32f4xx_hal_fmpsmbus.h"
#endif /* HAL_FMPSMBUS_MODULE_ENABLED */

#ifdef HAL_SPDIFRX_MODULE_ENABLED
 #include "stm32f4xx_hal_spdifrx.h"
#endif /* HAL_SPDIFRX_MODULE_ENABLED */

#ifdef HAL_DFSDM_MODULE_ENABLED
 #include "stm32f4xx_hal_dfsdm.h"
#endif /* HAL_DFSDM_MODULE_ENABLED */

#ifdef HAL_LPTIM_MODULE_ENABLED
 #include "stm32f4xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */

#ifdef HAL_MMC_MODULE_ENABLED
 #include "stm32f4xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */

/* Exported macro ------------------------------------------------------------*/
#ifdef  USE_FULL_ASSERT
/**
  * @brief  The assert_param macro is used for function's parameters check.
  * @param  expr If expr is false, it calls assert_failed function
  *         which reports the name of the source file and the source
  *         line number of the call that failed.
  *         If expr is true, it returns no value.
  * @retval None
  */
  #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
  void assert_failed(uint8_t* file, uint32_t line);
#else
  #define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */

#ifdef __cplusplus
}
#endif

#endif /* __STM32F4xx_HAL_CONF_H */

Credits

PRINCESS LAURON
3 projects • 1 follower
HEART LAHOYLAHOY
3 projects • 0 followers

Comments