diff --git a/src/main/target/DYSF4/CMakeLists.txt b/src/main/target/DYSF4/CMakeLists.txt
new file mode 100644
index 00000000000..ec00b5acc49
--- /dev/null
+++ b/src/main/target/DYSF4/CMakeLists.txt
@@ -0,0 +1,2 @@
+target_stm32f405xg(DYSF4PRO)
+target_stm32f405xg(DYSF4PROV2)
diff --git a/src/main/target/DYSF4/target.c b/src/main/target/DYSF4/target.c
new file mode 100644
index 00000000000..d6de2e9bf25
--- /dev/null
+++ b/src/main/target/DYSF4/target.c
@@ -0,0 +1,47 @@
+/*
+ * 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/pwm_mapping.h"
+#include "drivers/timer.h"
+#include "drivers/bus.h"
+
+timerHardware_t timerHardware[] = {
+
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2
+ DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D1_ST6
+ DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1
+
+ // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_OUTPUT_AUTO }, // MOTOR_3
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT MOTOR, SERVO or LED
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT
+
+
+ // DEF_TIM(TIM12, CH1, PB14, TIM_USE_PPM, 0, 0), // PPM
+ DEF_TIM(TIM12, CH2, PB15, TIM_USE_ANY, 0, 0), // S2_IN
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), // S3_IN, UART6_TX
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // S4_IN, UART6_RX
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // S5_IN
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), // S6_IN
+
+};
+
+const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
diff --git a/src/main/target/DYSF4/target.h b/src/main/target/DYSF4/target.h
new file mode 100644
index 00000000000..76e79106afa
--- /dev/null
+++ b/src/main/target/DYSF4/target.h
@@ -0,0 +1,159 @@
+/*
+ * 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
+
+// This directory contains: DYSF4PRO, DYSF4PROV2
+
+#if defined(DYSF4PRO)
+#define TARGET_BOARD_IDENTIFIER "DYS4"
+#elif defined(DYSF4PROV2)
+#define TARGET_BOARD_IDENTIFIER "DY42"
+#endif
+
+#define USBD_PRODUCT_STRING "DysF4Pro"
+
+#define LED0 PB5
+
+#define BEEPER PB4
+#define BEEPER_INVERTED
+
+#if defined(DYSF4PROV2)
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+#define I2C_EXT_BUS BUS_I2C1
+#else
+#define USE_I2C
+#define USE_I2C_DEVICE_2
+#define I2C_DEVICE_2_SHARES_UART3
+#define I2C_EXT_BUS BUS_I2C2
+#endif
+
+#define UG2864_I2C_BUS I2C_EXT_BUS
+
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_BUS BUS_SPI1
+
+#define USE_IMU_MPU6000
+#define IMU_MPU6000_ALIGN CW180_DEG
+
+#define USE_MAG
+#define MAG_I2C_BUS I2C_EXT_BUS
+#define USE_MAG_ALL
+
+#define TEMPERATURE_I2C_BUS I2C_EXT_BUS
+
+#define USE_BARO
+#define BARO_I2C_BUS I2C_EXT_BUS
+#define USE_BARO_BMP085
+#define USE_BARO_BMP280
+#define USE_BARO_MS5611
+
+#define PITOT_I2C_BUS I2C_EXT_BUS
+
+#define USE_RANGEFINDER
+#define RANGEFINDER_I2C_BUS I2C_EXT_BUS
+
+#define USE_VCP
+#define VBUS_SENSING_PIN PC5
+#define VBUS_SENSING_ENABLED
+
+
+#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 USE_SOFTSERIAL1
+#define SOFTSERIAL_1_RX_PIN PC8
+#define SOFTSERIAL_1_TX_PIN PC9
+
+#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
+
+#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
+#define SERIALRX_PROVIDER SERIALRX_SBUS
+#define SERIALRX_UART SERIAL_PORT_USART1
+
+#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_MAX7456
+#define MAX7456_SPI_BUS BUS_SPI3
+#define MAX7456_CS_PIN PA15
+
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+#define M25P16_CS_PIN SPI3_NSS_PIN
+#define M25P16_SPI_BUS BUS_SPI3
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+
+#define USE_ADC
+#define ADC_CHANNEL_1_PIN PC1
+#define ADC_CHANNEL_2_PIN PC2
+
+#ifdef DYSF4PRO
+ #define ADC_CHANNEL_3_PIN PC3
+#else
+ #define ADC_CHANNEL_3_PIN PA0
+#endif
+
+#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
+#define VBAT_ADC_CHANNEL ADC_CHN_2
+#define RSSI_ADC_CHANNEL ADC_CHN_3
+
+#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
+
+#define USE_LED_STRIP
+#define WS2811_PIN PA1
+
+#define DISABLE_RX_PWM_FEATURE
+#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)
+
+#define USE_SPEKTRUM_BIND
+#define BIND_PIN PB11 // USART3 RX
+
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+// Number of available PWM outputs
+#define MAX_PWM_OUTPUT_PORTS 6
+#define TARGET_MOTOR_COUNT 6
+#define USE_DSHOT
+#define USE_ESC_SENSOR
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+
diff --git a/src/main/target/OMNIBUSF4/CMakeLists.txt b/src/main/target/OMNIBUSF4/CMakeLists.txt
index a6ccb483bf5..28f13c7cd5b 100644
--- a/src/main/target/OMNIBUSF4/CMakeLists.txt
+++ b/src/main/target/OMNIBUSF4/CMakeLists.txt
@@ -1,11 +1 @@
-target_stm32f405xg(DYSF4PRO)
-target_stm32f405xg(DYSF4PROV2)
target_stm32f405xg(OMNIBUSF4)
-# the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping
-target_stm32f405xg(OMNIBUSF4PRO)
-target_stm32f405xg(OMNIBUSF4V3_S5_S6_2SS)
-target_stm32f405xg(OMNIBUSF4V3_S5S6_SS)
-target_stm32f405xg(OMNIBUSF4V3_S6_SS)
-# OMNIBUSF4V3 is a (almost identical) variant of OMNIBUSF4PRO target,
-# except for an inverter on UART6.
-target_stm32f405xg(OMNIBUSF4V3)
diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c
index be85e9fbce3..d6de2e9bf25 100644
--- a/src/main/target/OMNIBUSF4/target.c
+++ b/src/main/target/OMNIBUSF4/target.c
@@ -31,36 +31,16 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1
// { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_OUTPUT_AUTO }, // MOTOR_3
-#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !(defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS))
-
- DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT
-#elif defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
- DEF_TIM(TIM5, CH2, PA1, TIM_USE_ANY, 0, 0), // S5_OUT SOFTSERIAL
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL
-#elif defined(OMNIBUSF4V3_S6_SS)
- DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL
-#else
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT MOTOR, SERVO or LED
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT
-#endif
-#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3))
- DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4)
-#endif
-#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
- // DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
- DEF_TIM(TIM4, CH4, PB9, TIM_USE_ANY, 0, 0), // S2_IN
-#else
// DEF_TIM(TIM12, CH1, PB14, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM12, CH2, PB15, TIM_USE_ANY, 0, 0), // S2_IN
-#endif
DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), // S3_IN, UART6_TX
DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // S4_IN, UART6_RX
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // S5_IN // pad labelled CH5 on OMNIBUSF4PRO
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), // S6_IN // pad labelled CH6 on OMNIBUSF4PRO
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // S5_IN
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), // S6_IN
};
diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h
index 2c5a27afbb6..48bdfb7f910 100644
--- a/src/main/target/OMNIBUSF4/target.h
+++ b/src/main/target/OMNIBUSF4/target.h
@@ -17,77 +17,27 @@
#pragma once
-//Same target as OMNIBUSF4PRO with LED strip in M5
-#ifdef OMNIBUSF4PRO_LEDSTRIPM5
-#define OMNIBUSF4PRO
-#endif
-//Same target as OMNIBUSF4V3 with softserial in M5 and M6
-#if defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
-#define OMNIBUSF4V3
-#endif
-
-#ifdef OMNIBUSF4PRO
-#define TARGET_BOARD_IDENTIFIER "OBSD"
-#elif defined(OMNIBUSF4V3)
-#define TARGET_BOARD_IDENTIFIER "OB43"
-#elif defined(DYSF4PRO)
-#define TARGET_BOARD_IDENTIFIER "DYS4"
-#elif defined(DYSF4PROV2)
-#define TARGET_BOARD_IDENTIFIER "DY42"
-#else
#define TARGET_BOARD_IDENTIFIER "OBF4"
-#endif
-#if defined(DYSF4PRO) || defined(DYSF4PROV2)
-#define USBD_PRODUCT_STRING "DysF4Pro"
-#else
#define USBD_PRODUCT_STRING "Omnibus F4"
-#endif
#define LED0 PB5
#define BEEPER PB4
#define BEEPER_INVERTED
-#if defined(DYSF4PROV2)
-#define USE_I2C
-#define USE_I2C_DEVICE_1
-#define I2C1_SCL PB8
-#define I2C1_SDA PB9
-#define I2C_EXT_BUS BUS_I2C1
-#else
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C_DEVICE_2_SHARES_UART3
#define I2C_EXT_BUS BUS_I2C2
-#endif
#define UG2864_I2C_BUS I2C_EXT_BUS
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
-#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
- #define USE_IMU_MPU6000
- #define IMU_MPU6000_ALIGN CW270_DEG
-#else
- #define USE_IMU_MPU6000
- #define IMU_MPU6000_ALIGN CW180_DEG
-#endif
-
-// Support for OMNIBUS F4 PRO CORNER - it has ICM20608 instead of MPU6000
-#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
- #define MPU6500_CS_PIN MPU6000_CS_PIN
- #define MPU6500_SPI_BUS MPU6000_SPI_BUS
- #define USE_IMU_MPU6500
- #define IMU_MPU6500_ALIGN IMU_MPU6000_ALIGN
-
- //BMI270
- #define USE_IMU_BMI270
- #define IMU_BMI270_ALIGN IMU_MPU6000_ALIGN
- #define BMI270_SPI_BUS MPU6000_SPI_BUS
- #define BMI270_CS_PIN MPU6000_CS_PIN
-#endif
+#define USE_IMU_MPU6000
+#define IMU_MPU6000_ALIGN CW180_DEG
#define USE_MAG
#define MAG_I2C_BUS I2C_EXT_BUS
@@ -96,21 +46,10 @@
#define TEMPERATURE_I2C_BUS I2C_EXT_BUS
#define USE_BARO
-
-#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
- #define USE_BARO_BMP280
- #define BMP280_SPI_BUS BUS_SPI3
- #define BMP280_CS_PIN PB3 // v1
- // Support external barometers
- #define BARO_I2C_BUS I2C_EXT_BUS
- #define USE_BARO_BMP085
- #define USE_BARO_MS5611
-#else
- #define BARO_I2C_BUS I2C_EXT_BUS
- #define USE_BARO_BMP085
- #define USE_BARO_BMP280
- #define USE_BARO_MS5611
-#endif
+#define BARO_I2C_BUS I2C_EXT_BUS
+#define USE_BARO_BMP085
+#define USE_BARO_BMP280
+#define USE_BARO_MS5611
#define PITOT_I2C_BUS I2C_EXT_BUS
@@ -121,17 +60,11 @@
#define VBUS_SENSING_PIN PC5
#define VBUS_SENSING_ENABLED
-#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
-#define USE_UART_INVERTER
-#endif
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
-#if defined(OMNIBUSF4PRO)
-#define INVERTER_PIN_UART1_RX PC0 // PC0 has never been used as inverter control on genuine OMNIBUS F4 variants, but leave it as is since some clones actually implement it.
-#endif
#define USE_UART3
#define UART3_RX_PIN PB11
@@ -140,51 +73,13 @@
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
-#if defined(OMNIBUSF4V3)
- #define INVERTER_PIN_UART6_RX PC8
- #define INVERTER_PIN_UART6_TX PC9
-#endif
-
-#if defined(OMNIBUSF4V3) && !(defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS))
-#define USE_SOFTSERIAL1
-#define SOFTSERIAL_1_RX_PIN PC6 // shared with UART6 TX
-#define SOFTSERIAL_1_TX_PIN PC6 // shared with UART6 TX
-
-#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
-#elif defined(OMNIBUSF4V3_S6_SS) // one softserial on S6
#define USE_SOFTSERIAL1
-#define SOFTSERIAL_1_RX_PIN PA8 // S6 output
-#define SOFTSERIAL_1_TX_PIN PA8 // S6 output
+#define SOFTSERIAL_1_RX_PIN PC8
+#define SOFTSERIAL_1_TX_PIN PC9
#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
-#elif defined(OMNIBUSF4V3_S5S6_SS) // one softserial on S5/RX S6/TX
-#define USE_SOFTSERIAL1
-#define SOFTSERIAL_1_RX_PIN PA1 // S5 output
-#define SOFTSERIAL_1_TX_PIN PA8 // S6 output
-
-#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
-
-#elif defined(OMNIBUSF4V3_S5_S6_2SS) // two softserials, one on S5 and one on S6
-#define USE_SOFTSERIAL1
-#define SOFTSERIAL_1_RX_PIN PA1 // S5 output
-#define SOFTSERIAL_1_TX_PIN PA1 // S5 output
-
-#define USE_SOFTSERIAL2
-#define SOFTSERIAL_2_RX_PIN PA8 // S6 output
-#define SOFTSERIAL_2_TX_PIN PA8 // S6 output
-
-#define SERIAL_PORT_COUNT 6 // VCP, USART1, USART3, USART6, SOFTSERIAL1, SOFTSERIAL2
-
-#else // One softserial on versions other than OMNIBUSF4V3
-#define USE_SOFTSERIAL1
-#define SOFTSERIAL_1_RX_PIN PC8 // pad labelled CH5 on OMNIBUSF4PRO
-#define SOFTSERIAL_1_TX_PIN PC9 // pad labelled CH6 on OMNIBUSF4PRO
-
-#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
-#endif
-
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1
@@ -193,20 +88,9 @@
#define USE_SPI_DEVICE_1
-#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
- #define USE_SPI_DEVICE_2
- #define SPI2_NSS_PIN PB12
- #define SPI2_SCK_PIN PB13
- #define SPI2_MISO_PIN PB14
- #define SPI2_MOSI_PIN PB15
-#endif
#define USE_SPI_DEVICE_3
-#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
- #define SPI3_NSS_PIN PA15
-#else
- #define SPI3_NSS_PIN PB3
-#endif
+#define SPI3_NSS_PIN PB3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
@@ -215,33 +99,16 @@
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN PA15
-#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
- #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
- #define USE_SDCARD
- #define USE_SDCARD_SPI
-
- #define SDCARD_SPI_BUS BUS_SPI2
- #define SDCARD_CS_PIN SPI2_NSS_PIN
-
- #define SDCARD_DETECT_PIN PB7
- #define SDCARD_DETECT_INVERTED
-#else
- #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
- #define M25P16_CS_PIN SPI3_NSS_PIN
- #define M25P16_SPI_BUS BUS_SPI3
- #define USE_FLASHFS
- #define USE_FLASH_M25P16
-#endif
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+#define M25P16_CS_PIN SPI3_NSS_PIN
+#define M25P16_SPI_BUS BUS_SPI3
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC1
#define ADC_CHANNEL_2_PIN PC2
-
-#ifdef DYSF4PRO
- #define ADC_CHANNEL_3_PIN PC3
-#else
- #define ADC_CHANNEL_3_PIN PA0
-#endif
+#define ADC_CHANNEL_3_PIN PA0
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
#define VBAT_ADC_CHANNEL ADC_CHN_2
@@ -250,11 +117,7 @@
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
#define USE_LED_STRIP
-#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5)
- #define WS2811_PIN PB6
-#else
- #define WS2811_PIN PA1
-#endif
+#define WS2811_PIN PA1
#define DISABLE_RX_PWM_FEATURE
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)
@@ -275,6 +138,3 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
-#ifdef OMNIBUSF4PRO
-#define CURRENT_METER_SCALE 265
-#endif
diff --git a/src/main/target/OMNIBUSF4PRO/CMakeLists.txt b/src/main/target/OMNIBUSF4PRO/CMakeLists.txt
new file mode 100644
index 00000000000..e09984ac0a9
--- /dev/null
+++ b/src/main/target/OMNIBUSF4PRO/CMakeLists.txt
@@ -0,0 +1,5 @@
+# OMNIBUSF4PRO has SD card, BMP280 baro
+target_stm32f405xg(OMNIBUSF4PRO)
+# OMNIBUSF4V3 is similar to PRO but with UART6 inverter
+target_stm32f405xg(OMNIBUSF4V3)
+target_stm32f405xg(OMNIBUSF4V3_ICM SKIP_RELEASES)
diff --git a/src/main/target/OMNIBUSF4PRO/target.c b/src/main/target/OMNIBUSF4PRO/target.c
new file mode 100644
index 00000000000..29cb945af85
--- /dev/null
+++ b/src/main/target/OMNIBUSF4PRO/target.c
@@ -0,0 +1,48 @@
+/*
+ * 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/pwm_mapping.h"
+#include "drivers/timer.h"
+#include "drivers/bus.h"
+
+timerHardware_t timerHardware[] = {
+
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2
+ DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D1_ST6
+ DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1
+
+ // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_OUTPUT_AUTO }, // MOTOR_3
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT
+
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4)
+
+ // DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
+ DEF_TIM(TIM4, CH4, PB9, TIM_USE_ANY, 0, 0), // S2_IN
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), // S3_IN, UART6_TX
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // S4_IN, UART6_RX
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // S5_IN // pad labelled CH5 on OMNIBUSF4PRO
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), // S6_IN // pad labelled CH6 on OMNIBUSF4PRO
+
+};
+
+const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
diff --git a/src/main/target/OMNIBUSF4PRO/target.h b/src/main/target/OMNIBUSF4PRO/target.h
new file mode 100644
index 00000000000..32bac107f96
--- /dev/null
+++ b/src/main/target/OMNIBUSF4PRO/target.h
@@ -0,0 +1,195 @@
+/*
+ * 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
+
+// This directory contains: OMNIBUSF4PRO, OMNIBUSF4V3, OMNIBUSF4V3_ICM
+// Softserial variants are in separate OMNIBUSF4V3_SS/ directory
+
+#ifdef OMNIBUSF4V3_ICM
+#define OMNIBUSF4V3
+#endif
+
+#ifdef OMNIBUSF4PRO
+#define TARGET_BOARD_IDENTIFIER "OBSD"
+#elif defined(OMNIBUSF4V3)
+#define TARGET_BOARD_IDENTIFIER "OB43"
+#endif
+
+#define USBD_PRODUCT_STRING "Omnibus F4"
+
+#define LED0 PB5
+
+#define BEEPER PB4
+#define BEEPER_INVERTED
+
+#define USE_I2C
+#define USE_I2C_DEVICE_2
+#define I2C_DEVICE_2_SHARES_UART3
+#define I2C_EXT_BUS BUS_I2C2
+
+#define UG2864_I2C_BUS I2C_EXT_BUS
+
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_BUS BUS_SPI1
+
+#define USE_IMU_MPU6000
+#define IMU_MPU6000_ALIGN CW270_DEG
+
+// Support for OMNIBUS F4 PRO CORNER - it has ICM20608 instead of MPU6000
+#define MPU6500_CS_PIN MPU6000_CS_PIN
+#define MPU6500_SPI_BUS MPU6000_SPI_BUS
+#define USE_IMU_MPU6500
+#define IMU_MPU6500_ALIGN IMU_MPU6000_ALIGN
+
+//BMI270
+#define USE_IMU_BMI270
+#define IMU_BMI270_ALIGN IMU_MPU6000_ALIGN
+#define BMI270_SPI_BUS MPU6000_SPI_BUS
+#define BMI270_CS_PIN MPU6000_CS_PIN
+
+#define USE_MAG
+#define MAG_I2C_BUS I2C_EXT_BUS
+#define USE_MAG_ALL
+
+#define TEMPERATURE_I2C_BUS I2C_EXT_BUS
+
+#define USE_BARO
+#define USE_BARO_BMP280
+#define BMP280_SPI_BUS BUS_SPI3
+#define BMP280_CS_PIN PB3 // v1
+// Support external barometers
+#define BARO_I2C_BUS I2C_EXT_BUS
+#define USE_BARO_BMP085
+#define USE_BARO_MS5611
+
+#define PITOT_I2C_BUS I2C_EXT_BUS
+
+#define USE_RANGEFINDER
+#define RANGEFINDER_I2C_BUS I2C_EXT_BUS
+
+#define USE_VCP
+#define VBUS_SENSING_PIN PC5
+#define VBUS_SENSING_ENABLED
+
+#define USE_UART_INVERTER
+
+#define USE_UART1
+#define UART1_RX_PIN PA10
+#define UART1_TX_PIN PA9
+#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
+#if defined(OMNIBUSF4PRO)
+#define INVERTER_PIN_UART1_RX PC0 // PC0 has never been used as inverter control on genuine OMNIBUS F4 variants, but leave it as is since some clones actually implement it.
+#endif
+
+#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
+#if defined(OMNIBUSF4V3)
+ #define INVERTER_PIN_UART6_RX PC8
+ #define INVERTER_PIN_UART6_TX PC9
+#endif
+
+#if defined(OMNIBUSF4V3)
+#define USE_SOFTSERIAL1
+#define SOFTSERIAL_1_RX_PIN PC6 // shared with UART6 TX
+#define SOFTSERIAL_1_TX_PIN PC6 // shared with UART6 TX
+
+#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
+
+#else // OMNIBUSF4PRO
+#define USE_SOFTSERIAL1
+#define SOFTSERIAL_1_RX_PIN PC8 // pad labelled CH5 on OMNIBUSF4PRO
+#define SOFTSERIAL_1_TX_PIN PC9 // pad labelled CH6 on OMNIBUSF4PRO
+
+#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
+#endif
+
+#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
+#define SERIALRX_PROVIDER SERIALRX_SBUS
+#define SERIALRX_UART SERIAL_PORT_USART1
+
+#define USE_SPI
+
+#define USE_SPI_DEVICE_1
+
+#define USE_SPI_DEVICE_2
+#define SPI2_NSS_PIN PB12
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_SPI_DEVICE_3
+#define SPI3_NSS_PIN PA15
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+
+#define USE_MAX7456
+#define MAX7456_SPI_BUS BUS_SPI3
+#define MAX7456_CS_PIN PA15
+
+#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
+#define USE_SDCARD
+#define USE_SDCARD_SPI
+
+#define SDCARD_SPI_BUS BUS_SPI2
+#define SDCARD_CS_PIN SPI2_NSS_PIN
+
+#define SDCARD_DETECT_PIN PB7
+#define SDCARD_DETECT_INVERTED
+
+#define USE_ADC
+#define ADC_CHANNEL_1_PIN PC1
+#define ADC_CHANNEL_2_PIN PC2
+#define ADC_CHANNEL_3_PIN PA0
+
+#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
+#define VBAT_ADC_CHANNEL ADC_CHN_2
+#define RSSI_ADC_CHANNEL ADC_CHN_3
+
+#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
+
+#define USE_LED_STRIP
+#define WS2811_PIN PB6
+
+#define DISABLE_RX_PWM_FEATURE
+#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)
+
+#define USE_SPEKTRUM_BIND
+#define BIND_PIN PB11 // USART3 RX
+
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+// Number of available PWM outputs
+#define MAX_PWM_OUTPUT_PORTS 6
+#define TARGET_MOTOR_COUNT 6
+#define USE_DSHOT
+#define USE_ESC_SENSOR
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+
+#ifdef OMNIBUSF4PRO
+#define CURRENT_METER_SCALE 265
+#endif
diff --git a/src/main/target/OMNIBUSF4V3_SS/CMakeLists.txt b/src/main/target/OMNIBUSF4V3_SS/CMakeLists.txt
new file mode 100644
index 00000000000..321eeb211d1
--- /dev/null
+++ b/src/main/target/OMNIBUSF4V3_SS/CMakeLists.txt
@@ -0,0 +1,4 @@
+# OMNIBUSF4V3 softserial variants with different S5/S6 timer configurations
+target_stm32f405xg(OMNIBUSF4V3_S6_SS)
+target_stm32f405xg(OMNIBUSF4V3_S5S6_SS)
+target_stm32f405xg(OMNIBUSF4V3_S5_S6_2SS)
diff --git a/src/main/target/OMNIBUSF4V3_SS/target.c b/src/main/target/OMNIBUSF4V3_SS/target.c
new file mode 100644
index 00000000000..95b496e8bfb
--- /dev/null
+++ b/src/main/target/OMNIBUSF4V3_SS/target.c
@@ -0,0 +1,53 @@
+/*
+ * 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/pwm_mapping.h"
+#include "drivers/timer.h"
+#include "drivers/bus.h"
+
+timerHardware_t timerHardware[] = {
+
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2
+ DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D1_ST6
+ DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1
+
+ // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_OUTPUT_AUTO }, // MOTOR_3
+#if defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_ANY, 0, 0), // S5_OUT SOFTSERIAL
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL
+#elif defined(OMNIBUSF4V3_S6_SS)
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL
+#endif
+
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4)
+
+ // DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
+ DEF_TIM(TIM4, CH4, PB9, TIM_USE_ANY, 0, 0), // S2_IN
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), // S3_IN, UART6_TX
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // S4_IN, UART6_RX
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // S5_IN
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), // S6_IN
+
+};
+
+const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
diff --git a/src/main/target/OMNIBUSF4V3_SS/target.h b/src/main/target/OMNIBUSF4V3_SS/target.h
new file mode 100644
index 00000000000..f3cbf6c4a49
--- /dev/null
+++ b/src/main/target/OMNIBUSF4V3_SS/target.h
@@ -0,0 +1,193 @@
+/*
+ * 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
+
+// This directory contains: OMNIBUSF4V3_S6_SS, OMNIBUSF4V3_S5S6_SS, OMNIBUSF4V3_S5_S6_2SS
+// Softserial variants of OMNIBUSF4V3 with different S5/S6 timer configurations
+#if defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
+#define OMNIBUSF4V3
+#endif
+
+#define TARGET_BOARD_IDENTIFIER "OB43"
+
+#define USBD_PRODUCT_STRING "Omnibus F4"
+
+#define LED0 PB5
+
+#define BEEPER PB4
+#define BEEPER_INVERTED
+
+#define USE_I2C
+#define USE_I2C_DEVICE_2
+#define I2C_DEVICE_2_SHARES_UART3
+#define I2C_EXT_BUS BUS_I2C2
+
+#define UG2864_I2C_BUS I2C_EXT_BUS
+
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_BUS BUS_SPI1
+
+#define USE_IMU_MPU6000
+#define IMU_MPU6000_ALIGN CW270_DEG
+
+// Support for OMNIBUS F4 PRO CORNER - it has ICM20608 instead of MPU6000
+#define MPU6500_CS_PIN MPU6000_CS_PIN
+#define MPU6500_SPI_BUS MPU6000_SPI_BUS
+#define USE_IMU_MPU6500
+#define IMU_MPU6500_ALIGN IMU_MPU6000_ALIGN
+
+//BMI270
+#define USE_IMU_BMI270
+#define IMU_BMI270_ALIGN IMU_MPU6000_ALIGN
+#define BMI270_SPI_BUS MPU6000_SPI_BUS
+#define BMI270_CS_PIN MPU6000_CS_PIN
+
+#define USE_MAG
+#define MAG_I2C_BUS I2C_EXT_BUS
+#define USE_MAG_ALL
+
+#define TEMPERATURE_I2C_BUS I2C_EXT_BUS
+
+#define USE_BARO
+#define USE_BARO_BMP280
+#define BMP280_SPI_BUS BUS_SPI3
+#define BMP280_CS_PIN PB3 // v1
+// Support external barometers
+#define BARO_I2C_BUS I2C_EXT_BUS
+#define USE_BARO_BMP085
+#define USE_BARO_MS5611
+
+#define PITOT_I2C_BUS I2C_EXT_BUS
+
+#define USE_RANGEFINDER
+#define RANGEFINDER_I2C_BUS I2C_EXT_BUS
+
+#define USE_VCP
+#define VBUS_SENSING_PIN PC5
+#define VBUS_SENSING_ENABLED
+
+#define USE_UART_INVERTER
+
+#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 INVERTER_PIN_UART6_RX PC8
+#define INVERTER_PIN_UART6_TX PC9
+
+#if defined(OMNIBUSF4V3_S6_SS) // one softserial on S6
+#define USE_SOFTSERIAL1
+#define SOFTSERIAL_1_RX_PIN PA8 // S6 output
+#define SOFTSERIAL_1_TX_PIN PA8 // S6 output
+
+#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
+
+#elif defined(OMNIBUSF4V3_S5S6_SS) // one softserial on S5/RX S6/TX
+#define USE_SOFTSERIAL1
+#define SOFTSERIAL_1_RX_PIN PA1 // S5 output
+#define SOFTSERIAL_1_TX_PIN PA8 // S6 output
+
+#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
+
+#elif defined(OMNIBUSF4V3_S5_S6_2SS) // two softserials, one on S5 and one on S6
+#define USE_SOFTSERIAL1
+#define SOFTSERIAL_1_RX_PIN PA1 // S5 output
+#define SOFTSERIAL_1_TX_PIN PA1 // S5 output
+
+#define USE_SOFTSERIAL2
+#define SOFTSERIAL_2_RX_PIN PA8 // S6 output
+#define SOFTSERIAL_2_TX_PIN PA8 // S6 output
+
+#define SERIAL_PORT_COUNT 6 // VCP, USART1, USART3, USART6, SOFTSERIAL1, SOFTSERIAL2
+#endif
+
+#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
+#define SERIALRX_PROVIDER SERIALRX_SBUS
+#define SERIALRX_UART SERIAL_PORT_USART1
+
+#define USE_SPI
+
+#define USE_SPI_DEVICE_1
+
+#define USE_SPI_DEVICE_2
+#define SPI2_NSS_PIN PB12
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_SPI_DEVICE_3
+#define SPI3_NSS_PIN PA15
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+
+#define USE_MAX7456
+#define MAX7456_SPI_BUS BUS_SPI3
+#define MAX7456_CS_PIN PA15
+
+#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
+#define USE_SDCARD
+#define USE_SDCARD_SPI
+
+#define SDCARD_SPI_BUS BUS_SPI2
+#define SDCARD_CS_PIN SPI2_NSS_PIN
+
+#define SDCARD_DETECT_PIN PB7
+#define SDCARD_DETECT_INVERTED
+
+#define USE_ADC
+#define ADC_CHANNEL_1_PIN PC1
+#define ADC_CHANNEL_2_PIN PC2
+#define ADC_CHANNEL_3_PIN PA0
+
+#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
+#define VBAT_ADC_CHANNEL ADC_CHN_2
+#define RSSI_ADC_CHANNEL ADC_CHN_3
+
+#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
+
+#define USE_LED_STRIP
+#define WS2811_PIN PB6
+
+#define DISABLE_RX_PWM_FEATURE
+#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)
+
+#define USE_SPEKTRUM_BIND
+#define BIND_PIN PB11 // USART3 RX
+
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+// Number of available PWM outputs
+#define MAX_PWM_OUTPUT_PORTS 6
+#define TARGET_MOTOR_COUNT 6
+#define USE_DSHOT
+#define USE_ESC_SENSOR
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+