From ab0da3c30baab6eb63e55217f2b4d5a719fb86e4 Mon Sep 17 00:00:00 2001 From: hathach Date: Sun, 19 Mar 2023 12:01:33 +0700 Subject: [PATCH] group stm32l0 --- .github/workflows/build_arm.yml | 2 +- hw/bsp/stm32l0/boards/stm32l052dap52/board.mk | 3 +- .../stm32l0538disco/STM32L053C8Tx_FLASH.ld | 0 .../boards/stm32l0538disco/board.h} | 147 ++------ .../stm32l0/boards/stm32l0538disco/board.mk | 14 + hw/bsp/stm32l0/family.c | 32 +- hw/bsp/stm32l0/family.mk | 13 +- hw/bsp/stm32l0/stm32l0xx_hal_conf.h | 90 +++-- hw/bsp/stm32l0538disco/board.mk | 54 --- hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h | 331 ------------------ 10 files changed, 130 insertions(+), 556 deletions(-) rename hw/bsp/{ => stm32l0/boards}/stm32l0538disco/STM32L053C8Tx_FLASH.ld (100%) rename hw/bsp/{stm32l0538disco/stm32l0538disco.c => stm32l0/boards/stm32l0538disco/board.h} (51%) create mode 100644 hw/bsp/stm32l0/boards/stm32l0538disco/board.mk delete mode 100644 hw/bsp/stm32l0538disco/board.mk delete mode 100644 hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h diff --git a/.github/workflows/build_arm.yml b/.github/workflows/build_arm.yml index 905cc4f9a..3abfd50a8 100644 --- a/.github/workflows/build_arm.yml +++ b/.github/workflows/build_arm.yml @@ -50,7 +50,7 @@ jobs: - 'stm32f7' - 'stm32g4 stm32wb' - 'stm32h7' - - 'stm32l4' + - 'stm32l0 stm32l4' - 'tm4c123 xmc4000' steps: - name: Setup Python diff --git a/hw/bsp/stm32l0/boards/stm32l052dap52/board.mk b/hw/bsp/stm32l0/boards/stm32l052dap52/board.mk index 84662344d..0b1348474 100644 --- a/hw/bsp/stm32l0/boards/stm32l052dap52/board.mk +++ b/hw/bsp/stm32l0/boards/stm32l052dap52/board.mk @@ -1,4 +1,5 @@ -CFLAGS += -DSTM32L052xx -DCFG_EXAMPLE_VIDEO_READONLY +CFLAGS += \ + -DSTM32L052xx LD_FILE = $(BOARD_PATH)/STM32L052K8Ux_FLASH.ld diff --git a/hw/bsp/stm32l0538disco/STM32L053C8Tx_FLASH.ld b/hw/bsp/stm32l0/boards/stm32l0538disco/STM32L053C8Tx_FLASH.ld similarity index 100% rename from hw/bsp/stm32l0538disco/STM32L053C8Tx_FLASH.ld rename to hw/bsp/stm32l0/boards/stm32l0538disco/STM32L053C8Tx_FLASH.ld diff --git a/hw/bsp/stm32l0538disco/stm32l0538disco.c b/hw/bsp/stm32l0/boards/stm32l0538disco/board.h similarity index 51% rename from hw/bsp/stm32l0538disco/stm32l0538disco.c rename to hw/bsp/stm32l0/boards/stm32l0538disco/board.h index 46f6f0ff6..0722e3102 100644 --- a/hw/bsp/stm32l0538disco/stm32l0538disco.c +++ b/hw/bsp/stm32l0/boards/stm32l0538disco/board.h @@ -1,7 +1,7 @@ /* * The MIT License (MIT) * - * Copyright (c) 2019 Ha Thach (tinyusb.org) + * Copyright (c) 2020, Ha Thach (tinyusb.org) * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -24,45 +24,35 @@ * This file is part of the TinyUSB stack. */ -#include "../board.h" -#include "stm32l0xx_hal.h" +#ifndef BOARD_H_ +#define BOARD_H_ -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void USB_IRQHandler(void) -{ - tud_int_handler(0); -} +#ifdef __cplusplus + extern "C" { +#endif -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ +// LED #define LED_PORT GPIOA #define LED_PIN GPIO_PIN_5 #define LED_STATE_ON 1 +// Button #define BUTTON_PORT GPIOA #define BUTTON_PIN GPIO_PIN_0 #define BUTTON_STATE_ACTIVE 1 -/** - * @brief System Clock Configuration - * The system Clock is configured as follow: - * HSI48 used as USB clock source - * - System Clock source = HSI - * - HSI Frequency(Hz) = 16000000 - * - SYSCLK(Hz) = 16000000 - * - HCLK(Hz) = 16000000 - * - AHB Prescaler = 1 - * - APB1 Prescaler = 1 - * - APB2 Prescaler = 1 - * - Flash Latency(WS) = 0 - * - Main regulator output voltage = Scale1 mode - * @param None - * @retval None - */ -static void SystemClock_Config(void) +// UART +//#define UART_DEV USART2 +//#define UART_CLK_EN __HAL_RCC_USART2_CLK_ENABLE +//#define UART_GPIO_PORT GPIOA +//#define UART_GPIO_AF GPIO_AF4_USART2 +//#define UART_TX_PIN GPIO_PIN_2 +//#define UART_RX_PIN GPIO_PIN_3 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_stm32l0_clock_init(void) { RCC_ClkInitTypeDef RCC_ClkInitStruct; RCC_OscInitTypeDef RCC_OscInitStruct; @@ -108,99 +98,12 @@ static void SystemClock_Config(void) HAL_RCCEx_CRSConfig (&RCC_CRSInitStruct); } -void board_init(void) +static inline void board_vbus_sense_init(void) { - SystemClock_Config(); +} -#if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); -#elif CFG_TUSB_OS == OPT_OS_FREERTOS - // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) - //NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY ); +#ifdef __cplusplus + } #endif - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - __HAL_RCC_GPIOA_CLK_ENABLE(); - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - board_led_write(false); - - // Button - //__HAL_RCC_GPIOA_CLK_ENABLE(); - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_PULLDOWN; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - // USB - /* Configure DM DP Pins */ - __HAL_RCC_GPIOA_CLK_ENABLE(); - GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Enable USB FS Clock */ - __HAL_RCC_USB_CLK_ENABLE(); -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -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 BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); -} - -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) buf; (void) len; - return 0; -} - -#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"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32l0/boards/stm32l0538disco/board.mk b/hw/bsp/stm32l0/boards/stm32l0538disco/board.mk new file mode 100644 index 000000000..deed519ba --- /dev/null +++ b/hw/bsp/stm32l0/boards/stm32l0538disco/board.mk @@ -0,0 +1,14 @@ +CFLAGS += \ + -DSTM32L053xx + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/STM32L053C8Tx_FLASH.ld + +SRC_S += \ + $(ST_CMSIS)/Source/Templates/gcc/startup_stm32l053xx.s + +# For flash-jlink target +JLINK_DEVICE = STM32L053R8 + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32l0/family.c b/hw/bsp/stm32l0/family.c index 6bce88b39..89749fb50 100644 --- a/hw/bsp/stm32l0/family.c +++ b/hw/bsp/stm32l0/family.c @@ -39,21 +39,14 @@ void USB_IRQHandler(void) //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ +#ifdef UART_DEV UART_HandleTypeDef UartHandle; +#endif void board_init(void) { board_stm32l0_clock_init(); - // Enable All GPIOs clocks - __HAL_RCC_GPIOA_CLK_ENABLE(); - __HAL_RCC_GPIOB_CLK_ENABLE(); - __HAL_RCC_GPIOC_CLK_ENABLE(); - __HAL_RCC_GPIOD_CLK_ENABLE(); - - // Enable UART Clock - UART_CLK_EN(); - #if CFG_TUSB_OS == OPT_OS_NONE // 1ms tick timer SysTick_Config(SystemCoreClock / 1000); @@ -66,6 +59,12 @@ void board_init(void) NVIC_SetPriority(USB_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); #endif + // Enable All GPIOs clocks + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + // LED GPIO_InitTypeDef GPIO_InitStruct; GPIO_InitStruct.Pin = LED_PIN; @@ -74,6 +73,8 @@ void board_init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + board_led_write(false); + // Button GPIO_InitStruct.Pin = BUTTON_PIN; GPIO_InitStruct.Mode = GPIO_MODE_INPUT; @@ -81,7 +82,10 @@ void board_init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - // Uart +#ifdef UART_DEV + // Enable UART Clock + UART_CLK_EN(); + GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; @@ -98,13 +102,14 @@ void board_init(void) UartHandle.Init.Mode = UART_MODE_TX_RX; UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; HAL_UART_Init(&UartHandle); +#endif // USB Pins // Configure USB DM and DP pins. This is optional, and maintained only for user guidance. GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); GPIO_InitStruct.Mode = GPIO_MODE_INPUT; GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); // USB Clock enable @@ -133,8 +138,13 @@ int board_uart_read(uint8_t* buf, int len) int board_uart_write(void const * buf, int len) { +#ifdef UART_DEV HAL_UART_Transmit(&UartHandle, (uint8_t*)(uintptr_t) buf, len, 0xffff); return len; +#else + (void) buf; (void) len; + return 0; +#endif } #if CFG_TUSB_OS == OPT_OS_NONE diff --git a/hw/bsp/stm32l0/family.mk b/hw/bsp/stm32l0/family.mk index 67a5c69b8..f069ae8f0 100644 --- a/hw/bsp/stm32l0/family.mk +++ b/hw/bsp/stm32l0/family.mk @@ -1,5 +1,8 @@ ST_FAMILY = l0 -DEPS_SUBMODULES += lib/CMSIS_5 hw/mcu/st/cmsis_device_$(ST_FAMILY) hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver +DEPS_SUBMODULES += \ + lib/CMSIS_5 \ + hw/mcu/st/cmsis_device_$(ST_FAMILY) \ + hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver @@ -17,8 +20,12 @@ CFLAGS += \ -DCFG_EXAMPLE_VIDEO_READONLY \ -DCFG_TUSB_MCU=OPT_MCU_STM32L0 -# suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=unused-parameter -Wno-error=redundant-decls -Wno-error=cast-align -Wno-error=maybe-uninitialized +# mcu driver cause following warnings +CFLAGS += \ + -Wno-error=unused-parameter \ + -Wno-error=redundant-decls \ + -Wno-error=cast-align \ + -Wno-error=maybe-uninitialized SRC_C += \ src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c \ diff --git a/hw/bsp/stm32l0/stm32l0xx_hal_conf.h b/hw/bsp/stm32l0/stm32l0xx_hal_conf.h index e3a131043..fd109bc8c 100644 --- a/hw/bsp/stm32l0/stm32l0xx_hal_conf.h +++ b/hw/bsp/stm32l0/stm32l0xx_hal_conf.h @@ -2,19 +2,41 @@ ****************************************************************************** * @file stm32l0xx_hal_conf.h * @author MCD Application Team - * @brief HAL configuration template file. - * This file should be copied to the application folder and renamed - * to stm32l0xx_hal_conf.h. + * @brief HAL configuration file. ****************************************************************************** - * @attention * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

+ * Copyright (c) 2016 STMicroelectronics International N.V. All rights reserved. * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF + * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, + * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * ****************************************************************************** */ @@ -35,35 +57,37 @@ * @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_CRC_MODULE_ENABLED */ -/*#define HAL_CRYP_MODULE_ENABLED */ -/*#define HAL_DAC_MODULE_ENABLED */ +// #define HAL_ADC_MODULE_ENABLED +/* #define HAL_COMP_MODULE_ENABLED */ +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ #define HAL_DMA_MODULE_ENABLED -/*#define HAL_FIREWALL_MODULE_ENABLED */ +/* #define HAL_FIREWALL_MODULE_ENABLED */ #define HAL_FLASH_MODULE_ENABLED #define HAL_GPIO_MODULE_ENABLED -/*#define HAL_I2C_MODULE_ENABLED */ -/*#define HAL_I2S_MODULE_ENABLED */ -/*#define HAL_IWDG_MODULE_ENABLED */ -/*#define HAL_LCD_MODULE_ENABLED */ -/*#define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_I2C_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LCD_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ #define HAL_PWR_MODULE_ENABLED #define HAL_RCC_MODULE_ENABLED -/*#define HAL_RNG_MODULE_ENABLED */ -/*#define HAL_RTC_MODULE_ENABLED */ -/*#define HAL_SPI_MODULE_ENABLED */ -/*#define HAL_TIM_MODULE_ENABLED */ -/*#define HAL_TSC_MODULE_ENABLED */ +//#define HAL_RNG_MODULE_ENABLED +/* #define HAL_RTC_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_IRDA_MODULE_ENABLED */ -/*#define HAL_SMARTCARD_MODULE_ENABLED */ -/*#define HAL_SMBUS_MODULE_ENABLED */ -/*#define HAL_WWDG_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_CORTEX_MODULE_ENABLED -#define HAL_PCD_MODULE_ENABLED +/* #define HAL_PCD_MODULE_ENABLED */ + /* ########################## Oscillator Values adaptation ####################*/ /** @@ -322,7 +346,7 @@ */ #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) /* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t* file, uint32_t line); + void assert_failed(uint8_t *file, uint32_t line); #else #define assert_param(expr) ((void)0U) #endif /* USE_FULL_ASSERT */ diff --git a/hw/bsp/stm32l0538disco/board.mk b/hw/bsp/stm32l0538disco/board.mk deleted file mode 100644 index 72e887adf..000000000 --- a/hw/bsp/stm32l0538disco/board.mk +++ /dev/null @@ -1,54 +0,0 @@ -ST_FAMILY = l0 -DEPS_SUBMODULES += lib/CMSIS_5 hw/mcu/st/cmsis_device_$(ST_FAMILY) hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m0plus \ - -mfloat-abi=soft \ - -nostdlib -nostartfiles \ - -DSTM32L053xx \ - -DCFG_EXAMPLE_MSC_READONLY \ - -DCFG_EXAMPLE_VIDEO_READONLY \ - -DCFG_TUSB_MCU=OPT_MCU_STM32L0 - -# mcu driver cause following warnings -CFLAGS += -Wno-error=unused-parameter -Wno-error=maybe-uninitialized -Wno-error=redundant-decls - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32L053C8Tx_FLASH.ld - -SRC_C += \ - src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc_ex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32l053xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For freeRTOS port source -FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/ARM_CM0 - -# For flash-jlink target -JLINK_DEVICE = STM32L053R8 - -# Path to STM32 Cube Programmer CLI, should be added into system path -STM32Prog = STM32_Programmer_CLI - -# flash target using on-board stlink -flash: $(BUILD)/$(PROJECT).elf - $(STM32Prog) --connect port=swd --write $< --go diff --git a/hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h b/hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h deleted file mode 100644 index a917214c3..000000000 --- a/hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h +++ /dev/null @@ -1,331 +0,0 @@ -/** - ****************************************************************************** - * @file stm32l0xx_hal_conf.h - * @author MCD Application Team - * @brief HAL configuration file. - ****************************************************************************** - * - * Copyright (c) 2016 STMicroelectronics International N.V. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted, provided that the following conditions are met: - * - * 1. Redistribution of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of other - * contributors to this software may be used to endorse or promote products - * derived from this software without specific written permission. - * 4. This software, including modifications and/or derivative works of this - * software, must execute solely and exclusively on microcontroller or - * microprocessor devices manufactured by or for STMicroelectronics. - * 5. Redistribution and use of this software other than as permitted under - * this license is void and will automatically terminate your rights under - * this license. - * - * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A - * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY - * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT - * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT - * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, - * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF - * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING - * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, - * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32L0xx_HAL_CONF_H -#define __STM32L0xx_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_CRC_MODULE_ENABLED */ -/* #define HAL_CRYP_MODULE_ENABLED */ -/* #define HAL_DAC_MODULE_ENABLED */ -#define HAL_DMA_MODULE_ENABLED -/* #define HAL_FIREWALL_MODULE_ENABLED */ -#define HAL_FLASH_MODULE_ENABLED -#define HAL_GPIO_MODULE_ENABLED -/* #define HAL_I2C_MODULE_ENABLED */ -/* #define HAL_I2S_MODULE_ENABLED */ -/* #define HAL_IWDG_MODULE_ENABLED */ -/* #define HAL_LCD_MODULE_ENABLED */ -/* #define HAL_LPTIM_MODULE_ENABLED */ -#define HAL_PWR_MODULE_ENABLED -#define HAL_RCC_MODULE_ENABLED -//#define HAL_RNG_MODULE_ENABLED -/* #define HAL_RTC_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_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_CORTEX_MODULE_ENABLED -/* #define HAL_PCD_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 ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSE_STARTUP_TIMEOUT) - #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ -#endif /* HSE_STARTUP_TIMEOUT */ - -/** - * @brief Internal Multiple Speed oscillator (MSI) default value. - * This value is the default MSI range value after Reset. - */ -#if !defined (MSI_VALUE) - #define MSI_VALUE ((uint32_t)2097152U) /*!< Value of the Internal oscillator in Hz*/ -#endif /* MSI_VALUE */ - -/** - * @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 High Speed oscillator for USB (HSI48) value. - */ -#if !defined (HSI48_VALUE) -#define HSI48_VALUE ((uint32_t)48000000U) /*!< Value of the Internal High Speed oscillator for USB in Hz. - The real value may vary depending on the variations - in voltage and temperature. */ -#endif /* HSI48_VALUE */ - -/** - * @brief Internal Low Speed oscillator (LSI) value. - */ -#if !defined (LSI_VALUE) - #define LSI_VALUE ((uint32_t)37000U) /*!< 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. - * This value is used by the UART, RTC HAL module to compute the system frequency - */ -#if !defined (LSE_VALUE) - #define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External oscillator in Hz*/ -#endif /* LSE_VALUE */ - -/** - * @brief Time out for LSE start up value in ms. - */ -#if !defined (LSE_STARTUP_TIMEOUT) - #define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */ -#endif /* LSE_STARTUP_TIMEOUT */ - - -/* 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 ((uint32_t)3300U) /*!< Value of VDD in mv */ -#define TICK_INT_PRIORITY ((uint32_t)0U) /*!< tick interrupt priority */ -#define USE_RTOS 0U -#define PREFETCH_ENABLE 1U -#define PREREAD_ENABLE 1U -#define BUFFER_CACHE_DISABLE 0U - -/* ########################## Assert Selection ############################## */ -/** - * @brief Uncomment the line below to expanse the "assert_param" macro in the - * HAL drivers code - */ -/* #define USE_FULL_ASSERT 1 */ - -/* ################## 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 - -/* Includes ------------------------------------------------------------------*/ -/** - * @brief Include module's header file - */ - -#ifdef HAL_RCC_MODULE_ENABLED - #include "stm32l0xx_hal_rcc.h" -#endif /* HAL_RCC_MODULE_ENABLED */ - -#ifdef HAL_GPIO_MODULE_ENABLED - #include "stm32l0xx_hal_gpio.h" -#endif /* HAL_GPIO_MODULE_ENABLED */ - -#ifdef HAL_DMA_MODULE_ENABLED - #include "stm32l0xx_hal_dma.h" -#endif /* HAL_DMA_MODULE_ENABLED */ - -#ifdef HAL_CORTEX_MODULE_ENABLED - #include "stm32l0xx_hal_cortex.h" -#endif /* HAL_CORTEX_MODULE_ENABLED */ - -#ifdef HAL_ADC_MODULE_ENABLED - #include "stm32l0xx_hal_adc.h" -#endif /* HAL_ADC_MODULE_ENABLED */ - -#ifdef HAL_COMP_MODULE_ENABLED - #include "stm32l0xx_hal_comp.h" -#endif /* HAL_COMP_MODULE_ENABLED */ - -#ifdef HAL_CRC_MODULE_ENABLED - #include "stm32l0xx_hal_crc.h" -#endif /* HAL_CRC_MODULE_ENABLED */ - -#ifdef HAL_CRYP_MODULE_ENABLED - #include "stm32l0xx_hal_cryp.h" -#endif /* HAL_CRYP_MODULE_ENABLED */ - -#ifdef HAL_DAC_MODULE_ENABLED - #include "stm32l0xx_hal_dac.h" -#endif /* HAL_DAC_MODULE_ENABLED */ - -#ifdef HAL_FIREWALL_MODULE_ENABLED - #include "stm32l0xx_hal_firewall.h" -#endif /* HAL_FIREWALL_MODULE_ENABLED */ - -#ifdef HAL_FLASH_MODULE_ENABLED - #include "stm32l0xx_hal_flash.h" -#endif /* HAL_FLASH_MODULE_ENABLED */ - -#ifdef HAL_I2C_MODULE_ENABLED - #include "stm32l0xx_hal_i2c.h" -#endif /* HAL_I2C_MODULE_ENABLED */ - -#ifdef HAL_I2S_MODULE_ENABLED - #include "stm32l0xx_hal_i2s.h" -#endif /* HAL_I2S_MODULE_ENABLED */ - -#ifdef HAL_IWDG_MODULE_ENABLED - #include "stm32l0xx_hal_iwdg.h" -#endif /* HAL_IWDG_MODULE_ENABLED */ - -#ifdef HAL_LCD_MODULE_ENABLED - #include "stm32l0xx_hal_lcd.h" -#endif /* HAL_LCD_MODULE_ENABLED */ - -#ifdef HAL_LPTIM_MODULE_ENABLED -#include "stm32l0xx_hal_lptim.h" -#endif /* HAL_LPTIM_MODULE_ENABLED */ - -#ifdef HAL_PWR_MODULE_ENABLED - #include "stm32l0xx_hal_pwr.h" -#endif /* HAL_PWR_MODULE_ENABLED */ - -#ifdef HAL_RNG_MODULE_ENABLED - #include "stm32l0xx_hal_rng.h" -#endif /* HAL_RNG_MODULE_ENABLED */ - -#ifdef HAL_RTC_MODULE_ENABLED - #include "stm32l0xx_hal_rtc.h" -#endif /* HAL_RTC_MODULE_ENABLED */ - -#ifdef HAL_SPI_MODULE_ENABLED - #include "stm32l0xx_hal_spi.h" -#endif /* HAL_SPI_MODULE_ENABLED */ - -#ifdef HAL_TIM_MODULE_ENABLED - #include "stm32l0xx_hal_tim.h" -#endif /* HAL_TIM_MODULE_ENABLED */ - -#ifdef HAL_TSC_MODULE_ENABLED - #include "stm32l0xx_hal_tsc.h" -#endif /* HAL_TSC_MODULE_ENABLED */ - -#ifdef HAL_UART_MODULE_ENABLED - #include "stm32l0xx_hal_uart.h" -#endif /* HAL_UART_MODULE_ENABLED */ - -#ifdef HAL_USART_MODULE_ENABLED - #include "stm32l0xx_hal_usart.h" -#endif /* HAL_USART_MODULE_ENABLED */ - -#ifdef HAL_IRDA_MODULE_ENABLED - #include "stm32l0xx_hal_irda.h" -#endif /* HAL_IRDA_MODULE_ENABLED */ - -#ifdef HAL_SMARTCARD_MODULE_ENABLED - #include "stm32l0xx_hal_smartcard.h" -#endif /* HAL_SMARTCARD_MODULE_ENABLED */ - -#ifdef HAL_SMBUS_MODULE_ENABLED - #include "stm32l0xx_hal_smbus.h" -#endif /* HAL_SMBUS_MODULE_ENABLED */ - -#ifdef HAL_WWDG_MODULE_ENABLED - #include "stm32l0xx_hal_wwdg.h" -#endif /* HAL_WWDG_MODULE_ENABLED */ - -#ifdef HAL_PCD_MODULE_ENABLED - #include "stm32l0xx_hal_pcd.h" -#endif /* HAL_PCD_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 /* __STM32L0xx_HAL_CONF_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/