diff --git a/src/main/target/REVO/SOULF4.mk b/src/main/target/REVO/SOULF4.mk
new file mode 100644
index 000000000..e69de29bb
diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h
index c18dae8b0..1bf49e84d 100644
--- a/src/main/target/REVO/target.h
+++ b/src/main/target/REVO/target.h
@@ -20,20 +20,24 @@
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
#if defined(AIRBOTF4)
-#define TARGET_BOARD_IDENTIFIER "AIR4"
-#define USBD_PRODUCT_STRING "AirbotF4"
+ #define TARGET_BOARD_IDENTIFIER "AIR4"
+ #define USBD_PRODUCT_STRING "AirbotF4"
#elif defined(REVOLT)
-#define TARGET_BOARD_IDENTIFIER "RVLT"
-#define USBD_PRODUCT_STRING "Revolt"
+ #define TARGET_BOARD_IDENTIFIER "RVLT"
+ #define USBD_PRODUCT_STRING "Revolt"
+
+#elif defined(SOULF4)
+ #define TARGET_BOARD_IDENTIFIER "SOUL"
+ #define USBD_PRODUCT_STRING "DemonSoulF4"
#else
-#define TARGET_BOARD_IDENTIFIER "REVO"
-#define USBD_PRODUCT_STRING "Revolution"
+ #define TARGET_BOARD_IDENTIFIER "REVO"
+ #define USBD_PRODUCT_STRING "Revolution"
-#ifdef OPBL
-#define USBD_SERIALNUMBER_STRING "0x8020000"
-#endif
+ #ifdef OPBL
+ #define USBD_SERIALNUMBER_STRING "0x8020000"
+ #endif
#endif
@@ -43,14 +47,14 @@
#define LED0 PB5
// Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper
#if defined(AIRBOTF4)
-#define BEEPER PB4
-#define BEEPER_INVERTED
+ #define BEEPER PB4
+ #define BEEPER_INVERTED
#elif defined(REVOLT)
-#define BEEPER PB4
+ #define BEEPER PB4
#else
-#define LED1 PB4
-// Leave beeper here but with none as io - so disabled unless mapped.
-#define BEEPER NONE
+ #define LED1 PB4
+ // Leave beeper here but with none as io - so disabled unless mapped.
+ #define BEEPER NONE
#endif
// PC0 used as inverter select GPIO
@@ -63,41 +67,47 @@
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
-#define ACC
-#define USE_ACC_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#if defined(SOULF4)
+ #define ACC
+ #define USE_ACC_SPI_MPU6000
+ #define GYRO_MPU6000_ALIGN CW180_DEG
-#define USE_ACC_MPU6500
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+ #define GYRO
+ #define USE_GYRO_SPI_MPU6000
+ #define ACC_MPU6000_ALIGN CW180_DEG
-#define GYRO
-#define USE_GYRO_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#else
+ #define ACC
+ #define USE_ACC_SPI_MPU6000
+ #define GYRO_MPU6000_ALIGN CW270_DEG
-#define USE_GYRO_MPU6500
-#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU9250_ALIGN CW270_DEG
+ #define USE_ACC_MPU6500
+ #define USE_ACC_SPI_MPU6500
+ #define ACC_MPU6500_ALIGN CW270_DEG
+
+ #define GYRO
+ #define USE_GYRO_SPI_MPU6000
+ #define ACC_MPU6000_ALIGN CW270_DEG
+
+ #define USE_GYRO_MPU6500
+ #define USE_GYRO_SPI_MPU6500
+ #define GYRO_MPU6500_ALIGN CW270_DEG
+
+#endif
// MPU6000 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
-#if !defined(AIRBOTF4) && !defined(REVOLT)
-#define MAG
-#define USE_MAG_HMC5883
-#define MAG_HMC5883_ALIGN CW90_DEG
+#if !defined(AIRBOTF4) && !defined(REVOLT) && !defined(SOULF4)
+ #define MAG
+ #define USE_MAG_HMC5883
+ #define MAG_HMC5883_ALIGN CW90_DEG
-//#define USE_MAG_NAZA
-//#define MAG_NAZA_ALIGN CW180_DEG_FLIP
+ #define BARO
+ #define USE_BARO_MS5611
-#define BARO
-#define USE_BARO_MS5611
-
-//#define PITOT
-//#define USE_PITOT_MS4525
-//#define MS4525_BUS I2C_DEVICE_EXT
#endif
#define M25P16_CS_PIN PB3
diff --git a/src/main/target/SOULF4/target.c b/src/main/target/SOULF4/target.c
deleted file mode 100644
index 3428d2e6a..000000000
--- a/src/main/target/SOULF4/target.c
+++ /dev/null
@@ -1,39 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it and/or modify
- * it 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 is distributed in the hope that it 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 Cleanflight. If not, see .
- */
-
-#include
-
-#include
-#include "drivers/io.h"
-#include "drivers/timer.h"
-#include "drivers/timer_def.h"
-#include "drivers/dma.h"
-
-const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // PPM (5th pin on FlexiIO port)
- DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN - GPIO_PartialRemap_TIM3
- DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0 ), // S3_IN
- DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0 ), // S4_IN
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S5_IN
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S6_IN
- DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0 ), // S1_OUT
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0 ), // S2_OUT
- DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 0 ), // S3_OUT
- DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0 ), // S4_OUT
- DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 1, 0 ), // S5_OUT - GPIO_PartialRemap_TIM3
- DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_LED, 1, 0 ), // S6_OUT
-};
diff --git a/src/main/target/SOULF4/target.h b/src/main/target/SOULF4/target.h
deleted file mode 100644
index db3d32eef..000000000
--- a/src/main/target/SOULF4/target.h
+++ /dev/null
@@ -1,122 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it and/or modify
- * it 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 is distributed in the hope that it 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 Cleanflight. If not, see .
- */
-
-#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "SOUL"
-
-#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
-
-#define USBD_PRODUCT_STRING "DemonSoulF4"
-#ifdef OPBL
-#define USBD_SERIALNUMBER_STRING "0x8020000"
-#endif
-
-#define LED0 PB5
-#define LED1 PB4
-
-#define BEEPER PB6
-#define BEEPER_INVERTED
-
-#define INVERTER PC0 // PC0 used as inverter select GPIO
-#define INVERTER_USART USART1
-
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
-#define ACC
-#define USE_ACC_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
-
-#define GYRO
-#define USE_GYRO_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-
-// MPU6000 interrupts
-#define USE_EXTI
-#define MPU_INT_EXTI PC4
-#define USE_MPU_DATA_READY_SIGNAL
-#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled)
-
-
-#define M25P16_CS_PIN PB3
-#define M25P16_SPI_INSTANCE SPI3
-
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-
-#define USE_VCP
-#define VBUS_SENSING_PIN PC5
-
-#define USE_UART1
-#define UART1_RX_PIN PA10
-#define UART1_TX_PIN PA9
-#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
-
-#define USE_UART3
-#define UART3_RX_PIN PB11
-#define UART3_TX_PIN PB10
-
-#define USE_UART6
-#define UART6_RX_PIN PC7
-#define UART6_TX_PIN PC6
-
-#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
-
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
-
-#define USE_SPI
-
-#define USE_SPI_DEVICE_1
-
-#define USE_SPI_DEVICE_3
-#define SPI3_NSS_PIN PB3
-#define SPI3_SCK_PIN PC10
-#define SPI3_MISO_PIN PC11
-#define SPI3_MOSI_PIN PC12
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_1)
-
-#define USE_ADC
-#define VBAT_ADC_PIN PC2
-
-
-#define SENSORS_SET (SENSOR_ACC)
-
-#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX)
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define SERIALRX_PROVIDER SERIALRX_SBUS
-
-#define LED_STRIP
-#define USE_DSHOT
-#define USE_ESC_TELEMETRY
-
-#define SPEKTRUM_BIND
-// USART3,
-#define BIND_PIN PB11
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD 0xffff
-
-#define USABLE_TIMER_CHANNEL_COUNT 12
-#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )
diff --git a/src/main/target/SOULF4/target.mk b/src/main/target/SOULF4/target.mk
deleted file mode 100644
index 0b39ad097..000000000
--- a/src/main/target/SOULF4/target.mk
+++ /dev/null
@@ -1,6 +0,0 @@
-F405_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH
-
-TARGET_SRC = \
- drivers/accgyro_spi_mpu6000.c
-