1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 04:15:44 +03:00

Source file re-arrangement for better separation of MCU types (#12268)

Source file re-arrangement for better spearation of MCU types

- Move STM32 specific files to drivers/stm32
This commit is contained in:
J Blackman 2023-02-01 11:12:34 +11:00 committed by GitHub
parent a3b7d74016
commit 33a96bb5f6
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
79 changed files with 537 additions and 485 deletions

View file

@ -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 = \
@ -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 \

View file

@ -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 \
@ -157,27 +157,27 @@ 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 \
@ -185,7 +185,7 @@ MCU_EXCLUDES = \
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 \

View file

@ -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 \
@ -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 = \
@ -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 \

View file

@ -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 \
@ -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 = \
@ -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 \

View file

@ -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

View file

@ -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"

View file

@ -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.

View file

@ -29,7 +29,7 @@
#include "drivers/nvic.h"
#include "drivers/dma.h"
#include "drivers/rcc.h"
#include "resource.h"
#include "drivers/resource.h"
/*
* DMA descriptors.

View file

@ -35,7 +35,7 @@
#include "drivers/system.h"
#include "drivers/timer.h"
#include "light_ws2811strip.h"
#include "drivers/light_ws2811strip.h"
static IO_t ws2811IO = IO_NONE;

View file

@ -37,7 +37,7 @@
#include "drivers/rcc.h"
#include "drivers/timer.h"
#include "light_ws2811strip.h"
#include "drivers/light_ws2811strip.h"
static IO_t ws2811IO = IO_NONE;
#if defined(STM32F4)

View file

@ -22,7 +22,7 @@
#include "platform.h"
#include "memprot.h"
#include "drivers/memprot.h"
static void memProtConfigError(void)
{

View file

@ -20,7 +20,7 @@
#include "platform.h"
#include "memprot.h"
#include "drivers/memprot.h"
// Defined in linker script
extern uint8_t dma_ram_r_start;

View file

@ -20,7 +20,7 @@
#include "platform.h"
#include "memprot.h"
#include "drivers/memprot.h"
// Defined in linker script
extern uint8_t dmaram_start;

View file

@ -0,0 +1,257 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#if defined(STM32G474xx)
#include "stm32g4xx.h"
#include "stm32g4xx_hal.h"
#include "system_stm32g4xx.h"
#include "stm32g4xx_ll_spi.h"
#include "stm32g4xx_ll_gpio.h"
#include "stm32g4xx_ll_dma.h"
#include "stm32g4xx_ll_rcc.h"
#include "stm32g4xx_ll_bus.h"
#include "stm32g4xx_ll_tim.h"
#include "stm32g4xx_ll_system.h"
#include "drivers/stm32/stm32g4xx_ll_ex.h"
// Chip Unique ID on G4
#define U_ID_0 (*(uint32_t*)UID_BASE)
#define U_ID_1 (*(uint32_t*)(UID_BASE + 4))
#define U_ID_2 (*(uint32_t*)(UID_BASE + 8))
#define USE_PIN_AF
#ifndef STM32G4
#define STM32G4
#endif
#elif defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
#include "stm32h7xx.h"
#include "stm32h7xx_hal.h"
#include "system_stm32h7xx.h"
#include "stm32h7xx_ll_spi.h"
#include "stm32h7xx_ll_gpio.h"
#include "stm32h7xx_ll_dma.h"
#include "stm32h7xx_ll_rcc.h"
#include "stm32h7xx_ll_bus.h"
#include "stm32h7xx_ll_tim.h"
#include "stm32h7xx_ll_system.h"
#include "drivers/stm32/stm32h7xx_ll_ex.h"
// Chip Unique ID on H7
#define U_ID_0 (*(uint32_t*)UID_BASE)
#define U_ID_1 (*(uint32_t*)(UID_BASE + 4))
#define U_ID_2 (*(uint32_t*)(UID_BASE + 8))
#define USE_PIN_AF
#ifndef STM32H7
#define STM32H7
#endif
#elif defined(STM32F722xx) || defined(STM32F745xx) || defined(STM32F746xx) || defined(STM32F765xx)
#include "stm32f7xx.h"
#include "stm32f7xx_hal.h"
#include "system_stm32f7xx.h"
#include "stm32f7xx_ll_spi.h"
#include "stm32f7xx_ll_gpio.h"
#include "stm32f7xx_ll_dma.h"
#include "stm32f7xx_ll_rcc.h"
#include "stm32f7xx_ll_bus.h"
#include "stm32f7xx_ll_tim.h"
#include "stm32f7xx_ll_system.h"
#include "drivers/stm32/stm32f7xx_ll_ex.h"
// Chip Unique ID on F7
#define U_ID_0 (*(uint32_t*)UID_BASE)
#define U_ID_1 (*(uint32_t*)(UID_BASE + 4))
#define U_ID_2 (*(uint32_t*)(UID_BASE + 8))
#define USE_PIN_AF
#ifndef STM32F7
#define STM32F7
#endif
#elif defined(STM32F40_41xxx) || defined(STM32F411xE) || defined(STM32F446xx)
#include "stm32f4xx.h"
// Chip Unique ID on F405
#define U_ID_0 (*(uint32_t*)0x1fff7a10)
#define U_ID_1 (*(uint32_t*)0x1fff7a14)
#define U_ID_2 (*(uint32_t*)0x1fff7a18)
#ifndef STM32F4
#define STM32F4
#endif
#endif
#ifdef STM32F4
#if defined(STM32F40_41xxx)
#define USE_FAST_DATA
#endif
#define USE_RPM_FILTER
#define USE_DYN_IDLE
#define USE_DYN_NOTCH_FILTER
#define USE_ADC_INTERNAL
#define USE_USB_CDC_HID
#define USE_USB_MSC
#define USE_PERSISTENT_MSC_RTC
#define USE_MCO
#define USE_DMA_SPEC
#define USE_TIMER_MGMT
#define USE_PERSISTENT_OBJECTS
#define USE_CUSTOM_DEFAULTS_ADDRESS
#define USE_LATE_TASK_STATISTICS
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
#define USE_OVERCLOCK
#endif
#endif // STM32F4
#ifdef STM32F7
#define USE_ITCM_RAM
#define ITCM_RAM_OPTIMISATION "-O2", "-freorder-blocks-algorithm=simple"
#define USE_FAST_DATA
#define USE_RPM_FILTER
#define USE_DYN_IDLE
#define USE_DYN_NOTCH_FILTER
#define USE_OVERCLOCK
#define USE_ADC_INTERNAL
#define USE_USB_CDC_HID
#define USE_USB_MSC
#define USE_PERSISTENT_MSC_RTC
#define USE_MCO
#define USE_DMA_SPEC
#define USE_TIMER_MGMT
#define USE_PERSISTENT_OBJECTS
#define USE_CUSTOM_DEFAULTS_ADDRESS
#define USE_LATE_TASK_STATISTICS
#endif // STM32F7
#ifdef STM32H7
#ifdef USE_DSHOT
#define USE_DSHOT_CACHE_MGMT
#endif
#define USE_ITCM_RAM
#define USE_FAST_DATA
#define USE_RPM_FILTER
#define USE_DYN_IDLE
#define USE_DYN_NOTCH_FILTER
#define USE_ADC_INTERNAL
#define USE_USB_CDC_HID
#define USE_DMA_SPEC
#define USE_TIMER_MGMT
#define USE_PERSISTENT_OBJECTS
#define USE_DMA_RAM
#define USE_USB_MSC
#define USE_RTC_TIME
#define USE_PERSISTENT_MSC_RTC
#define USE_LATE_TASK_STATISTICS
#endif
#ifdef STM32G4
#define USE_RPM_FILTER
#define USE_DYN_IDLE
#define USE_OVERCLOCK
#define USE_DYN_NOTCH_FILTER
#define USE_ADC_INTERNAL
#define USE_USB_MSC
#define USE_USB_CDC_HID
#define USE_MCO
#define USE_DMA_SPEC
#define USE_TIMER_MGMT
#define USE_LATE_TASK_STATISTICS
#endif
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
#define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
#define SCHEDULER_DELAY_LIMIT 10
#else
#define TASK_GYROPID_DESIRED_PERIOD 1000 // 1000us = 1kHz
#define SCHEDULER_DELAY_LIMIT 100
#endif
// Set the default cpu_overclock to the first level (108MHz) for F411
// Helps with looptime stability as the CPU is borderline when running native gyro sampling
#if defined(USE_OVERCLOCK) && defined(STM32F411xE)
#define DEFAULT_CPU_OVERCLOCK 1
#else
#define DEFAULT_CPU_OVERCLOCK 0
#endif
#if defined(STM32H7)
// Move ISRs to fast ram to avoid flash latency.
#define FAST_IRQ_HANDLER FAST_CODE
#else
#define FAST_IRQ_HANDLER
#endif
#if defined(STM32F4) || defined(STM32G4)
// F4 can't DMA to/from CCM (core coupled memory) SRAM (where the stack lives)
// On G4 there is no specific DMA target memory
#define DMA_DATA_ZERO_INIT
#define DMA_DATA
#define STATIC_DMA_DATA_AUTO static
#elif defined(STM32F7)
// F7 has no cache coherency issues DMAing to/from DTCM, otherwise buffers must be cache aligned
#define DMA_DATA_ZERO_INIT FAST_DATA_ZERO_INIT
#define DMA_DATA FAST_DATA
#define STATIC_DMA_DATA_AUTO static DMA_DATA
#else
// DMA to/from any memory
#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
#endif
#if defined(STM32F4) || defined(STM32H7)
// Data in RAM which is guaranteed to not be reset on hot reboot
#define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
#endif
#ifdef USE_DMA_RAM
#if defined(STM32H7)
#define DMA_RAM __attribute__((section(".DMA_RAM"), aligned(32)))
#define DMA_RW_AXI __attribute__((section(".DMA_RW_AXI"), aligned(32)))
extern uint8_t _dmaram_start__;
extern uint8_t _dmaram_end__;
#elif defined(STM32G4)
#define DMA_RAM_R __attribute__((section(".DMA_RAM_R")))
#define DMA_RAM_W __attribute__((section(".DMA_RAM_W")))
#define DMA_RAM_RW __attribute__((section(".DMA_RAM_RW")))
#endif
#else
#define DMA_RAM
#define DMA_RW_AXI
#define DMA_RAM_R
#define DMA_RAM_W
#define DMA_RAM_RW
#endif

View file

@ -35,7 +35,7 @@
#ifdef USE_SDCARD_SDIO
#include "sdmmc_sdio.h"
#include "drivers/sdmmc_sdio.h"
#include "stm32f4xx_gpio.h"
#include "pg/sdio.h"

View file

@ -32,7 +32,7 @@
#ifdef USE_SDCARD_SDIO
#include "sdmmc_sdio.h"
#include "drivers/sdmmc_sdio.h"
#include "stm32f7xx.h"
#include "pg/sdio.h"

View file

@ -32,7 +32,7 @@
#ifdef USE_SDCARD_SDIO
#include "sdmmc_sdio.h"
#include "drivers/sdmmc_sdio.h"
#include "pg/sdio.h"

View file

@ -36,10 +36,10 @@
#include "drivers/io.h"
#include "drivers/dma.h"
#include "rcc.h"
#include "drivers/rcc.h"
#include "timer.h"
#include "timer_impl.h"
#include "drivers/timer.h"
#include "drivers/timer_impl.h"
#define TIM_N(n) (1 << (n))

View file

@ -29,8 +29,8 @@
#include "drivers/timer_def.h"
#include "stm32f4xx.h"
#include "rcc.h"
#include "timer.h"
#include "drivers/rcc.h"
#include "drivers/timer.h"
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {

View file

@ -29,8 +29,8 @@
#include "drivers/timer_def.h"
#include "stm32f7xx.h"
#include "rcc.h"
#include "timer.h"
#include "drivers/rcc.h"
#include "drivers/timer.h"
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), .inputIrq = TIM1_CC_IRQn},

View file

@ -29,8 +29,8 @@
#include "drivers/timer_def.h"
#include "stm32g4xx.h"
#include "rcc.h"
#include "timer.h"
#include "drivers/rcc.h"
#include "drivers/timer.h"
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {

View file

@ -29,8 +29,8 @@
#include "drivers/timer_def.h"
#include "stm32h7xx.h"
#include "rcc.h"
#include "timer.h"
#include "drivers/rcc.h"
#include "drivers/timer.h"
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), .inputIrq = TIM1_CC_IRQn},

View file

@ -36,7 +36,7 @@
#include "drivers/transponder_ir_erlt.h"
#include "drivers/transponder_ir_ilap.h"
#include "transponder_ir.h"
#include "drivers/transponder_ir.h"
volatile uint8_t transponderIrDataTransferInProgress = 0;

View file

@ -36,7 +36,7 @@
#include "drivers/transponder_ir_erlt.h"
#include "drivers/transponder_ir_ilap.h"
#include "transponder_ir.h"
#include "drivers/transponder_ir.h"
volatile uint8_t transponderIrDataTransferInProgress = 0;

View file

@ -51,7 +51,7 @@
#include "usb_core.h"
#include "usbd_cdc_vcp.h"
#include "usb_io.h"
#include "drivers/usb_io.h"
uint8_t mscStart(void)
{

View file

@ -50,7 +50,7 @@
#include "vcp_hal/usbd_cdc_interface.h"
#include "usb_io.h"
#include "drivers/usb_io.h"
#include "usbd_msc.h"
uint8_t mscStart(void)

View file

@ -50,7 +50,7 @@
#include "vcp_hal/usbd_cdc_interface.h"
#include "usb_io.h"
#include "drivers/usb_io.h"
#include "usbd_msc.h"
uint8_t mscStart(void)

View file

@ -23,6 +23,7 @@
#include <string.h>
#include "platform.h"
#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
#include "common/utils.h"

View file

@ -29,141 +29,28 @@
// common to all
#define USE_TIMER_AF
#if defined(STM32G474xx)
#include "stm32g4xx.h"
#include "stm32g4xx_hal.h"
#include "system_stm32g4xx.h"
#if defined(STM32)
#include "stm32g4xx_ll_spi.h"
#include "stm32g4xx_ll_gpio.h"
#include "stm32g4xx_ll_dma.h"
#include "stm32g4xx_ll_rcc.h"
#include "stm32g4xx_ll_bus.h"
#include "stm32g4xx_ll_tim.h"
#include "stm32g4xx_ll_system.h"
#include "drivers/stm32g4xx_ll_ex.h"
#include "drivers/stm32/platform_stm32.h"
// Chip Unique ID on G4
#define U_ID_0 (*(uint32_t*)UID_BASE)
#define U_ID_1 (*(uint32_t*)(UID_BASE + 4))
#define U_ID_2 (*(uint32_t*)(UID_BASE + 8))
#elif defined(AT32)
#define USE_PIN_AF
#ifndef STM32G4
#define STM32G4
#endif
#elif defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
#include "stm32h7xx.h"
#include "stm32h7xx_hal.h"
#include "system_stm32h7xx.h"
#include "stm32h7xx_ll_spi.h"
#include "stm32h7xx_ll_gpio.h"
#include "stm32h7xx_ll_dma.h"
#include "stm32h7xx_ll_rcc.h"
#include "stm32h7xx_ll_bus.h"
#include "stm32h7xx_ll_tim.h"
#include "stm32h7xx_ll_system.h"
#include "drivers/stm32h7xx_ll_ex.h"
// Chip Unique ID on H7
#define U_ID_0 (*(uint32_t*)UID_BASE)
#define U_ID_1 (*(uint32_t*)(UID_BASE + 4))
#define U_ID_2 (*(uint32_t*)(UID_BASE + 8))
#define USE_PIN_AF
#ifndef STM32H7
#define STM32H7
#endif
#elif defined(STM32F722xx) || defined(STM32F745xx) || defined(STM32F746xx) || defined(STM32F765xx)
#include "stm32f7xx.h"
#include "stm32f7xx_hal.h"
#include "system_stm32f7xx.h"
#include "stm32f7xx_ll_spi.h"
#include "stm32f7xx_ll_gpio.h"
#include "stm32f7xx_ll_dma.h"
#include "stm32f7xx_ll_rcc.h"
#include "stm32f7xx_ll_bus.h"
#include "stm32f7xx_ll_tim.h"
#include "stm32f7xx_ll_system.h"
#include "drivers/stm32f7xx_ll_ex.h"
// Chip Unique ID on F7
#define U_ID_0 (*(uint32_t*)UID_BASE)
#define U_ID_1 (*(uint32_t*)(UID_BASE + 4))
#define U_ID_2 (*(uint32_t*)(UID_BASE + 8))
#define USE_PIN_AF
#ifndef STM32F7
#define STM32F7
#endif
#elif defined(STM32F40_41xxx) || defined (STM32F411xE) || defined (STM32F446xx)
#include "stm32f4xx.h"
// Chip Unique ID on F405
#define U_ID_0 (*(uint32_t*)0x1fff7a10)
#define U_ID_1 (*(uint32_t*)0x1fff7a14)
#define U_ID_2 (*(uint32_t*)0x1fff7a18)
#ifndef STM32F4
#define STM32F4
#endif
#elif 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)))
#include "drivers/at32/platform_at32.h"
#elif defined(SIMULATOR_BUILD)
// Nop
#undef USE_TIMER_AF
#define DEFAULT_CPU_OVERCLOCK 1
#define DMA_RAM
#define DMA_RW_AXI
#define DMA_RAM_R
#define DMA_RAM_W
#define DMA_RAM_RW
#define DMA_DATA_ZERO_INIT
#define DMA_DATA
#define STATIC_DMA_DATA_AUTO
#else
#error "Invalid chipset specified. Update platform.h"
#endif

View file

@ -27,7 +27,7 @@ DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xM.ld
ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE)
DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32
MCU_COMMON_SRC = \
$(addprefix startup/at32/,$(notdir $(wildcard $(SRC_DIR)/startup/at32/*.c))) \

View file

@ -59,126 +59,12 @@
#define USE_DSHOT_TELEMETRY_STATS
#endif
#ifdef AT32F4
#define USE_TIMER_MGMT
#define USE_DMA_SPEC
#define USE_PERSISTENT_OBJECTS
#define USE_CUSTOM_DEFAULTS_ADDRESS
#endif
#ifdef STM32F4
#if defined(STM32F40_41xxx)
#define USE_FAST_DATA
#endif
#define USE_RPM_FILTER
#define USE_DYN_IDLE
#define USE_DYN_NOTCH_FILTER
#define USE_ADC_INTERNAL
#define USE_USB_CDC_HID
#define USE_USB_MSC
#define USE_PERSISTENT_MSC_RTC
#define USE_MCO
#define USE_DMA_SPEC
#define USE_TIMER_MGMT
#define USE_PERSISTENT_OBJECTS
#define USE_CUSTOM_DEFAULTS_ADDRESS
#define USE_LATE_TASK_STATISTICS
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
#define USE_OVERCLOCK
#endif
#endif // STM32F4
#ifdef STM32F7
#define USE_ITCM_RAM
#define ITCM_RAM_OPTIMISATION "-O2", "-freorder-blocks-algorithm=simple"
#define USE_FAST_DATA
#define USE_RPM_FILTER
#define USE_DYN_IDLE
#define USE_DYN_NOTCH_FILTER
#define USE_OVERCLOCK
#define USE_ADC_INTERNAL
#define USE_USB_CDC_HID
#define USE_USB_MSC
#define USE_PERSISTENT_MSC_RTC
#define USE_MCO
#define USE_DMA_SPEC
#define USE_TIMER_MGMT
#define USE_PERSISTENT_OBJECTS
#define USE_CUSTOM_DEFAULTS_ADDRESS
#define USE_LATE_TASK_STATISTICS
#endif // STM32F7
#ifdef STM32H7
#ifdef USE_DSHOT
#define USE_DSHOT_CACHE_MGMT
#endif
#define USE_ITCM_RAM
#define USE_FAST_DATA
#define USE_RPM_FILTER
#define USE_DYN_IDLE
#define USE_DYN_NOTCH_FILTER
#define USE_ADC_INTERNAL
#define USE_USB_CDC_HID
#define USE_DMA_SPEC
#define USE_TIMER_MGMT
#define USE_PERSISTENT_OBJECTS
#define USE_DMA_RAM
#define USE_USB_MSC
#define USE_RTC_TIME
#define USE_PERSISTENT_MSC_RTC
#define USE_LATE_TASK_STATISTICS
#endif
#ifdef STM32G4
#define USE_RPM_FILTER
#define USE_DYN_IDLE
#define USE_OVERCLOCK
#define USE_DYN_NOTCH_FILTER
#define USE_ADC_INTERNAL
#define USE_USB_MSC
#define USE_USB_CDC_HID
#define USE_MCO
#define USE_DMA_SPEC
#define USE_TIMER_MGMT
#define USE_LATE_TASK_STATISTICS
#endif
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
#define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
#define SCHEDULER_DELAY_LIMIT 10
#else
#define TASK_GYROPID_DESIRED_PERIOD 1000 // 1000us = 1kHz
#define SCHEDULER_DELAY_LIMIT 100
#endif
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
#define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT
#else
#define DEFAULT_AUX_CHANNEL_COUNT 6
#endif
// Set the default cpu_overclock to the first level (108MHz) for F411
// Helps with looptime stability as the CPU is borderline when running native gyro sampling
#if defined(USE_OVERCLOCK) && defined(STM32F411xE)
#define DEFAULT_CPU_OVERCLOCK 1
#else
#define DEFAULT_CPU_OVERCLOCK 0
#endif
#if defined(STM32H7)
// Move ISRs to fast ram to avoid flash latency.
#define FAST_IRQ_HANDLER FAST_CODE
#else
#define FAST_IRQ_HANDLER
#endif
#ifdef USE_ITCM_RAM
#if defined(ITCM_RAM_OPTIMISATION) && !defined(DEBUG)
#define FAST_CODE __attribute__((section(".tcm_code"))) __attribute__((optimize(ITCM_RAM_OPTIMISATION)))
@ -212,48 +98,6 @@
#define FAST_DATA
#endif // USE_FAST_DATA
#if defined(STM32F4) || defined(STM32G4)
// F4 can't DMA to/from CCM (core coupled memory) SRAM (where the stack lives)
// On G4 there is no specific DMA target memory
#define DMA_DATA_ZERO_INIT
#define DMA_DATA
#define STATIC_DMA_DATA_AUTO static
#elif defined (STM32F7)
// F7 has no cache coherency issues DMAing to/from DTCM, otherwise buffers must be cache aligned
#define DMA_DATA_ZERO_INIT FAST_DATA_ZERO_INIT
#define DMA_DATA FAST_DATA
#define STATIC_DMA_DATA_AUTO static DMA_DATA
#else
// DMA to/from any memory
#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
#endif
#if defined(STM32F4) || defined (STM32H7)
// Data in RAM which is guaranteed to not be reset on hot reboot
#define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
#endif
#ifdef USE_DMA_RAM
#if defined(STM32H7)
#define DMA_RAM __attribute__((section(".DMA_RAM"), aligned(32)))
#define DMA_RW_AXI __attribute__((section(".DMA_RW_AXI"), aligned(32)))
extern uint8_t _dmaram_start__;
extern uint8_t _dmaram_end__;
#elif defined(STM32G4)
#define DMA_RAM_R __attribute__((section(".DMA_RAM_R")))
#define DMA_RAM_W __attribute__((section(".DMA_RAM_W")))
#define DMA_RAM_RW __attribute__((section(".DMA_RAM_RW")))
#endif
#else
#define DMA_RAM
#define DMA_RW_AXI
#define DMA_RAM_R
#define DMA_RAM_W
#define DMA_RAM_RW
#endif
#define USE_MOTOR
#define USE_DMA
#define USE_TIMER