diff --git a/make/mcu/STM32F4.mk b/make/mcu/STM32F4.mk
index 1be59de09e..1b77fe3367 100644
--- a/make/mcu/STM32F4.mk
+++ b/make/mcu/STM32F4.mk
@@ -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 \
diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk
index 7f365d1f53..e4c09731cf 100644
--- a/make/mcu/STM32F7.mk
+++ b/make/mcu/STM32F7.mk
@@ -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 \
diff --git a/make/mcu/STM32G4.mk b/make/mcu/STM32G4.mk
index a47134cef0..6e3eee4690 100644
--- a/make/mcu/STM32G4.mk
+++ b/make/mcu/STM32G4.mk
@@ -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 \
diff --git a/make/mcu/STM32H7.mk b/make/mcu/STM32H7.mk
index f5c8ebb341..4b8f39992e 100644
--- a/make/mcu/STM32H7.mk
+++ b/make/mcu/STM32H7.mk
@@ -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 \
diff --git a/src/main/build/build_config.c b/src/main/build/build_config.c
index 5788d22883..0faab12b4d 100644
--- a/src/main/build/build_config.c
+++ b/src/main/build/build_config.c
@@ -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;
diff --git a/src/main/config/config_streamer.c b/src/main/config/config_streamer.c
index 674119b158..89ff09c5dc 100644
--- a/src/main/config/config_streamer.c
+++ b/src/main/config/config_streamer.c
@@ -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)
diff --git a/src/main/drivers/at32/platform_at32.h b/src/main/drivers/at32/platform_at32.h
new file mode 100644
index 0000000000..201a505f78
--- /dev/null
+++ b/src/main/drivers/at32/platform_at32.h
@@ -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
+
diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c
index d43adda2fb..297c15af7b 100644
--- a/src/main/drivers/bus_spi.c
+++ b/src/main/drivers/bus_spi.c
@@ -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){
diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/stm32/adc_stm32f4xx.c
similarity index 98%
rename from src/main/drivers/adc_stm32f4xx.c
rename to src/main/drivers/stm32/adc_stm32f4xx.c
index 566b4bc8d0..0ce2a8e075 100644
--- a/src/main/drivers/adc_stm32f4xx.c
+++ b/src/main/drivers/stm32/adc_stm32f4xx.c
@@ -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"
diff --git a/src/main/drivers/adc_stm32f7xx.c b/src/main/drivers/stm32/adc_stm32f7xx.c
similarity index 100%
rename from src/main/drivers/adc_stm32f7xx.c
rename to src/main/drivers/stm32/adc_stm32f7xx.c
diff --git a/src/main/drivers/adc_stm32g4xx.c b/src/main/drivers/stm32/adc_stm32g4xx.c
similarity index 100%
rename from src/main/drivers/adc_stm32g4xx.c
rename to src/main/drivers/stm32/adc_stm32g4xx.c
diff --git a/src/main/drivers/adc_stm32h7xx.c b/src/main/drivers/stm32/adc_stm32h7xx.c
similarity index 100%
rename from src/main/drivers/adc_stm32h7xx.c
rename to src/main/drivers/stm32/adc_stm32h7xx.c
diff --git a/src/main/drivers/audio_stm32f7xx.c b/src/main/drivers/stm32/audio_stm32f7xx.c
similarity index 100%
rename from src/main/drivers/audio_stm32f7xx.c
rename to src/main/drivers/stm32/audio_stm32f7xx.c
diff --git a/src/main/drivers/audio_stm32h7xx.c b/src/main/drivers/stm32/audio_stm32h7xx.c
similarity index 100%
rename from src/main/drivers/audio_stm32h7xx.c
rename to src/main/drivers/stm32/audio_stm32h7xx.c
diff --git a/src/main/drivers/bus_i2c_hal.c b/src/main/drivers/stm32/bus_i2c_hal.c
similarity index 100%
rename from src/main/drivers/bus_i2c_hal.c
rename to src/main/drivers/stm32/bus_i2c_hal.c
diff --git a/src/main/drivers/bus_i2c_hal_init.c b/src/main/drivers/stm32/bus_i2c_hal_init.c
similarity index 100%
rename from src/main/drivers/bus_i2c_hal_init.c
rename to src/main/drivers/stm32/bus_i2c_hal_init.c
diff --git a/src/main/drivers/bus_i2c_stm32f4xx.c b/src/main/drivers/stm32/bus_i2c_stm32f4xx.c
similarity index 99%
rename from src/main/drivers/bus_i2c_stm32f4xx.c
rename to src/main/drivers/stm32/bus_i2c_stm32f4xx.c
index b45ac7f099..a0c7ddde20 100644
--- a/src/main/drivers/bus_i2c_stm32f4xx.c
+++ b/src/main/drivers/stm32/bus_i2c_stm32f4xx.c
@@ -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),
@@ -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),
diff --git a/src/main/drivers/bus_quadspi_hal.c b/src/main/drivers/stm32/bus_quadspi_hal.c
similarity index 100%
rename from src/main/drivers/bus_quadspi_hal.c
rename to src/main/drivers/stm32/bus_quadspi_hal.c
diff --git a/src/main/drivers/bus_spi_ll.c b/src/main/drivers/stm32/bus_spi_ll.c
similarity index 100%
rename from src/main/drivers/bus_spi_ll.c
rename to src/main/drivers/stm32/bus_spi_ll.c
diff --git a/src/main/drivers/bus_spi_stdperiph.c b/src/main/drivers/stm32/bus_spi_stdperiph.c
similarity index 100%
rename from src/main/drivers/bus_spi_stdperiph.c
rename to src/main/drivers/stm32/bus_spi_stdperiph.c
diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/stm32/dma_stm32f4xx.c
similarity index 98%
rename from src/main/drivers/dma_stm32f4xx.c
rename to src/main/drivers/stm32/dma_stm32f4xx.c
index e4eaa84b98..97311e2c06 100644
--- a/src/main/drivers/dma_stm32f4xx.c
+++ b/src/main/drivers/stm32/dma_stm32f4xx.c
@@ -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.
diff --git a/src/main/drivers/dma_stm32f7xx.c b/src/main/drivers/stm32/dma_stm32f7xx.c
similarity index 100%
rename from src/main/drivers/dma_stm32f7xx.c
rename to src/main/drivers/stm32/dma_stm32f7xx.c
diff --git a/src/main/drivers/dma_stm32g4xx.c b/src/main/drivers/stm32/dma_stm32g4xx.c
similarity index 99%
rename from src/main/drivers/dma_stm32g4xx.c
rename to src/main/drivers/stm32/dma_stm32g4xx.c
index a3db8a23f8..6e0d805038 100644
--- a/src/main/drivers/dma_stm32g4xx.c
+++ b/src/main/drivers/stm32/dma_stm32g4xx.c
@@ -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.
diff --git a/src/main/drivers/dma_stm32h7xx.c b/src/main/drivers/stm32/dma_stm32h7xx.c
similarity index 100%
rename from src/main/drivers/dma_stm32h7xx.c
rename to src/main/drivers/stm32/dma_stm32h7xx.c
diff --git a/src/main/drivers/dshot_bitbang_ll.c b/src/main/drivers/stm32/dshot_bitbang_ll.c
similarity index 100%
rename from src/main/drivers/dshot_bitbang_ll.c
rename to src/main/drivers/stm32/dshot_bitbang_ll.c
diff --git a/src/main/drivers/dshot_bitbang_stdperiph.c b/src/main/drivers/stm32/dshot_bitbang_stdperiph.c
similarity index 100%
rename from src/main/drivers/dshot_bitbang_stdperiph.c
rename to src/main/drivers/stm32/dshot_bitbang_stdperiph.c
diff --git a/src/main/drivers/light_ws2811strip_hal.c b/src/main/drivers/stm32/light_ws2811strip_hal.c
similarity index 99%
rename from src/main/drivers/light_ws2811strip_hal.c
rename to src/main/drivers/stm32/light_ws2811strip_hal.c
index 61faedafca..6a654f4ea6 100644
--- a/src/main/drivers/light_ws2811strip_hal.c
+++ b/src/main/drivers/stm32/light_ws2811strip_hal.c
@@ -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;
diff --git a/src/main/drivers/light_ws2811strip_stdperiph.c b/src/main/drivers/stm32/light_ws2811strip_stdperiph.c
similarity index 99%
rename from src/main/drivers/light_ws2811strip_stdperiph.c
rename to src/main/drivers/stm32/light_ws2811strip_stdperiph.c
index 5c0d1fa13d..1b4dbf9017 100644
--- a/src/main/drivers/light_ws2811strip_stdperiph.c
+++ b/src/main/drivers/stm32/light_ws2811strip_stdperiph.c
@@ -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)
diff --git a/src/main/drivers/memprot_hal.c b/src/main/drivers/stm32/memprot_hal.c
similarity index 99%
rename from src/main/drivers/memprot_hal.c
rename to src/main/drivers/stm32/memprot_hal.c
index 07cfac5bdc..abfd7c85a7 100644
--- a/src/main/drivers/memprot_hal.c
+++ b/src/main/drivers/stm32/memprot_hal.c
@@ -22,7 +22,7 @@
#include "platform.h"
-#include "memprot.h"
+#include "drivers/memprot.h"
static void memProtConfigError(void)
{
diff --git a/src/main/drivers/memprot_stm32g4xx.c b/src/main/drivers/stm32/memprot_stm32g4xx.c
similarity index 98%
rename from src/main/drivers/memprot_stm32g4xx.c
rename to src/main/drivers/stm32/memprot_stm32g4xx.c
index d8daae2682..f07dd45b8b 100644
--- a/src/main/drivers/memprot_stm32g4xx.c
+++ b/src/main/drivers/stm32/memprot_stm32g4xx.c
@@ -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;
diff --git a/src/main/drivers/memprot_stm32h7xx.c b/src/main/drivers/stm32/memprot_stm32h7xx.c
similarity index 98%
rename from src/main/drivers/memprot_stm32h7xx.c
rename to src/main/drivers/stm32/memprot_stm32h7xx.c
index 49772f7d0c..d258e19de3 100644
--- a/src/main/drivers/memprot_stm32h7xx.c
+++ b/src/main/drivers/stm32/memprot_stm32h7xx.c
@@ -20,7 +20,7 @@
#include "platform.h"
-#include "memprot.h"
+#include "drivers/memprot.h"
// Defined in linker script
extern uint8_t dmaram_start;
diff --git a/src/main/drivers/stm32/platform_stm32.h b/src/main/drivers/stm32/platform_stm32.h
new file mode 100644
index 0000000000..0f7a9087c9
--- /dev/null
+++ b/src/main/drivers/stm32/platform_stm32.h
@@ -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 .
+ */
+
+#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
diff --git a/src/main/drivers/pwm_output_dshot_hal.c b/src/main/drivers/stm32/pwm_output_dshot_hal.c
similarity index 100%
rename from src/main/drivers/pwm_output_dshot_hal.c
rename to src/main/drivers/stm32/pwm_output_dshot_hal.c
diff --git a/src/main/drivers/pwm_output_dshot_hal_hal.c b/src/main/drivers/stm32/pwm_output_dshot_hal_hal.c
similarity index 100%
rename from src/main/drivers/pwm_output_dshot_hal_hal.c
rename to src/main/drivers/stm32/pwm_output_dshot_hal_hal.c
diff --git a/src/main/drivers/sdio_f4xx.c b/src/main/drivers/stm32/sdio_f4xx.c
similarity index 99%
rename from src/main/drivers/sdio_f4xx.c
rename to src/main/drivers/stm32/sdio_f4xx.c
index b084a5d647..08ed8b09f4 100644
--- a/src/main/drivers/sdio_f4xx.c
+++ b/src/main/drivers/stm32/sdio_f4xx.c
@@ -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"
@@ -212,8 +212,8 @@ typedef struct
uint32_t CID[4]; // SD card identification number table
volatile uint32_t TransferComplete; // SD transfer complete flag in non blocking mode
volatile uint32_t TransferError; // SD transfer error flag in non blocking mode
- volatile uint32_t RXCplt; // SD RX Complete is equal 0 when no transfer
- volatile uint32_t TXCplt; // SD TX Complete is equal 0 when no transfer
+ volatile uint32_t RXCplt; // SD RX Complete is equal 0 when no transfer
+ volatile uint32_t TXCplt; // SD TX Complete is equal 0 when no transfer
volatile uint32_t Operation; // SD transfer operation (read/write)
} SD_Handle_t;
@@ -261,7 +261,7 @@ void SDIO_DMA_ST6_IRQHandler(dmaChannelDescriptor_t *dma);
//static void SD_PowerOFF (void);
/** -----------------------------------------------------------------------------------------------------------------*/
-/** DataTransferInit
+/** DataTransferInit
*
* @brief Prepare the state machine for transfer
* @param SD_TransferType_e TransfertDir
@@ -280,7 +280,7 @@ static void SD_DataTransferInit(uint32_t Size, uint32_t DataBlockSize, bool IsIt
/** -----------------------------------------------------------------------------------------------------------------*/
-/** SD_TransmitCommand
+/** SD_TransmitCommand
*
* @brief Send the command to SDIO
* @param uint32_t Command
@@ -424,7 +424,7 @@ static SD_Error_t CheckOCR_Response(uint32_t Response_R1)
/** -----------------------------------------------------------------------------------------------------------------*/
-/** GetResponse
+/** GetResponse
*
* @brief Get response from SD device
* @param uint32_t* pResponse
diff --git a/src/main/drivers/sdio_f7xx.c b/src/main/drivers/stm32/sdio_f7xx.c
similarity index 99%
rename from src/main/drivers/sdio_f7xx.c
rename to src/main/drivers/stm32/sdio_f7xx.c
index 62574beaa1..8c4f69b257 100644
--- a/src/main/drivers/sdio_f7xx.c
+++ b/src/main/drivers/stm32/sdio_f7xx.c
@@ -32,7 +32,7 @@
#ifdef USE_SDCARD_SDIO
-#include "sdmmc_sdio.h"
+#include "drivers/sdmmc_sdio.h"
#include "stm32f7xx.h"
#include "pg/sdio.h"
@@ -194,8 +194,8 @@ typedef struct
uint32_t CID[4]; // SD card identification number table
volatile uint32_t TransferComplete; // SD transfer complete flag in non blocking mode
volatile uint32_t TransferError; // SD transfer error flag in non blocking mode
- volatile uint32_t RXCplt; // SD RX Complete is equal 0 when no transfer
- volatile uint32_t TXCplt; // SD TX Complete is equal 0 when no transfer
+ volatile uint32_t RXCplt; // SD RX Complete is equal 0 when no transfer
+ volatile uint32_t TXCplt; // SD TX Complete is equal 0 when no transfer
volatile uint32_t Operation; // SD transfer operation (read/write)
} SD_Handle_t;
@@ -243,7 +243,7 @@ void SDMMC_DMA_ST6_IRQHandler(dmaChannelDescriptor_t *dma);
//static void SD_PowerOFF (void);
/** -----------------------------------------------------------------------------------------------------------------*/
-/** DataTransferInit
+/** DataTransferInit
*
* @brief Prepare the state machine for transfer
* @param SD_TransferType_e TransfertDir
@@ -262,7 +262,7 @@ static void SD_DataTransferInit(uint32_t Size, uint32_t DataBlockSize, bool IsIt
/** -----------------------------------------------------------------------------------------------------------------*/
-/** SD_TransmitCommand
+/** SD_TransmitCommand
*
* @brief Send the commande to SDMMC1
* @param uint32_t Command
@@ -406,7 +406,7 @@ static SD_Error_t CheckOCR_Response(uint32_t Response_R1)
/** -----------------------------------------------------------------------------------------------------------------*/
-/** GetResponse
+/** GetResponse
*
* @brief Get response from SD device
* @param uint32_t* pResponse
diff --git a/src/main/drivers/sdio_h7xx.c b/src/main/drivers/stm32/sdio_h7xx.c
similarity index 99%
rename from src/main/drivers/sdio_h7xx.c
rename to src/main/drivers/stm32/sdio_h7xx.c
index a876742790..a5d1bb5aff 100644
--- a/src/main/drivers/sdio_h7xx.c
+++ b/src/main/drivers/stm32/sdio_h7xx.c
@@ -32,7 +32,7 @@
#ifdef USE_SDCARD_SDIO
-#include "sdmmc_sdio.h"
+#include "drivers/sdmmc_sdio.h"
#include "pg/sdio.h"
diff --git a/src/main/drivers/serial_uart_hal.c b/src/main/drivers/stm32/serial_uart_hal.c
similarity index 100%
rename from src/main/drivers/serial_uart_hal.c
rename to src/main/drivers/stm32/serial_uart_hal.c
diff --git a/src/main/drivers/serial_uart_stdperiph.c b/src/main/drivers/stm32/serial_uart_stdperiph.c
similarity index 100%
rename from src/main/drivers/serial_uart_stdperiph.c
rename to src/main/drivers/stm32/serial_uart_stdperiph.c
diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/stm32/serial_uart_stm32f4xx.c
similarity index 99%
rename from src/main/drivers/serial_uart_stm32f4xx.c
rename to src/main/drivers/stm32/serial_uart_stm32f4xx.c
index 0f1dc8dbb1..814631d087 100644
--- a/src/main/drivers/serial_uart_stm32f4xx.c
+++ b/src/main/drivers/stm32/serial_uart_stm32f4xx.c
@@ -53,12 +53,12 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.txDMAResource = (dmaResource_t *)DMA2_Stream7,
#endif
.rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) },
-#if defined (STM32F411xE)
+#if defined(STM32F411xE)
{ DEFIO_TAG_E(PB3) },
#endif
},
.txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) },
-#if defined (STM32F411xE)
+#if defined(STM32F411xE)
{ DEFIO_TAG_E(PA15) },
#endif
},
@@ -191,14 +191,14 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.txDMAResource = (dmaResource_t *)DMA2_Stream6,
#endif
.rxPins = { { DEFIO_TAG_E(PC7) },
-#if defined (STM32F411xE)
+#if defined(STM32F411xE)
{ DEFIO_TAG_E(PA12) },
#else
{ DEFIO_TAG_E(PG9) },
#endif
},
.txPins = { { DEFIO_TAG_E(PC6) },
-#if defined (STM32F411xE)
+#if defined(STM32F411xE)
{ DEFIO_TAG_E(PA11) },
#else
{ DEFIO_TAG_E(PG14) },
diff --git a/src/main/drivers/serial_uart_stm32f7xx.c b/src/main/drivers/stm32/serial_uart_stm32f7xx.c
similarity index 100%
rename from src/main/drivers/serial_uart_stm32f7xx.c
rename to src/main/drivers/stm32/serial_uart_stm32f7xx.c
diff --git a/src/main/drivers/serial_uart_stm32g4xx.c b/src/main/drivers/stm32/serial_uart_stm32g4xx.c
similarity index 100%
rename from src/main/drivers/serial_uart_stm32g4xx.c
rename to src/main/drivers/stm32/serial_uart_stm32g4xx.c
diff --git a/src/main/drivers/serial_uart_stm32h7xx.c b/src/main/drivers/stm32/serial_uart_stm32h7xx.c
similarity index 100%
rename from src/main/drivers/serial_uart_stm32h7xx.c
rename to src/main/drivers/stm32/serial_uart_stm32h7xx.c
diff --git a/src/main/drivers/stm32f7xx_ll_ex.h b/src/main/drivers/stm32/stm32f7xx_ll_ex.h
similarity index 100%
rename from src/main/drivers/stm32f7xx_ll_ex.h
rename to src/main/drivers/stm32/stm32f7xx_ll_ex.h
diff --git a/src/main/drivers/stm32g4xx_ll_ex.h b/src/main/drivers/stm32/stm32g4xx_ll_ex.h
similarity index 100%
rename from src/main/drivers/stm32g4xx_ll_ex.h
rename to src/main/drivers/stm32/stm32g4xx_ll_ex.h
diff --git a/src/main/drivers/stm32h7xx_ll_ex.h b/src/main/drivers/stm32/stm32h7xx_ll_ex.h
similarity index 100%
rename from src/main/drivers/stm32h7xx_ll_ex.h
rename to src/main/drivers/stm32/stm32h7xx_ll_ex.h
diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/stm32/system_stm32f4xx.c
similarity index 100%
rename from src/main/drivers/system_stm32f4xx.c
rename to src/main/drivers/stm32/system_stm32f4xx.c
diff --git a/src/main/drivers/system_stm32f7xx.c b/src/main/drivers/stm32/system_stm32f7xx.c
similarity index 100%
rename from src/main/drivers/system_stm32f7xx.c
rename to src/main/drivers/stm32/system_stm32f7xx.c
diff --git a/src/main/drivers/system_stm32g4xx.c b/src/main/drivers/stm32/system_stm32g4xx.c
similarity index 100%
rename from src/main/drivers/system_stm32g4xx.c
rename to src/main/drivers/stm32/system_stm32g4xx.c
diff --git a/src/main/drivers/system_stm32h7xx.c b/src/main/drivers/stm32/system_stm32h7xx.c
similarity index 100%
rename from src/main/drivers/system_stm32h7xx.c
rename to src/main/drivers/stm32/system_stm32h7xx.c
diff --git a/src/main/drivers/timer_hal.c b/src/main/drivers/stm32/timer_hal.c
similarity index 99%
rename from src/main/drivers/timer_hal.c
rename to src/main/drivers/stm32/timer_hal.c
index b09ecf10ca..f06c521daa 100644
--- a/src/main/drivers/timer_hal.c
+++ b/src/main/drivers/stm32/timer_hal.c
@@ -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))
diff --git a/src/main/drivers/timer_stm32f4xx.c b/src/main/drivers/stm32/timer_stm32f4xx.c
similarity index 98%
rename from src/main/drivers/timer_stm32f4xx.c
rename to src/main/drivers/stm32/timer_stm32f4xx.c
index 41a03688aa..df45b995b6 100644
--- a/src/main/drivers/timer_stm32f4xx.c
+++ b/src/main/drivers/stm32/timer_stm32f4xx.c
@@ -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] = {
@@ -226,10 +226,10 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = {
uint32_t timerClock(TIM_TypeDef *tim)
{
-#if defined (STM32F411xE)
+#if defined(STM32F411xE)
UNUSED(tim);
return SystemCoreClock;
-#elif defined (STM32F40_41xxx) || defined (STM32F446xx)
+#elif defined(STM32F40_41xxx) || defined(STM32F446xx)
if (tim == TIM8 || tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
return SystemCoreClock;
} else {
diff --git a/src/main/drivers/timer_stm32f7xx.c b/src/main/drivers/stm32/timer_stm32f7xx.c
similarity index 99%
rename from src/main/drivers/timer_stm32f7xx.c
rename to src/main/drivers/stm32/timer_stm32f7xx.c
index 32055ad3e0..c0f3fa9340 100644
--- a/src/main/drivers/timer_stm32f7xx.c
+++ b/src/main/drivers/stm32/timer_stm32f7xx.c
@@ -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},
diff --git a/src/main/drivers/timer_stm32g4xx.c b/src/main/drivers/stm32/timer_stm32g4xx.c
similarity index 99%
rename from src/main/drivers/timer_stm32g4xx.c
rename to src/main/drivers/stm32/timer_stm32g4xx.c
index f4c2bd8f24..12e9c228bf 100644
--- a/src/main/drivers/timer_stm32g4xx.c
+++ b/src/main/drivers/stm32/timer_stm32g4xx.c
@@ -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] = {
diff --git a/src/main/drivers/timer_stm32h7xx.c b/src/main/drivers/stm32/timer_stm32h7xx.c
similarity index 99%
rename from src/main/drivers/timer_stm32h7xx.c
rename to src/main/drivers/stm32/timer_stm32h7xx.c
index 5177076a79..4da0ee3230 100644
--- a/src/main/drivers/timer_stm32h7xx.c
+++ b/src/main/drivers/stm32/timer_stm32h7xx.c
@@ -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},
diff --git a/src/main/drivers/transponder_ir_io_hal.c b/src/main/drivers/stm32/transponder_ir_io_hal.c
similarity index 99%
rename from src/main/drivers/transponder_ir_io_hal.c
rename to src/main/drivers/stm32/transponder_ir_io_hal.c
index c971f2d763..8fa20459a3 100644
--- a/src/main/drivers/transponder_ir_io_hal.c
+++ b/src/main/drivers/stm32/transponder_ir_io_hal.c
@@ -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;
diff --git a/src/main/drivers/transponder_ir_io_stdperiph.c b/src/main/drivers/stm32/transponder_ir_io_stdperiph.c
similarity index 99%
rename from src/main/drivers/transponder_ir_io_stdperiph.c
rename to src/main/drivers/stm32/transponder_ir_io_stdperiph.c
index 67193ead58..0d4170cc0f 100644
--- a/src/main/drivers/transponder_ir_io_stdperiph.c
+++ b/src/main/drivers/stm32/transponder_ir_io_stdperiph.c
@@ -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;
diff --git a/src/main/drivers/usb_msc_f4xx.c b/src/main/drivers/stm32/usb_msc_f4xx.c
similarity index 98%
rename from src/main/drivers/usb_msc_f4xx.c
rename to src/main/drivers/stm32/usb_msc_f4xx.c
index 66b0fcf43d..1768932534 100644
--- a/src/main/drivers/usb_msc_f4xx.c
+++ b/src/main/drivers/stm32/usb_msc_f4xx.c
@@ -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)
{
diff --git a/src/main/drivers/usb_msc_f7xx.c b/src/main/drivers/stm32/usb_msc_f7xx.c
similarity index 98%
rename from src/main/drivers/usb_msc_f7xx.c
rename to src/main/drivers/stm32/usb_msc_f7xx.c
index 9fbf62c8ee..69da876805 100644
--- a/src/main/drivers/usb_msc_f7xx.c
+++ b/src/main/drivers/stm32/usb_msc_f7xx.c
@@ -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)
diff --git a/src/main/drivers/usb_msc_h7xx.c b/src/main/drivers/stm32/usb_msc_h7xx.c
similarity index 98%
rename from src/main/drivers/usb_msc_h7xx.c
rename to src/main/drivers/stm32/usb_msc_h7xx.c
index 96f5d2a4b4..69397f5079 100644
--- a/src/main/drivers/usb_msc_h7xx.c
+++ b/src/main/drivers/stm32/usb_msc_h7xx.c
@@ -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)
diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c
index 1455c501ea..a2e0eec56f 100644
--- a/src/main/drivers/timer.c
+++ b/src/main/drivers/timer.c
@@ -347,12 +347,12 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
timerNVICConfigure(irq);
// HACK - enable second IRQ on timers that need it
switch (irq) {
-#if defined (STM32F40_41xxx) || defined(STM32F411xE)
+#if defined(STM32F40_41xxx) || defined(STM32F411xE)
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
break;
#endif
-#if defined (STM32F40_41xxx)
+#if defined(STM32F40_41xxx)
case TIM8_CC_IRQn:
timerNVICConfigure(TIM8_UP_TIM13_IRQn);
break;
@@ -759,7 +759,7 @@ static inline void timUpdateHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig
#if USED_TIMERS & TIM_N(1)
_TIM_IRQ_HANDLER(TIM1_CC_IRQHandler, 1);
-# if defined(STM32F40_41xxx) || defined (STM32F411xE)
+# if defined(STM32F40_41xxx) || defined(STM32F411xE)
# if USED_TIMERS & TIM_N(10)
_TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
# else
@@ -806,7 +806,7 @@ _TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler, 8, 13); // both timers are in use
_TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8); // timer13 is not used
# endif
# endif
-# if defined (STM32F411xE)
+# if defined(STM32F411xE)
# endif
#endif
#if USED_TIMERS & TIM_N(9)
diff --git a/src/main/io/displayport_hott.c b/src/main/io/displayport_hott.c
index 1dec6bab01..829132d89e 100644
--- a/src/main/io/displayport_hott.c
+++ b/src/main/io/displayport_hott.c
@@ -23,7 +23,8 @@
#include
#include "platform.h"
-#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
+
+#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
#include "common/utils.h"
#include "cms/cms.h"
diff --git a/src/main/msc/emfat_file.c b/src/main/msc/emfat_file.c
index f7c6b4db9e..e129f86eea 100644
--- a/src/main/msc/emfat_file.c
+++ b/src/main/msc/emfat_file.c
@@ -227,7 +227,7 @@ static const char icon_file[] =
#define CMA_TIME EMFAT_ENCODE_CMA_TIME(1,1,2018, 13,0,0)
#define CMA { CMA_TIME, CMA_TIME, CMA_TIME }
-#if defined (USE_EMFAT_AUTORUN) || defined (USE_EMFAT_ICON) || defined (USE_EMFAT_README)
+#if defined(USE_EMFAT_AUTORUN) || defined(USE_EMFAT_ICON) || defined(USE_EMFAT_README)
static void memory_read_proc(uint8_t *dest, int size, uint32_t offset, emfat_entry_t *entry)
{
int len;
diff --git a/src/main/msc/usbd_msc_desc.c b/src/main/msc/usbd_msc_desc.c
index 2c61361273..9d5e7f954b 100644
--- a/src/main/msc/usbd_msc_desc.c
+++ b/src/main/msc/usbd_msc_desc.c
@@ -100,7 +100,7 @@ USBD_DEVICE MSC_desc =
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
- #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
@@ -128,7 +128,7 @@ __ALIGN_BEGIN uint8_t USBD_DeviceDesc_MSC[USB_SIZ_DEVICE_DESC] __ALIGN_END =
} ; /* USB_DeviceDescriptor */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
- #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
@@ -148,7 +148,7 @@ __ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc_MSC[USB_LEN_DEV_QUALIFIER_DESC] _
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
- #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
@@ -168,7 +168,7 @@ uint8_t USBD_StringSerial_MSC[USB_SIZ_STRING_SERIAL] =
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
- #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
diff --git a/src/main/platform.h b/src/main/platform.h
index 00b01bc24e..918983a16e 100644
--- a/src/main/platform.h
+++ b/src/main/platform.h
@@ -26,144 +26,31 @@
#pragma GCC poison sprintf snprintf
#endif
-// common to all
+// 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
diff --git a/src/main/startup/at32/at32f435_437.h b/src/main/startup/at32/at32f435_437.h
index 636169162f..9ed25b5580 100644
--- a/src/main/startup/at32/at32f435_437.h
+++ b/src/main/startup/at32/at32f435_437.h
@@ -31,7 +31,7 @@
extern "C" {
#endif
-#if defined (__CC_ARM)
+#if defined(__CC_ARM)
#pragma anon_unions
#endif
@@ -53,30 +53,30 @@ extern "C" {
* devices, you can define the device in your toolchain compiler preprocessor.
*/
-#if !defined (AT32F435CCU7) && !defined (AT32F435CGU7) && !defined (AT32F435CMU7) && \
- !defined (AT32F435CCT7) && !defined (AT32F435CGT7) && !defined (AT32F435CMT7) && \
- !defined (AT32F435RCT7) && !defined (AT32F435RGT7) && !defined (AT32F435RMT7) && \
- !defined (AT32F435VCT7) && !defined (AT32F435VGT7) && !defined (AT32F435VMT7) && \
- !defined (AT32F435ZCT7) && !defined (AT32F435ZGT7) && !defined (AT32F435ZMT7) && \
- !defined (AT32F437RCT7) && !defined (AT32F437RGT7) && !defined (AT32F437RMT7) && \
- !defined (AT32F437VCT7) && !defined (AT32F437VGT7) && !defined (AT32F437VMT7) && \
- !defined (AT32F437ZCT7) && !defined (AT32F437ZGT7) && !defined (AT32F437ZMT7)
+#if !defined(AT32F435CCU7) && !defined(AT32F435CGU7) && !defined(AT32F435CMU7) && \
+ !defined(AT32F435CCT7) && !defined(AT32F435CGT7) && !defined(AT32F435CMT7) && \
+ !defined(AT32F435RCT7) && !defined(AT32F435RGT7) && !defined(AT32F435RMT7) && \
+ !defined(AT32F435VCT7) && !defined(AT32F435VGT7) && !defined(AT32F435VMT7) && \
+ !defined(AT32F435ZCT7) && !defined(AT32F435ZGT7) && !defined(AT32F435ZMT7) && \
+ !defined(AT32F437RCT7) && !defined(AT32F437RGT7) && !defined(AT32F437RMT7) && \
+ !defined(AT32F437VCT7) && !defined(AT32F437VGT7) && !defined(AT32F437VMT7) && \
+ !defined(AT32F437ZCT7) && !defined(AT32F437ZGT7) && !defined(AT32F437ZMT7)
#error "Please select first the target device used in your application (in at32f435_437.h file)"
#endif
-#if defined (AT32F435CCU7) || defined (AT32F435CGU7) || defined (AT32F435CMU7) || \
- defined (AT32F435CCT7) || defined (AT32F435CGT7) || defined (AT32F435CMT7) || \
- defined (AT32F435RCT7) || defined (AT32F435RGT7) || defined (AT32F435RMT7) || \
- defined (AT32F435VCT7) || defined (AT32F435VGT7) || defined (AT32F435VMT7) || \
- defined (AT32F435ZCT7) || defined (AT32F435ZGT7) || defined (AT32F435ZMT7)
+#if defined(AT32F435CCU7) || defined(AT32F435CGU7) || defined(AT32F435CMU7) || \
+ defined(AT32F435CCT7) || defined(AT32F435CGT7) || defined(AT32F435CMT7) || \
+ defined(AT32F435RCT7) || defined(AT32F435RGT7) || defined(AT32F435RMT7) || \
+ defined(AT32F435VCT7) || defined(AT32F435VGT7) || defined(AT32F435VMT7) || \
+ defined(AT32F435ZCT7) || defined(AT32F435ZGT7) || defined(AT32F435ZMT7)
#define AT32F435xx
#endif
-#if defined (AT32F437RCT7) || defined (AT32F437RGT7) || defined (AT32F437RMT7) || \
- defined (AT32F437VCT7) || defined (AT32F437VGT7) || defined (AT32F437VMT7) || \
- defined (AT32F437ZCT7) || defined (AT32F437ZGT7) || defined (AT32F437ZMT7)
+#if defined(AT32F437RCT7) || defined(AT32F437RGT7) || defined(AT32F437RMT7) || \
+ defined(AT32F437VCT7) || defined(AT32F437VGT7) || defined(AT32F437VMT7) || \
+ defined(AT32F437ZCT7) || defined(AT32F437ZGT7) || defined(AT32F437ZMT7)
#define AT32F437xx
#endif
@@ -84,8 +84,8 @@ extern "C" {
#ifndef USE_STDPERIPH_DRIVER
/**
* @brief comment the line below if you will not use the peripherals drivers.
- * in this case, these drivers will not be included and the application code will
- * be based on direct access to peripherals registers
+ * in this case, these drivers will not be included and the application code will
+ * be based on direct access to peripherals registers
*/
#ifdef _RTE_
#include "RTE_Components.h"
@@ -162,7 +162,7 @@ typedef enum IRQn
EDMA_Stream6_IRQn = 16, /*!< edma stream 6 global interrupt */
EDMA_Stream7_IRQn = 17, /*!< edma stream 7 global interrupt */
-#if defined (AT32F435xx)
+#if defined(AT32F435xx)
ADC1_2_3_IRQn = 18, /*!< adc1 adc2 and adc3 global interrupt */
CAN1_TX_IRQn = 19, /*!< can1 tx interrupts */
CAN1_RX0_IRQn = 20, /*!< can1 rx0 interrupts */
@@ -241,7 +241,7 @@ typedef enum IRQn
DMA2_Channel7_IRQn = 114, /*!< dma1 channel 7 global interrupt */
#endif
-#if defined (AT32F437xx)
+#if defined(AT32F437xx)
ADC1_2_3_IRQn = 18, /*!< adc1 adc2 and adc3 global interrupt */
CAN1_TX_IRQn = 19, /*!< can1 tx interrupts */
CAN1_RX0_IRQn = 20, /*!< can1 rx0 interrupts */
@@ -334,7 +334,7 @@ typedef enum IRQn
/** @addtogroup Exported_types
* @{
- */
+ */
typedef int32_t INT32;
typedef int16_t INT16;
@@ -431,7 +431,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
#define AHBPERIPH1_BASE (PERIPH_BASE + 0x20000)
#define AHBPERIPH2_BASE (PERIPH_BASE + 0x10000000)
-#if defined (AT32F435xx)
+#if defined(AT32F435xx)
/* apb1 bus base address */
#define UART8_BASE (APB1PERIPH_BASE + 0x7C00)
#define UART7_BASE (APB1PERIPH_BASE + 0x7800)
@@ -557,7 +557,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
#define EDMA_STREAM6_2D_BASE (EDMA_2D_BASE + 0x002C)
#define EDMA_STREAM7_2D_BASE (EDMA_2D_BASE + 0x0034)
#define EDMA_STREAM8_2D_BASE (EDMA_2D_BASE + 0x003C)
-
+
#define EDMA_LL_BASE (EDMA_BASE + 0x00D0)
#define EDMA_STREAM1_LL_BASE (EDMA_LL_BASE + 0x0004)
#define EDMA_STREAM2_LL_BASE (EDMA_LL_BASE + 0x0008)
@@ -591,7 +591,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
#define OTGFS1_BASE (AHBPERIPH2_BASE + 0x00000)
#endif
-#if defined (AT32F437xx)
+#if defined(AT32F437xx)
/* apb1 bus base address */
#define UART8_BASE (APB1PERIPH_BASE + 0x7C00)
#define UART7_BASE (APB1PERIPH_BASE + 0x7800)
diff --git a/src/main/startup/at32/system_at32f435_437.c b/src/main/startup/at32/system_at32f435_437.c
index 8d2dbddf91..6f4c7aae4b 100644
--- a/src/main/startup/at32/system_at32f435_437.c
+++ b/src/main/startup/at32/system_at32f435_437.c
@@ -64,7 +64,7 @@ unsigned int system_core_clock = HICK_VALUE; /*!< system clock frequen
*/
void SystemInit (void)
{
-#if defined (__FPU_USED) && (__FPU_USED == 1U)
+#if defined(__FPU_USED) && (__FPU_USED == 1U)
SCB->CPACR |= ((3U << 10U * 2U) | /* set cp10 full access */
(3U << 11U * 2U) ); /* set cp11 full access */
#endif
diff --git a/src/main/startup/system_stm32h7xx.c b/src/main/startup/system_stm32h7xx.c
index 890ed7ee57..1b3de91b2f 100644
--- a/src/main/startup/system_stm32h7xx.c
+++ b/src/main/startup/system_stm32h7xx.c
@@ -153,7 +153,7 @@
/** @addtogroup STM32H7xx_System_Private_FunctionPrototypes
* @{
*/
-#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
static void SystemInit_ExtMemCtl(void);
#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
@@ -809,7 +809,7 @@ void SystemInit (void)
/* Change the switch matrix read issuing capability to 1 for the AXI SRAM target (Target 7) */
*((__IO uint32_t*)0x51008108) = 0x00000001;
-#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
SystemInit_ExtMemCtl();
#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
@@ -905,7 +905,7 @@ void SystemCoreClockUpdate (void)
SystemCoreClock = HAL_RCC_GetSysClockFreq();
}
-#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
/**
* @brief Setup the external memory controller.
* Called in startup_stm32h7xx.s before jump to main.
@@ -916,7 +916,7 @@ void SystemCoreClockUpdate (void)
*/
void SystemInit_ExtMemCtl(void)
{
-#if defined (DATA_IN_ExtSDRAM)
+#if defined(DATA_IN_ExtSDRAM)
register uint32_t tmpreg = 0, timeout = 0xFFFF;
register __IO uint32_t index;
diff --git a/src/main/target/AT32F435/target.mk b/src/main/target/AT32F435/target.mk
index 80633b20ab..d8c917d59c 100644
--- a/src/main/target/AT32F435/target.mk
+++ b/src/main/target/AT32F435/target.mk
@@ -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))) \
diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h
index 971059f570..747ee0236f 100644
--- a/src/main/target/common_post.h
+++ b/src/main/target/common_post.h
@@ -33,15 +33,15 @@
CLOUD_BUILD and CORE_BUILD should not be referenced here.
- NOTE: for 4.5 we will be removing any conditions related to specific MCU types, instead
+ NOTE: for 4.5 we will be removing any conditions related to specific MCU types, instead
these should be defined in the target.h or in a file that is imported by target.h (in the
case of common settings for a given MCU group)
-
+
*/
/*
BEGIN HARDWARE INCLUSIONS
-
+
Simplified options for the moment, i.e. adding USE_MAG or USE_BARO and the entire driver suite is added.
In the future we can move to specific drivers being added only - to save flash space.
*/
@@ -482,7 +482,7 @@ extern uint8_t __config_end;
#endif
#endif
-#if defined(USE_RX_SPI) || defined (USE_SERIALRX_SRXL2)
+#if defined(USE_RX_SPI) || defined(USE_SERIALRX_SRXL2)
#define USE_RX_BIND
#endif
diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h
index d44c1ddd68..16fff68104 100644
--- a/src/main/target/common_pre.h
+++ b/src/main/target/common_pre.h
@@ -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
diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c
index f52a650455..ea1e6eb2c3 100644
--- a/src/main/telemetry/hott.c
+++ b/src/main/telemetry/hott.c
@@ -86,7 +86,7 @@
#include "telemetry/hott.h"
#include "telemetry/telemetry.h"
-#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
+#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
#include "scheduler/scheduler.h"
#include "io/displayport_hott.h"
@@ -129,7 +129,7 @@ static portSharing_e hottPortSharing;
static HOTT_GPS_MSG_t hottGPSMessage;
static HOTT_EAM_MSG_t hottEAMMessage;
-#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
+#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
static hottTextModeMsg_t hottTextModeMessage;
static bool textmodeIsAlive = false;
static int32_t telemetryTaskPeriod = 0;
@@ -176,7 +176,7 @@ static void initialiseMessages(void)
#ifdef USE_GPS
initialiseGPSMessage(&hottGPSMessage, sizeof(hottGPSMessage));
#endif
-#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
+#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
initialiseTextmodeMessage(&hottTextModeMessage);
#endif
}
@@ -351,7 +351,7 @@ void initHoTTTelemetry(void)
hottPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_HOTT);
-#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
+#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
hottDisplayportRegister();
#endif
@@ -459,7 +459,7 @@ static void hottPrepareMessages(void)
#endif
}
-#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
+#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
static void hottTextmodeStart(void)
{
// Increase menu speed
@@ -538,7 +538,7 @@ static void processHottTextModeRequest(const uint8_t cmd)
static void processBinaryModeRequest(uint8_t address)
{
-#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
+#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
if (textmodeIsAlive) {
hottTextmodeStop();
textmodeIsAlive = false;
@@ -622,7 +622,7 @@ static void hottCheckSerialData(uint32_t currentMicros)
*/
processBinaryModeRequest(address);
}
-#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
+#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
else if (requestId == HOTTV4_TEXT_MODE_REQUEST_ID) {
processHottTextModeRequest(address);
}
diff --git a/src/main/telemetry/hott.h b/src/main/telemetry/hott.h
index e3be8aa7c2..46d3b85e7d 100644
--- a/src/main/telemetry/hott.h
+++ b/src/main/telemetry/hott.h
@@ -501,7 +501,7 @@ void initHoTTTelemetry(void);
void configureHoTTTelemetryPort(void);
void freeHoTTTelemetryPort(void);
-#if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
+#if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
bool hottTextmodeIsAlive();
void hottTextmodeGrab();
void hottTextmodeExit();
diff --git a/src/main/telemetry/srxl.c b/src/main/telemetry/srxl.c
index cd244d8157..319a1edf9a 100644
--- a/src/main/telemetry/srxl.c
+++ b/src/main/telemetry/srxl.c
@@ -462,7 +462,7 @@ bool srxlFrameFlightPackCurrent(sbuf_t *dst, timeUs_t currentTimeUs)
return false;
}
-#if defined (USE_SPEKTRUM_CMS_TELEMETRY) && defined (USE_CMS)
+#if defined(USE_SPEKTRUM_CMS_TELEMETRY) && defined(USE_CMS)
// Betaflight CMS using Spektrum Tx telemetry TEXT_GEN sensor as display.
@@ -691,7 +691,7 @@ static bool srxlFrameVTX(sbuf_t *dst, timeUs_t currentTimeUs)
#define SRXL_GPS_STAT_COUNT 0
#endif
-#if defined (USE_SPEKTRUM_CMS_TELEMETRY) && defined (USE_CMS)
+#if defined(USE_SPEKTRUM_CMS_TELEMETRY) && defined(USE_CMS)
#define SRXL_SCHEDULE_CMS_COUNT 1
#else
#define SRXL_SCHEDULE_CMS_COUNT 0
@@ -721,7 +721,7 @@ const srxlScheduleFnPtr srxlScheduleFuncs[SRXL_TOTAL_COUNT] = {
#if defined(USE_SPEKTRUM_VTX_TELEMETRY) && defined(USE_SPEKTRUM_VTX_CONTROL) && defined(USE_VTX_COMMON)
srxlFrameVTX,
#endif
-#if defined (USE_SPEKTRUM_CMS_TELEMETRY) && defined (USE_CMS)
+#if defined(USE_SPEKTRUM_CMS_TELEMETRY) && defined(USE_CMS)
srxlFrameText,
#endif
};
@@ -742,7 +742,7 @@ static void processSrxl(timeUs_t currentTimeUs)
srxlFnPtr = srxlScheduleFuncs[srxlScheduleIndex + srxlScheduleUserIndex];
srxlScheduleUserIndex = (srxlScheduleUserIndex + 1) % SRXL_SCHEDULE_USER_COUNT;
-#if defined (USE_SPEKTRUM_CMS_TELEMETRY) && defined (USE_CMS)
+#if defined(USE_SPEKTRUM_CMS_TELEMETRY) && defined(USE_CMS)
// Boost CMS performance by sending nothing else but CMS Text frames when in a CMS menu.
// Sideeffect, all other reports are still not sent if user leaves CMS without a proper EXIT.
if (cmsInMenu &&
diff --git a/src/main/vcp/stm32_it.c b/src/main/vcp/stm32_it.c
index ee783ec7b0..3574c9e58b 100644
--- a/src/main/vcp/stm32_it.c
+++ b/src/main/vcp/stm32_it.c
@@ -143,7 +143,7 @@ void PendSV_Handler(void)
* Output : None
* Return : None
*******************************************************************************/
-#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)|| defined (STM32F37X)
+#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)|| defined(STM32F37X)
void USB_LP_IRQHandler(void)
#else
void USB_LP_CAN1_RX0_IRQHandler(void)
diff --git a/src/main/vcp/usb_pwr.c b/src/main/vcp/usb_pwr.c
index 5e65bc9c76..449f04d30b 100644
--- a/src/main/vcp/usb_pwr.c
+++ b/src/main/vcp/usb_pwr.c
@@ -175,7 +175,7 @@ void Suspend(void)
/* Store the new value */
PWR->CR = tmpreg;
/* Set SLEEPDEEP bit of Cortex System Control Register */
-#if defined (STM32F303xC) || defined (STM32F37X)
+#if defined(STM32F303xC) || defined(STM32F37X)
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
#else
SCB->SCR |= SCB_SCR_SLEEPDEEP;
@@ -184,7 +184,7 @@ void Suspend(void)
if ((_GetISTR() & ISTR_WKUP) == 0) {
__WFI();
/* Reset SLEEPDEEP bit of Cortex System Control Register */
-#if defined (STM32F303xC) || defined (STM32F37X)
+#if defined(STM32F303xC) || defined(STM32F37X)
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
#else
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP);
@@ -202,7 +202,7 @@ void Suspend(void)
PWR->CR = savePWR_CR;
/* Reset SLEEPDEEP bit of Cortex System Control Register */
-#if defined (STM32F303xC) || defined (STM32F37X)
+#if defined(STM32F303xC) || defined(STM32F37X)
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
#else
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP);
diff --git a/src/main/vcp_hal/usbd_desc.c b/src/main/vcp_hal/usbd_desc.c
index e30f1b7447..9530098230 100644
--- a/src/main/vcp_hal/usbd_desc.c
+++ b/src/main/vcp_hal/usbd_desc.c
@@ -103,7 +103,7 @@ USBD_DescriptorsTypeDef VCP_Desc = {
};
/* USB Standard Device Descriptor */
-#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
__ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = {
@@ -159,7 +159,7 @@ __ALIGN_BEGIN uint8_t USBD_MSC_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END =
#endif
/* USB Standard Device Descriptor */
-#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_LEN_LANGID_STR_DESC] __ALIGN_END = {
@@ -175,7 +175,7 @@ uint8_t USBD_StringSerial[USB_SIZ_STRING_SERIAL] =
USB_DESC_TYPE_STRING,
};
-#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
__ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END;
diff --git a/src/main/vcpf4/usb_conf.h b/src/main/vcpf4/usb_conf.h
index a3cfdca483..f384f8aec4 100644
--- a/src/main/vcpf4/usb_conf.h
+++ b/src/main/vcpf4/usb_conf.h
@@ -214,9 +214,9 @@
#define __ALIGN_END
#if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
- #elif defined (__ICCARM__) /* IAR Compiler */
+ #elif defined(__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
- #elif defined (__TASKING__) /* TASKING Compiler */
+ #elif defined(__TASKING__) /* TASKING Compiler */
#define __ALIGN_BEGIN __align(4)
#endif /* __CC_ARM */
#endif /* __GNUC__ */
@@ -226,15 +226,15 @@
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* __packed keyword used to decrease the data type alignment to 1-byte */
-#if defined (__CC_ARM) /* ARM Compiler */
+#if defined(__CC_ARM) /* ARM Compiler */
#define __packed __packed
-#elif defined (__ICCARM__) /* IAR Compiler */
+#elif defined(__ICCARM__) /* IAR Compiler */
#define __packed __packed
-#elif defined ( __GNUC__ ) /* GNU Compiler */
+#elif defined( __GNUC__ ) /* GNU Compiler */
#ifndef __packed
#define __packed __attribute__ ((__packed__))
#endif
-#elif defined (__TASKING__) /* TASKING Compiler */
+#elif defined(__TASKING__) /* TASKING Compiler */
#define __packed __unaligned
#endif /* __CC_ARM */
diff --git a/src/main/vcpf4/usbd_desc.c b/src/main/vcpf4/usbd_desc.c
index 2e6c40f402..839d8196c9 100644
--- a/src/main/vcpf4/usbd_desc.c
+++ b/src/main/vcpf4/usbd_desc.c
@@ -118,7 +118,7 @@ USBD_DEVICE USR_desc =
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
- #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
@@ -163,7 +163,7 @@ __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_SIZ_DEVICE_DESC] __ALIGN_END =
} ; /* USB_DeviceDescriptor */
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
- #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
@@ -183,7 +183,7 @@ __ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALI
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
- #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #if defined( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */