Skip to content

Commit

Permalink
Source file re-arrangement for better separation of MCU types (#12268)
Browse files Browse the repository at this point in the history
Source file re-arrangement for better spearation of MCU types

- Move STM32 specific files to drivers/stm32
  • Loading branch information
blckmn committed Feb 1, 2023
1 parent a3b7d74 commit 33a96bb
Show file tree
Hide file tree
Showing 79 changed files with 538 additions and 486 deletions.
28 changes: 14 additions & 14 deletions make/mcu/STM32F4.mk
Original file line number Diff line number Diff line change
Expand Up @@ -143,29 +143,29 @@ MCU_FLASH_SIZE := 512
else
$(error Unknown MCU for F4 target)
endif
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32

MCU_COMMON_SRC = \
startup/system_stm32f4xx.c \
drivers/accgyro/accgyro_mpu.c \
drivers/adc_stm32f4xx.c \
drivers/bus_i2c_stm32f4xx.c \
drivers/bus_spi_stdperiph.c \
drivers/dma_stm32f4xx.c \
drivers/stm32/adc_stm32f4xx.c \
drivers/stm32/bus_i2c_stm32f4xx.c \
drivers/stm32/bus_spi_stdperiph.c \
drivers/stm32/dma_stm32f4xx.c \
drivers/dshot_bitbang.c \
drivers/dshot_bitbang_decode.c \
drivers/dshot_bitbang_stdperiph.c \
drivers/stm32/dshot_bitbang_stdperiph.c \
drivers/inverter.c \
drivers/light_ws2811strip_stdperiph.c \
drivers/transponder_ir_io_stdperiph.c \
drivers/stm32/light_ws2811strip_stdperiph.c \
drivers/stm32/transponder_ir_io_stdperiph.c \
drivers/pwm_output_dshot.c \
drivers/pwm_output_dshot_shared.c \
drivers/serial_uart_stdperiph.c \
drivers/serial_uart_stm32f4xx.c \
drivers/system_stm32f4xx.c \
drivers/timer_stm32f4xx.c \
drivers/stm32/serial_uart_stdperiph.c \
drivers/stm32/serial_uart_stm32f4xx.c \
drivers/stm32/system_stm32f4xx.c \
drivers/stm32/timer_stm32f4xx.c \
drivers/persistent.c \
drivers/sdio_f4xx.c
drivers/stm32/sdio_f4xx.c

ifeq ($(PERIPH_DRIVER), HAL)
VCP_SRC = \
Expand All @@ -187,7 +187,7 @@ endif

MSC_SRC = \
drivers/usb_msc_common.c \
drivers/usb_msc_f4xx.c \
drivers/stm32/usb_msc_f4xx.c \
msc/usbd_msc_desc.c \
msc/usbd_storage.c \
msc/usbd_storage_emfat.c \
Expand Down
36 changes: 18 additions & 18 deletions make/mcu/STM32F7.mk
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ OPTIMISE_SPEED = -O2
else
$(error Unknown MCU for F7 target)
endif
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32

VCP_SRC = \
vcp_hal/usbd_desc.c \
Expand All @@ -157,35 +157,35 @@ VCP_SRC = \
MCU_COMMON_SRC = \
startup/system_stm32f7xx.c \
drivers/accgyro/accgyro_mpu.c \
drivers/adc_stm32f7xx.c \
drivers/audio_stm32f7xx.c \
drivers/bus_i2c_hal.c \
drivers/bus_i2c_hal_init.c \
drivers/stm32/adc_stm32f7xx.c \
drivers/stm32/audio_stm32f7xx.c \
drivers/stm32/bus_i2c_hal.c \
drivers/stm32/bus_i2c_hal_init.c \
drivers/bus_i2c_timing.c \
drivers/dma_stm32f7xx.c \
drivers/light_ws2811strip_hal.c \
drivers/transponder_ir_io_hal.c \
drivers/bus_spi_ll.c \
drivers/stm32/dma_stm32f7xx.c \
drivers/stm32/light_ws2811strip_hal.c \
drivers/stm32/transponder_ir_io_hal.c \
drivers/stm32/bus_spi_ll.c \
drivers/persistent.c \
drivers/dshot_bitbang.c \
drivers/dshot_bitbang_decode.c \
drivers/dshot_bitbang_ll.c \
drivers/pwm_output_dshot_hal.c \
drivers/stm32/dshot_bitbang_ll.c \
drivers/stm32/pwm_output_dshot_hal.c \
drivers/pwm_output_dshot_shared.c \
drivers/timer_hal.c \
drivers/timer_stm32f7xx.c \
drivers/system_stm32f7xx.c \
drivers/serial_uart_hal.c \
drivers/serial_uart_stm32f7xx.c \
drivers/sdio_f7xx.c
drivers/stm32/timer_hal.c \
drivers/stm32/timer_stm32f7xx.c \
drivers/stm32/system_stm32f7xx.c \
drivers/stm32/serial_uart_hal.c \
drivers/stm32/serial_uart_stm32f7xx.c \
drivers/stm32/sdio_f7xx.c

MCU_EXCLUDES = \
drivers/bus_i2c.c \
drivers/timer.c

MSC_SRC = \
drivers/usb_msc_common.c \
drivers/usb_msc_f7xx.c \
drivers/stm32/usb_msc_f7xx.c \
msc/usbd_storage.c \
msc/usbd_storage_emfat.c \
msc/emfat.c \
Expand Down
36 changes: 18 additions & 18 deletions make/mcu/STM32G4.mk
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ OPTIMISE_SPEED = -O2
else
$(error Unknown MCU for G4 target)
endif
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32

VCP_SRC = \
vcp_hal/usbd_desc.c \
Expand All @@ -143,27 +143,27 @@ VCP_SRC = \

MCU_COMMON_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/adc_stm32g4xx.c \
drivers/bus_i2c_hal.c \
drivers/bus_i2c_hal_init.c \
drivers/stm32/adc_stm32g4xx.c \
drivers/stm32/bus_i2c_hal.c \
drivers/stm32/bus_i2c_hal_init.c \
drivers/bus_i2c_timing.c \
drivers/bus_spi_ll.c \
drivers/dma_stm32g4xx.c \
drivers/stm32/bus_spi_ll.c \
drivers/stm32/dma_stm32g4xx.c \
drivers/dshot_bitbang.c \
drivers/dshot_bitbang_decode.c \
drivers/dshot_bitbang_ll.c \
drivers/light_ws2811strip_hal.c \
drivers/memprot_hal.c \
drivers/memprot_stm32g4xx.c \
drivers/stm32/dshot_bitbang_ll.c \
drivers/stm32/light_ws2811strip_hal.c \
drivers/stm32/memprot_hal.c \
drivers/stm32/memprot_stm32g4xx.c \
drivers/persistent.c \
drivers/pwm_output_dshot_shared.c \
drivers/pwm_output_dshot_hal.c \
drivers/timer_hal.c \
drivers/timer_stm32g4xx.c \
drivers/transponder_ir_io_hal.c \
drivers/system_stm32g4xx.c \
drivers/serial_uart_stm32g4xx.c \
drivers/serial_uart_hal.c \
drivers/stm32/pwm_output_dshot_hal.c \
drivers/stm32/timer_hal.c \
drivers/stm32/timer_stm32g4xx.c \
drivers/stm32/transponder_ir_io_hal.c \
drivers/stm32/system_stm32g4xx.c \
drivers/stm32/serial_uart_stm32g4xx.c \
drivers/stm32/serial_uart_hal.c \
startup/system_stm32g4xx.c

MCU_EXCLUDES = \
Expand All @@ -173,7 +173,7 @@ MCU_EXCLUDES = \
# G4's MSC use the same driver layer file with F7
MSC_SRC = \
drivers/usb_msc_common.c \
drivers/usb_msc_f7xx.c \
drivers/stm32/usb_msc_f7xx.c \
msc/usbd_storage.c \
msc/usbd_storage_emfat.c \
msc/emfat.c \
Expand Down
44 changes: 22 additions & 22 deletions make/mcu/STM32H7.mk
Original file line number Diff line number Diff line change
Expand Up @@ -271,7 +271,7 @@ ifneq ($(FIRMWARE_SIZE),)
DEVICE_FLAGS += -DFIRMWARE_SIZE=$(FIRMWARE_SIZE)
endif

DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DHSE_STARTUP_TIMEOUT=1000
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DHSE_STARTUP_TIMEOUT=1000 -DSTM32

VCP_SRC = \
vcp_hal/usbd_desc.c \
Expand All @@ -283,31 +283,31 @@ VCP_SRC = \

MCU_COMMON_SRC = \
startup/system_stm32h7xx.c \
drivers/system_stm32h7xx.c \
drivers/timer_hal.c \
drivers/timer_stm32h7xx.c \
drivers/serial_uart_hal.c \
drivers/serial_uart_stm32h7xx.c \
drivers/bus_quadspi_hal.c \
drivers/bus_spi_ll.c \
drivers/dma_stm32h7xx.c \
drivers/stm32/system_stm32h7xx.c \
drivers/stm32/timer_hal.c \
drivers/stm32/timer_stm32h7xx.c \
drivers/stm32/serial_uart_hal.c \
drivers/stm32/serial_uart_stm32h7xx.c \
drivers/stm32/bus_quadspi_hal.c \
drivers/stm32/bus_spi_ll.c \
drivers/stm32/dma_stm32h7xx.c \
drivers/dshot_bitbang.c \
drivers/dshot_bitbang_decode.c \
drivers/dshot_bitbang_ll.c \
drivers/light_ws2811strip_hal.c \
drivers/adc_stm32h7xx.c \
drivers/bus_i2c_hal.c \
drivers/bus_i2c_hal_init.c \
drivers/stm32/dshot_bitbang_ll.c \
drivers/stm32/light_ws2811strip_hal.c \
drivers/stm32/adc_stm32h7xx.c \
drivers/stm32/bus_i2c_hal.c \
drivers/stm32/bus_i2c_hal_init.c \
drivers/bus_i2c_timing.c \
drivers/pwm_output_dshot_hal.c \
drivers/stm32/pwm_output_dshot_hal.c \
drivers/pwm_output_dshot_shared.c \
drivers/persistent.c \
drivers/transponder_ir_io_hal.c \
drivers/audio_stm32h7xx.c \
drivers/memprot_hal.c \
drivers/memprot_stm32h7xx.c \
drivers/sdio_h7xx.c \
drivers/bus_quadspi_hal.c \
drivers/stm32/transponder_ir_io_hal.c \
drivers/stm32/audio_stm32h7xx.c \
drivers/stm32/memprot_hal.c \
drivers/stm32/memprot_stm32h7xx.c \
drivers/stm32/sdio_h7xx.c \
drivers/stm32/bus_quadspi_hal.c \
drivers/bus_quadspi.c

MCU_EXCLUDES = \
Expand All @@ -316,7 +316,7 @@ MCU_EXCLUDES = \

MSC_SRC = \
drivers/usb_msc_common.c \
drivers/usb_msc_h7xx.c \
drivers/stm32/usb_msc_h7xx.c \
msc/usbd_storage.c \
msc/usbd_storage_emfat.c \
msc/emfat.c \
Expand Down
2 changes: 1 addition & 1 deletion src/main/build/build_config.c
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ mcuTypeId_e getMcuTypeId(void)
return MCU_TYPE_H723_725;
#elif defined(STM32G474xx)
return MCU_TYPE_G474;
#elif defined (AT32F435)
#elif defined(AT32F435)
return MCU_TYPE_AT32;
#else
return MCU_TYPE_UNKNOWN;
Expand Down
4 changes: 2 additions & 2 deletions src/main/config/config_streamer.c
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,11 @@ uint8_t eepromData[EEPROM_SIZE];
// F4
#if defined(STM32F40_41xxx)
# define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
# elif defined (STM32F411xE)
# elif defined(STM32F411xE)
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
# elif defined(STM32F427_437xx)
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
# elif defined (STM32F446xx)
# elif defined(STM32F446xx)
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
// F7
#elif defined(STM32F722xx)
Expand Down
66 changes: 66 additions & 0 deletions src/main/drivers/at32/platform_at32.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@

#if defined(AT32F435ZMT7)

#include "at32f435_437.h"

typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;

#define GPIO_TypeDef gpio_type
#define GPIO_InitTypeDef gpio_init_type
#define TIM_TypeDef tmr_type
#define TIM_OCInitTypeDef tmr_output_config_type
#define DMA_TypeDef dma_type
#define DMA_InitTypeDef dma_init_type
#define DMA_Channel_TypeDef dma_channel_type
#define SPI_TypeDef spi_type
#define ADC_TypeDef adc_type
#define USART_TypeDef usart_type
#define TIM_OCInitTypeDef tmr_output_config_type
#define TIM_ICInitTypeDef tmr_input_config_type
#define SystemCoreClock system_core_clock
#define EXTI_TypeDef exint_type
#define EXTI_InitTypeDef exint_init_type
#define USART_TypeDef usart_type

// Chip Unique ID on F43X
#define U_ID_0 (*(uint32_t*)0x1ffff7e8)
#define U_ID_1 (*(uint32_t*)0x1ffff7ec)
#define U_ID_2 (*(uint32_t*)0x1ffff7f0)

#define USE_PIN_AF

#ifndef AT32F4
#define AT32F4
#endif

#define SET_BIT(REG, BIT) ((REG) |= (BIT))
#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT))
#define READ_BIT(REG, BIT) ((REG) & (BIT))
#define CLEAR_REG(REG) ((REG) = (0x0))
#define WRITE_REG(REG, VAL) ((REG) = (VAL))
#define READ_REG(REG) ((REG))
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))

#endif

#define USE_TIMER_MGMT
#define USE_DMA_SPEC
#define USE_PERSISTENT_OBJECTS
#define USE_CUSTOM_DEFAULTS_ADDRESS

#define TASK_GYROPID_DESIRED_PERIOD 1000 // 1000us = 1kHz
#define SCHEDULER_DELAY_LIMIT 100

#define DEFAULT_CPU_OVERCLOCK 0
#define FAST_IRQ_HANDLER

#define DMA_DATA_ZERO_INIT __attribute__ ((section(".dmaram_bss"), aligned(32)))
#define DMA_DATA __attribute__ ((section(".dmaram_data"), aligned(32)))
#define STATIC_DMA_DATA_AUTO static DMA_DATA

#define DMA_RAM
#define DMA_RW_AXI
#define DMA_RAM_R
#define DMA_RAM_W
#define DMA_RAM_RW

2 changes: 1 addition & 1 deletion src/main/drivers/bus_spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -376,7 +376,7 @@ uint32_t spiCalculateClock(uint16_t spiClkDivisor)
uint32_t spiClk = SystemCoreClock / 2;
#elif defined(STM32H7)
uint32_t spiClk = 100000000;
#elif defined (AT32F4)
#elif defined(AT32F4)
uint32_t spiClk = system_core_clock / 2;

if ((spiClk / spiClkDivisor) > 36000000){
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,16 +29,13 @@
#include "build/debug.h"

#include "drivers/dma_reqmap.h"

#include "drivers/io.h"
#include "io_impl.h"
#include "rcc.h"
#include "dma.h"

#include "drivers/io_impl.h"
#include "drivers/rcc.h"
#include "drivers/dma.h"
#include "drivers/sensor.h"

#include "adc.h"
#include "adc_impl.h"
#include "drivers/adc.h"
#include "drivers/adc_impl.h"

#include "pg/adc.h"

Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
#endif
I2CPINDEF(PF0, GPIO_AF_I2C2),

#if defined(STM32F40_41xxx) || defined (STM32F411xE)
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
// STM32F401xx/STM32F410xx/STM32F411xE/STM32F412xG
I2CPINDEF(PB3, GPIO_AF9_I2C2),
I2CPINDEF(PB9, GPIO_AF9_I2C2),
Expand All @@ -112,7 +112,7 @@ const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
.sdaPins = {
I2CPINDEF(PC9, GPIO_AF_I2C3),

#if defined(STM32F40_41xxx) || defined (STM32F411xE)
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
// STM32F401xx/STM32F410xx/STM32F411xE/STM32F412xG
I2CPINDEF(PB4, GPIO_AF9_I2C3),
I2CPINDEF(PB8, GPIO_AF9_I2C3),
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
#ifdef USE_DMA

#include "drivers/nvic.h"
#include "dma.h"
#include "resource.h"
#include "drivers/dma.h"
#include "drivers/resource.h"

/*
* DMA descriptors.
Expand Down
File renamed without changes.

0 comments on commit 33a96bb

Please sign in to comment.