Initial project setup

This commit is contained in:
2025-12-13 11:59:11 +02:00
commit 3218e6039f
2176 changed files with 355321 additions and 0 deletions

View File

@@ -0,0 +1,153 @@
/*
* FreeRTOS Kernel V10.0.0
* Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software. If you wish to use our Amazon
* FreeRTOS name, please do so in a fair use way that does not cause confusion.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/*-----------------------------------------------------------
* Application specific definitions.
*
* These definitions should be adjusted for your particular hardware and
* application requirements.
*
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
*
* See http://www.freertos.org/a00110.html.
*----------------------------------------------------------*/
// skip if included from IAR assembler
#ifndef __IASMARM__
#include "stm32wbaxx.h"
#endif
/* Cortex M23/M33 port configuration. */
#define configENABLE_MPU 0
#if defined(__ARM_FP) && __ARM_FP >= 4
#define configENABLE_FPU 1
#else
#define configENABLE_FPU 0
#endif
#define configENABLE_TRUSTZONE 0
#define configMINIMAL_SECURE_STACK_SIZE (1024)
#define configUSE_PREEMPTION 1
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
#define configCPU_CLOCK_HZ SystemCoreClock
#define configTICK_RATE_HZ ( 1000 )
#define configMAX_PRIORITIES ( 5 )
#define configMINIMAL_STACK_SIZE ( 128 )
#define configTOTAL_HEAP_SIZE ( configSUPPORT_DYNAMIC_ALLOCATION*4*1024 )
#define configMAX_TASK_NAME_LEN 16
#define configUSE_16_BIT_TICKS 0
#define configIDLE_SHOULD_YIELD 1
#define configUSE_MUTEXES 1
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_COUNTING_SEMAPHORES 1
#define configQUEUE_REGISTRY_SIZE 4
#define configUSE_QUEUE_SETS 0
#define configUSE_TIME_SLICING 0
#define configUSE_NEWLIB_REENTRANT 0
#define configENABLE_BACKWARD_COMPATIBILITY 1
#define configSTACK_ALLOCATION_FROM_SEPARATE_HEAP 0
#define configSUPPORT_STATIC_ALLOCATION 1
#define configSUPPORT_DYNAMIC_ALLOCATION 0
/* Hook function related definitions. */
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configUSE_MALLOC_FAILED_HOOK 0 // cause nested extern warning
#define configCHECK_FOR_STACK_OVERFLOW 2
#define configCHECK_HANDLER_INSTALLATION 0
/* Run time and task stats gathering related definitions. */
#define configGENERATE_RUN_TIME_STATS 0
#define configRECORD_STACK_HIGH_ADDRESS 1
#define configUSE_TRACE_FACILITY 1 // legacy trace
#define configUSE_STATS_FORMATTING_FUNCTIONS 0
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
#define configMAX_CO_ROUTINE_PRIORITIES 2
/* Software timer related definitions. */
#define configUSE_TIMERS 1
#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES-2)
#define configTIMER_QUEUE_LENGTH 32
#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE
/* Optional functions - most linkers will remove unused functions anyway. */
#define INCLUDE_vTaskPrioritySet 0
#define INCLUDE_uxTaskPriorityGet 0
#define INCLUDE_vTaskDelete 0
#define INCLUDE_vTaskSuspend 1 // required for queue, semaphore, mutex to be blocked indefinitely with portMAX_DELAY
#define INCLUDE_xResumeFromISR 0
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 0
#define INCLUDE_xTaskGetCurrentTaskHandle 1
#define INCLUDE_uxTaskGetStackHighWaterMark 0
#define INCLUDE_xTaskGetIdleTaskHandle 0
#define INCLUDE_xTimerGetTimerDaemonTaskHandle 0
#define INCLUDE_pcTaskGetTaskName 0
#define INCLUDE_eTaskGetState 0
#define INCLUDE_xEventGroupSetBitFromISR 0
#define INCLUDE_xTimerPendFunctionCall 0
/* FreeRTOS hooks to NVIC vectors */
#define xPortPendSVHandler PendSV_Handler
#define xPortSysTickHandler SysTick_Handler
#define vPortSVCHandler SVC_Handler
//--------------------------------------------------------------------+
// Interrupt nesting behavior configuration.
//--------------------------------------------------------------------+
// For Cortex-M specific: __NVIC_PRIO_BITS is defined in mcu header
#define configPRIO_BITS 4
/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY ((1<<configPRIO_BITS) - 1)
/* The highest interrupt priority that can be used by any interrupt service
routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
PRIORITY THAN THIS! (higher priorities are lower numeric values. */
#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 2
/* Interrupt priorities used by the kernel port layer itself. These are generic
to all Cortex-M ports, and do not rely on any particular library functions. */
#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
#endif

View File

@@ -0,0 +1,8 @@
set(MCU_VARIANT stm32wba65xx)
set(JLINK_DEVICE STM32WBA65RI)
function(update_board TARGET)
target_compile_definitions(${TARGET} PUBLIC
STM32WBA65xx
)
endfunction()

View File

@@ -0,0 +1,136 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2025, Dalton Caron
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
/* metadata:
name: STM32 NUCLEO-WBA65RI
url: https://www.st.com/en/evaluation-tools/nucleo-wba65ri.html
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
// LED (user LED 1)
#define LED_CLK_EN __HAL_RCC_GPIOD_CLK_ENABLE
#define LED_PORT GPIOD
#define LED_PIN GPIO_PIN_8
#define LED_STATE_ON 1
// Button (user button 1)
#define BUTTON_CLK_EN __HAL_RCC_GPIOC_CLK_ENABLE
#define BUTTON_PORT GPIOC
#define BUTTON_PIN GPIO_PIN_13
#define BUTTON_STATE_ACTIVE 0
// USART (on STM link USB connector)
#define USART_GPIO_CLK_EN __HAL_RCC_GPIOB_CLK_ENABLE(); __HAL_RCC_GPIOA_CLK_ENABLE
#define USART_DEV USART3
#define USART_CLK_EN __HAL_RCC_USART3_CLK_ENABLE
#define USART_TX_GPIO_PORT GPIOA
#define USART_RX_GPIO_PORT GPIOA
#define USART_GPIO_AF GPIO_AF8_USART3
#define USART_TX_PIN GPIO_PIN_7
#define USART_RX_PIN GPIO_PIN_5
// USB Pins
// These pints are only used for USB and must be in analog mode when not used.
// They are by default configured for USB operation after reset.
#define USB_DP_PORT GPIOD
#define USB_DP_PIN GPIO_PIN_6
#define USB_DM_PORT GPIOD
#define USB_DM_PIN GPIO_PIN_7
//--------------------------------------------------------------------+
// The system clock is configured as follows:
// System Clock source = PLL (HSE, crystal)
// SYSCLK (CPU Clock) = 64 MHz
// HCLK (AXI and AHB Clocks) = 64 MHz
// AHB Prescaler = 1
// APB1 Prescaler = 1 (APB3 Clock = 64MHz)
// APB2 Prescaler = 1 (APB1 Clock = 64MHz)
// APB7 Prescaler = 1 (APB2 Clock = 64MHz)
// HPRE5 Prescaler = 2 (AHB5 Clock = 32MHz)
// HSE Frequency (Hz) = 32 MHz
// PLL_M = 2
// PLL_N = 8
// PLL_P = 2
// PLL_Q = 2
// PLL_R = 2
// VDD (V) = 3.3 V
// Flash Latency = 1 Wait States
//--------------------------------------------------------------------+
static void board_system_clock_config( void )
{
RCC_OscInitTypeDef RCC_OscInitStruct = { 0 };
RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 };
__HAL_RCC_SYSCFG_CLK_ENABLE();
__HAL_RCC_PWR_CLK_ENABLE();
( void ) HAL_PWREx_ConfigSupply( PWR_LDO_SUPPLY );
// Must be in voltage scaling mode 1 for the OTG USB HS peripheral to function
( void ) HAL_PWREx_ControlVoltageScaling( PWR_REGULATOR_VOLTAGE_SCALE1 );
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.HSEDiv = RCC_HSE_DIV1;
RCC_OscInitStruct.PLL1.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL1.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL1.PLLM = 2;
RCC_OscInitStruct.PLL1.PLLN = 8;
RCC_OscInitStruct.PLL1.PLLP = 2;
RCC_OscInitStruct.PLL1.PLLQ = 2;
RCC_OscInitStruct.PLL1.PLLR = 2;
RCC_OscInitStruct.PLL1.PLLFractional = 0;
( void ) HAL_RCC_OscConfig( &RCC_OscInitStruct );
RCC_ClkInitStruct.ClockType = ( RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK
| RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2
| RCC_CLOCKTYPE_PCLK7 | RCC_CLOCKTYPE_HCLK5 );
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.APB7CLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.AHB5_PLL1_CLKDivider = RCC_SYSCLK_PLL1_DIV2;
RCC_ClkInitStruct.AHB5_HSEHSI_CLKDivider = RCC_SYSCLK_HSEHSI_DIV1;
( void ) HAL_RCC_ClockConfig( &RCC_ClkInitStruct, FLASH_LATENCY_1 );
( void ) SystemCoreClockUpdate();
( void ) HAL_ICACHE_Enable();
}
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@@ -0,0 +1,6 @@
MCU_VARIANT = stm32wba65xx
CFLAGS += -DSTM32WBA65xx
# For flash-jlink target
JLINK_DEVICE = STM32WBA65RI

View File

@@ -0,0 +1,216 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2025 Dalton Caron
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
/* metadata:
manufacturer: STMicroelectronics
*/
#include <stdbool.h>
#include "stm32wbaxx_hal.h"
#include "bsp/board_api.h"
#include "board.h"
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
#ifndef USART_TIMEOUT_TICKS
#define USART_TIMEOUT_TICKS 1000
#endif
static UART_HandleTypeDef uart_handle;
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void USB_OTG_HS_IRQHandler(void) {
tud_int_handler(0);
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
static void board_gpio_configuration(void) {
GPIO_InitTypeDef gpio_init = {0};
USART_GPIO_CLK_EN();
USART_CLK_EN();
// Configure USART TX pin
gpio_init.Pin = USART_TX_PIN;
gpio_init.Mode = GPIO_MODE_AF_PP;
gpio_init.Pull = GPIO_NOPULL;
gpio_init.Speed = GPIO_SPEED_FREQ_HIGH;
gpio_init.Alternate = USART_GPIO_AF;
HAL_GPIO_Init(USART_TX_GPIO_PORT, &gpio_init);
// Configure USART RX pin
gpio_init.Pin = USART_RX_PIN;
gpio_init.Mode = GPIO_MODE_AF_PP;
gpio_init.Pull = GPIO_PULLUP;
gpio_init.Speed = GPIO_SPEED_FREQ_HIGH;
gpio_init.Alternate = USART_GPIO_AF;
HAL_GPIO_Init(USART_RX_GPIO_PORT, &gpio_init);
// Configure the LED
LED_CLK_EN();
gpio_init.Pin = LED_PIN;
gpio_init.Mode = GPIO_MODE_OUTPUT_PP;
gpio_init.Pull = GPIO_PULLUP;
gpio_init.Speed = GPIO_SPEED_FREQ_LOW;
gpio_init.Alternate = 0;
HAL_GPIO_Init(LED_PORT, &gpio_init);
// Default LED state is off
board_led_write(false);
// Configure the button
BUTTON_CLK_EN();
gpio_init.Pin = BUTTON_PIN;
gpio_init.Mode = GPIO_MODE_INPUT;
gpio_init.Pull = GPIO_PULLUP;
gpio_init.Speed = GPIO_SPEED_FREQ_LOW;
gpio_init.Alternate = 0;
HAL_GPIO_Init(BUTTON_PORT, &gpio_init);
// Configure USB DM and DP pins. This is optional, and maintained only for user guidance.
gpio_init.Pin = (GPIO_PIN_7 | GPIO_PIN_6);
gpio_init.Mode = GPIO_MODE_INPUT;
gpio_init.Pull = GPIO_NOPULL;
gpio_init.Speed = GPIO_SPEED_FREQ_HIGH;
HAL_GPIO_Init(GPIOD, &gpio_init);
}
static void board_uart_configuration(void) {
uart_handle = ( UART_HandleTypeDef){
.Instance = USART_DEV,
.Init.BaudRate = CFG_BOARD_UART_BAUDRATE,
.Init.WordLength = UART_WORDLENGTH_8B,
.Init.StopBits = UART_STOPBITS_1,
.Init.Parity = UART_PARITY_NONE,
.Init.HwFlowCtl = UART_HWCONTROL_NONE,
.Init.Mode = UART_MODE_TX_RX,
.Init.OverSampling = UART_OVERSAMPLING_16
};
HAL_UART_Init(&uart_handle);
}
void board_init(void) {
board_system_clock_config();
board_gpio_configuration();
board_uart_configuration();
#ifdef USB_OTG_HS
// STM32WBA65/64/62 only has 1 USB HS port
#if CFG_TUSB_OS == OPT_OS_NONE
// 1ms tick timer
SysTick_Config(SystemCoreClock / 1000);
#elif CFG_TUSB_OS == OPT_OS_FREERTOS
// Explicitly disable systick to prevent its ISR runs before scheduler start
SysTick->CTRL &= ~1U;
// If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
NVIC_SetPriority(USB_OTG_HS_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY);
#endif
// USB clock enable
__HAL_RCC_USB_OTG_HS_CLK_ENABLE();
__HAL_RCC_USB_OTG_HS_PHY_CLK_ENABLE();
// See the reference manual section 11.4.7 for the USB OTG powering sequence
// Remove the VDDUSB power isolation
PWR->SVMCR |= PWR_SVMCR_USV;
// Enable VDD11USB supply by clearing VDD11USBDIS to 0
PWR->VOSR &= ~PWR_VOSR_VDD11USBDIS;
// Enable USB OTG internal power by setting USBPWREN to 1
PWR->VOSR |= PWR_VOSR_USBPWREN;
// Wait for VDD11USB supply to be ready in VDD11USBRDY = 1
while ((PWR->VOSR & PWR_VOSR_VDD11USBRDY) == 0) {}
// Enable USB OTG booster by setting USBBOOSTEN to 1
PWR->VOSR |= PWR_VOSR_USBBOOSTEN;
// Wait for USB OTG booster to be ready in USBBOOSTRDY = 1
while ((PWR->VOSR & PWR_VOSR_USBBOOSTRDY) == 0) {}
// Enable USB power on Pwrctrl CR2 register
PWR->SVMCR |= PWR_SVMCR_USV;
// Set the reference clock selection (must match the clock source)
SYSCFG->OTGHSPHYCR &= ~SYSCFG_OTGHSPHYCR_CLKSEL;
SYSCFG->OTGHSPHYCR |= SYSCFG_OTGHSPHYCR_CLKSEL_0 | SYSCFG_OTGHSPHYCR_CLKSEL_1 |
SYSCFG_OTGHSPHYCR_CLKSEL_3;// 32MHz clock
// Configuring the SYSCFG registers OTG_HS PHY
SYSCFG->OTGHSPHYCR |= SYSCFG_OTGHSPHYCR_EN;
// Disable VBUS sense (B device)
USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN;
// B-peripheral session valid override enable
USB_OTG_HS->GCCFG |= USB_OTG_GCCFG_VBVALEXTOEN;
USB_OTG_HS->GCCFG |= USB_OTG_GCCFG_VBVALOVAL;
#endif // USB_OTG_FS
}
void board_led_write(bool state) { HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1 - LED_STATE_ON)); }
uint32_t board_button_read(void) { return HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) == BUTTON_STATE_ACTIVE; }
int board_uart_read(uint8_t *buf, int len) {
(void) buf;
(void) len;
return 0;
}
int board_uart_write(void const *buf, int len) {
(void) HAL_UART_Transmit(&uart_handle, (const uint8_t *) buf, len, USART_TIMEOUT_TICKS);
return len;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void SysTick_Handler(void) {
HAL_IncTick();
system_ticks++;
}
uint32_t board_millis(void) { return system_ticks; }
#endif
void HardFault_Handler(void) { asm( "bkpt 1" ); }
// Required by __libc_init_array in startup code if we are compiling using -nostdlib/-nostartfiles.
void _init(void);
void _init(void) {}

View File

@@ -0,0 +1,134 @@
include_guard()
set(ST_FAMILY wba)
set(ST_PREFIX stm32${ST_FAMILY}xx)
set(ST_HAL_DRIVER ${TOP}/hw/mcu/st/stm32${ST_FAMILY}xx_hal_driver)
set(ST_CMSIS ${TOP}/hw/mcu/st/cmsis-device-${ST_FAMILY})
set(CMSIS_5 ${TOP}/lib/CMSIS_5)
# include board specific
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
# toolchain set up
set(CMAKE_SYSTEM_CPU cortex-m33 CACHE INTERNAL "System Processor")
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake)
set(FAMILY_MCUS STM32WBA CACHE INTERNAL "")
# ----------------------
# Port & Speed Selection
# ----------------------
set(RHPORT_DEVICE 0)
set(RHPORT_HOST 0)
# WBA65/64/62 has built-in HS PHY
set(RHPORT_DEVICE_SPEED OPT_MODE_HIGH_SPEED)
set(RHPORT_HOST_SPEED OPT_MODE_HIGH_SPEED)
#------------------------------------
# BOARD_TARGET
#------------------------------------
# only need to be built ONCE for all examples
function(add_board_target BOARD_TARGET)
if (TARGET ${BOARD_TARGET})
return()
endif()
# STM32WBA HAL uses uppercase MCU_VARIANT (excluding the x's) for linking and lowercase MCU_VARIANT for startup.
string(TOUPPER "${MCU_VARIANT}" UPPERCASE_MCU_VARIANT)
string(REGEX REPLACE "X" "x" UPPERCASE_MCU_VARIANT "${UPPERCASE_MCU_VARIANT}")
# Startup & Linker script
set(STARTUP_FILE_GNU ${ST_CMSIS}/Source/Templates/gcc/startup_${MCU_VARIANT}.s)
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
set(STARTUP_FILE_IAR ${ST_CMSIS}/Source/Templates/iar/startup_${MCU_VARIANT}.s)
set(LD_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/linker/${UPPERCASE_MCU_VARIANT}_FLASH_ns.ld)
set(LD_FILE_Clang ${LD_FILE_GNU})
set(LD_FILE_IAR ${ST_CMSIS}/Source/Templates/iar/linker/${MCU_VARIANT}_flash_ns.icf)
add_library(${BOARD_TARGET} STATIC
${ST_CMSIS}/Source/Templates/system_${ST_PREFIX}.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_cortex.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_icache.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_pwr.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_pwr_ex.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_rcc.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_rcc_ex.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_uart.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_gpio.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_pcd.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_pcd_ex.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_ll_usb.c
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
)
target_include_directories(${BOARD_TARGET} PUBLIC
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
${CMSIS_5}/CMSIS/Core/Include
${ST_CMSIS}/Include
${ST_HAL_DRIVER}/Inc
)
update_board(${BOARD_TARGET})
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--script=${LD_FILE_GNU}"
-nostartfiles
--specs=nosys.specs --specs=nano.specs
)
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--script=${LD_FILE_Clang}"
)
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--config=${LD_FILE_IAR}"
)
endif ()
endfunction()
#------------------------------------
# Functions
#------------------------------------
function(family_configure_example TARGET RTOS)
family_configure_common(${TARGET} ${RTOS})
target_compile_definitions(${TARGET} PUBLIC
CFG_TUSB_MCU=OPT_MCU_STM32WBA
)
# Board target
add_board_target(board_${BOARD})
#---------- Port Specific ----------
# These files are built for each example since it depends on example's tusb_config.h
target_sources(${TARGET} PUBLIC
# BSP
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
)
target_include_directories(${TARGET} PUBLIC
# family, hw, board
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
)
# Add TinyUSB target and port source
family_add_tinyusb(${TARGET} OPT_MCU_STM32WBA)
target_sources(${TARGET} PUBLIC
${TOP}/src/portable/synopsys/dwc2/dcd_dwc2.c
${TOP}/src/portable/synopsys/dwc2/hcd_dwc2.c
${TOP}/src/portable/synopsys/dwc2/dwc2_common.c
)
target_link_libraries(${TARGET} PUBLIC board_${BOARD})
# Flashing
family_add_bin_hex(${TARGET})
family_flash_stlink(${TARGET})
family_flash_jlink(${TARGET})
endfunction()

View File

@@ -0,0 +1,59 @@
UF2_FAMILY_ID = 0x70d16657
ST_FAMILY = wba
ST_PREFIX = stm32${ST_FAMILY}xx
ST_CMSIS = hw/mcu/st/cmsis-device-$(ST_FAMILY)
ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
include $(TOP)/$(BOARD_PATH)/board.mk
CPU_CORE ?= cortex-m33
CFLAGS += \
-DCFG_TUSB_MCU=OPT_MCU_STM32WBA
CFLAGS_GCC += \
-flto \
-Wno-error=cast-align -Wno-unused-parameter
LDFLAGS_GCC += \
-nostdlib -nostartfiles \
-specs=nosys.specs -specs=nano.specs -Wl,--gc-sections
SRC_C += \
src/portable/synopsys/dwc2/dcd_dwc2.c \
src/portable/synopsys/dwc2/hcd_dwc2.c \
src/portable/synopsys/dwc2/dwc2_common.c \
$(ST_CMSIS)/Source/Templates/system_${ST_PREFIX}.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_cortex.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_icache.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_pwr.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_pwr_ex.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_rcc.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_rcc_ex.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_uart.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_gpio.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_pcd.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_hal_pcd_ex.c \
$(ST_HAL_DRIVER)/Src/${ST_PREFIX}_ll_usb.c
INC += \
$(TOP)/$(BOARD_PATH) \
$(TOP)/$(BOARD_PATH)/include \
$(TOP)/lib/CMSIS_5/CMSIS/Core/Include \
$(TOP)/$(ST_CMSIS)/Include \
$(TOP)/$(ST_HAL_DRIVER)/Inc
# STM32WBA HAL uses uppercase MCU_VARIANT (excluding the x's) for linking and lowercase MCU_VARIANT for startup.
UPPERCASE_MCU_VARIANT = $(subst XX,xx,$(call to_upper,$(MCU_VARIANT)))
# Startup - Manually specify lowercase version for startup file
SRC_S_GCC += $(ST_CMSIS)/Source/Templates/gcc/startup_$(MCU_VARIANT).s
SRC_S_IAR += $(ST_CMSIS)/Source/Templates/iar/startup_$(MCU_VARIANT).s
# Linker
LD_FILE_GCC ?= ${FAMILY_PATH}/linker/${UPPERCASE_MCU_VARIANT}_FLASH_ns.ld
LD_FILE_IAR ?= $(ST_CMSIS)/Source/Templates/iar/linker/$(MCU_VARIANT)_flash_ns.icf
# flash target using on-board stlink
flash: flash-stlink

View File

@@ -0,0 +1,188 @@
/*
******************************************************************************
**
** File : LinkerScript.ld
**
** Author : STM32CubeIDE
**
** Abstract : Linker script for STM32WBA65xx Device from STM32WBA series
** 2048Kbytes FLASH
** 512Kbytes RAM
**
** Set heap size, stack size and stack location according
** to application requirements.
**
** Set memory bank area and size if external memory is used
**
** Target : STMicroelectronics STM32
**
** Distribution: The file is distributed as is, without any warranty
** of any kind.
**
******************************************************************************
** @attention
**
** Copyright (c) 2024 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.
**
******************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
_Min_Heap_Size = 0x200; /* required amount of heap */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Memories definition */
MEMORY
{
RAM (xrw) : ORIGIN = 0x20038000, LENGTH = 224K
RAM2 (xrw) : ORIGIN = 0x20078000, LENGTH = 32K
FLASH (rx) : ORIGIN = 0x08100000, LENGTH = 1024K
}
/* Highest address of the user mode stack */
_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
/* Sections */
SECTIONS
{
/* The startup code into "FLASH" Rom type memory */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* The program code and other data into "FLASH" Rom type memory */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH
/* Constant data into "FLASH" Rom type memory */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >FLASH
.ARM.extab :
{
. = ALIGN(4);
*(.ARM.extab* .gnu.linkonce.armextab.*)
. = ALIGN(4);
} >FLASH
.ARM :
{
. = ALIGN(4);
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
. = ALIGN(4);
} >FLASH
.preinit_array :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(4);
} >FLASH
.init_array :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(4);
} >FLASH
.fini_array :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
. = ALIGN(4);
} >FLASH
/* Used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections into "RAM" Ram type memory */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
*(.RamFunc) /* .RamFunc sections */
*(.RamFunc*) /* .RamFunc* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section into "RAM" Ram type memory */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
._user_heap_stack :
{
. = ALIGN(8);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(8);
} >RAM
/* Remove information from the compiler libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

View File

@@ -0,0 +1,367 @@
/**
******************************************************************************
* @file stm32wbaxx_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 stm32wbaxx_hal_conf.h.
******************************************************************************
* @attention
*
* Copyright (c) 2022 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef STM32WBAxx_HAL_CONF_H
#define STM32WBAxx_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_ADC_MODULE_ENABLED
// #define HAL_COMP_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
// #define HAL_CRC_MODULE_ENABLED
// #define HAL_CRYP_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_GTZC_MODULE_ENABLED
#define HAL_HASH_MODULE_ENABLED
#define HAL_HCD_MODULE_ENABLED
#define HAL_HSEM_MODULE_ENABLED
// #define HAL_I2C_MODULE_ENABLED
#define HAL_ICACHE_MODULE_ENABLED
// #define HAL_IRDA_MODULE_ENABLED
// #define HAL_IWDG_MODULE_ENABLED
// #define HAL_LPTIM_MODULE_ENABLED
#define HAL_PCD_MODULE_ENABLED
// #define HAL_PKA_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_RAMCFG_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
// #define HAL_RNG_MODULE_ENABLED
// #define HAL_RTC_MODULE_ENABLED
// #define HAL_SAI_MODULE_ENABLED
// #define HAL_SMARTCARD_MODULE_ENABLED
// #define HAL_SMBUS_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
// #define HAL_TSC_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
// #define HAL_WWDG_MODULE_ENABLED
// #define HAL_XSPI_MODULE_ENABLED
/* ########################## Oscillator 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 32000000UL /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT 100UL /*!< 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 16000000UL /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#define LSI_VALUE 32000UL /*!< 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.*/
#if defined (RCC_LSI2_SUPPORT)
#if !defined (LSI2_VALUE)
#define LSI2_VALUE 32000UL /*!< LSI2 Typical Value in Hz*/
#endif /* LSI2_VALUE */
#endif
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE 32768UL /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT 5000UL /*!< Time out for LSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for SAI1 peripheral
* This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source
* frequency.
*/
#if !defined (EXTERNAL_SAI1_CLOCK_VALUE)
#define EXTERNAL_SAI1_CLOCK_VALUE 48000UL /*!< Value of the SAI1 External clock source in Hz*/
#endif /* EXTERNAL_SAI1_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 3300UL /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((1UL<<__NVIC_PRIO_BITS) - 1UL) /*!< tick interrupt priority (lowest by default) */
#define USE_RTOS 0U
#define PREFETCH_ENABLE 1U /*!< Enable prefetch */
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* ################## Register callback feature configuration ############### */
/**
* @brief Set below the peripheral configuration to "1U" to add the support
* of HAL callback registration/unregistration feature for the HAL
* driver(s). This allows user application to provide specific callback
* functions thanks to HAL_PPP_RegisterCallback() rather than overwriting
* the default weak callback functions (see each stm32wbaxx_hal_ppp.h file
* for possible callback identifiers defined in HAL_PPP_CallbackIDTypeDef
* for each PPP peripheral).
*/
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP 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_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
#define USE_HAL_IWDG_REGISTER_CALLBACKS 0U /* IWDG register callback disabled */
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
#define USE_HAL_PKA_REGISTER_CALLBACKS 0U /* PKA register callback disabled */
#define USE_HAL_RAMCFG_REGISTER_CALLBACKS 0U /* RAMCFG 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_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD 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_TSC_REGISTER_CALLBACKS 0U /* TSC 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 */
#define USE_HAL_XSPI_REGISTER_CALLBACKS 0U /* XSPI register callback disabled */
/* ################## 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 1U
/* ################## CRYP peripheral configuration ########################## */
#define USE_HAL_CRYP_SUSPEND_RESUME 0U
/* ################## HASH peripheral configuration ########################## */
#define USE_HAL_HASH_SUSPEND_RESUME 0U
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32wbaxx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32wbaxx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32wbaxx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32wbaxx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32wbaxx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32wbaxx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32wbaxx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32wbaxx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32wbaxx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32wbaxx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_GTZC_MODULE_ENABLED
#include "stm32wbaxx_hal_gtzc.h"
#endif /* HAL_GTZC_MODULE_ENABLED */
#ifdef HAL_HASH_MODULE_ENABLED
#include "stm32wbaxx_hal_hash.h"
#endif /* HAL_HASH_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32wbaxx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
#ifdef HAL_HSEM_MODULE_ENABLED
#include "stm32wbaxx_hal_hsem.h"
#endif /* HAL_HSEM_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32wbaxx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_ICACHE_MODULE_ENABLED
#include "stm32wbaxx_hal_icache.h"
#endif /* HAL_ICACHE_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32wbaxx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32wbaxx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32wbaxx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32wbaxx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_PKA_MODULE_ENABLED
#include "stm32wbaxx_hal_pka.h"
#endif /* HAL_PKA_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32wbaxx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RAMCFG_MODULE_ENABLED
#include "stm32wbaxx_hal_ramcfg.h"
#endif /* HAL_RAMCFG_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32wbaxx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32wbaxx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SAI_MODULE_ENABLED
#include "stm32wbaxx_hal_sai.h"
#endif /* HAL_SAI_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32wbaxx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32wbaxx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32wbaxx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32wbaxx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_TSC_MODULE_ENABLED
#include "stm32wbaxx_hal_tsc.h"
#endif /* HAL_TSC_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32wbaxx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32wbaxx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32wbaxx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_XSPI_MODULE_ENABLED
#include "stm32wbaxx_hal_xspi.h"
#endif /* HAL_XSPI_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 /* STM32WBAxx_HAL_CONF_H */