diff --git a/src/main/target/STM32F405/target.h b/src/main/target/STM32F405/target.h
index a2d3e3af70..7edb5570be 100644
--- a/src/main/target/STM32F405/target.h
+++ b/src/main/target/STM32F405/target.h
@@ -26,7 +26,7 @@
#define TARGET_BOARD_IDENTIFIER "S405"
-#define USBD_PRODUCT_STRING "S405"
+#define USBD_PRODUCT_STRING "Betaflight STM32F405"
#define USE_BEEPER
diff --git a/src/main/target/STM32F411/target.c b/src/main/target/STM32F411/target.c
new file mode 100644
index 0000000000..a087e06bd2
--- /dev/null
+++ b/src/main/target/STM32F411/target.c
@@ -0,0 +1,22 @@
+/*
+ * 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 .
+ */
+
+// Needed to suppress the pedantic warning about an empty file
+#include
diff --git a/src/main/target/STM32F411/target.h b/src/main/target/STM32F411/target.h
new file mode 100644
index 0000000000..9090968603
--- /dev/null
+++ b/src/main/target/STM32F411/target.h
@@ -0,0 +1,121 @@
+/*
+ * 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
+
+// Treat the target as generic, and expect manufacturer id / board name
+// to be supplied when the board is configured for the first time
+#define USE_UNIFIED_TARGET
+
+#define TARGET_BOARD_IDENTIFIER "S411"
+
+#define USBD_PRODUCT_STRING "Betaflight STM32F411"
+
+#define USE_BEEPER
+
+// MPU interrupt
+#define USE_EXTI
+#define USE_MPU_DATA_READY_SIGNAL
+//#define DEBUG_MPU_DATA_READY_INTERRUPT
+#define USE_GYRO_EXTI
+
+#define USE_ACC
+#define USE_GYRO
+
+#define USE_ACC_MPU6050
+#define USE_GYRO_MPU6050
+#define USE_ACC_MPU6500
+#define USE_GYRO_MPU6500
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_MPU6000
+#define USE_ACC_SPI_MPU6500
+#define USE_GYRO_SPI_MPU6500
+#define USE_ACC_SPI_ICM20689
+#define USE_GYRO_SPI_ICM20689
+// Other USE_ACCs and USE_GYROs should follow
+
+#define USE_MAG
+#define USE_MAG_HMC5883
+#define USE_MAG_SPI_HMC5883
+#define USE_MAG_QMC5883
+#define USE_MAG_LIS3MDL
+#define USE_MAG_AK8963
+#define USE_MAG_SPI_AK8963
+
+#define USE_BARO
+#define USE_BARO_MS5611
+#define USE_BARO_SPI_MS5611
+#define USE_BARO_BMP280
+#define USE_BARO_SPI_BMP280
+#define USE_BARO_LPS
+#define USE_BARO_SPI_LPS
+
+#define USE_SDCARD
+#define USE_SDCARD_SPI
+
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+
+#define USE_MAX7456
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define USE_I2C_DEVICE_2
+#define USE_I2C_DEVICE_3
+#define I2C_FULL_RECONFIGURABILITY
+
+#define USE_VCP
+
+#define USE_UART1
+#define USE_UART2
+#define USE_UART6
+#define USE_SOFTSERIAL1
+#define USE_SOFTSERIAL2
+#define USE_INVERTER
+#define SERIAL_PORT_COUNT 6
+
+#define USE_ESCSERIAL
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define USE_SPI_DEVICE_2
+#define USE_SPI_DEVICE_3
+#define SPI_FULL_RECONFIGURABILITY
+
+#define USE_ADC
+
+//TODO: Make this work with runtime configurability
+//#define USE_RX_FRSKY_SPI_D
+//#define USE_RX_FRSKY_SPI_X
+//#define USE_RX_SFHSS_SPI
+//#define USE_RX_FRSKY_SPI_TELEMETRY
+//#define USE_RX_CC2500_SPI_PA_LNA
+//#define USE_RX_CC2500_SPI_DIVERSITY
+
+//TODO: Make this work with runtime configurability
+//#define USE_RX_FLYSKY
+//#define USE_RX_FLYSKY_SPI_LED
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+#define TARGET_IO_PORTE 0xffff
+#define TARGET_IO_PORTF 0xffff
diff --git a/src/main/target/STM32F411/target.mk b/src/main/target/STM32F411/target.mk
new file mode 100644
index 0000000000..47a7d89b33
--- /dev/null
+++ b/src/main/target/STM32F411/target.mk
@@ -0,0 +1,17 @@
+F411_TARGETS += $(TARGET)
+
+FEATURES += SDCARD_SPI VCP ONBOARDFLASH
+
+TARGET_SRC = \
+ $(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
+ $(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \
+ $(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+ drivers/max7456.c \
+ drivers/rx/rx_cc2500.c \
+ rx/cc2500_common.c \
+ rx/cc2500_frsky_shared.c \
+ rx/cc2500_frsky_d.c \
+ rx/cc2500_frsky_x.c \
+ rx/cc2500_sfhss.c \
+ drivers/rx/rx_a7105.c \
+ rx/a7105_flysky.c
diff --git a/src/main/target/STM32F411DISCOVERY/target.h b/src/main/target/STM32F411DISCOVERY/target.h
index 27587f9e0b..5610073b53 100644
--- a/src/main/target/STM32F411DISCOVERY/target.h
+++ b/src/main/target/STM32F411DISCOVERY/target.h
@@ -21,7 +21,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "S411" // STM Discovery F411
-#define USBD_PRODUCT_STRING "DISCF411"
+#define USBD_PRODUCT_STRING "STM32F411DISCOVERY"
#define USE_SENSOR_NAMES
diff --git a/src/main/target/STM32F4DISCOVERY/target.h b/src/main/target/STM32F4DISCOVERY/target.h
index eb3195fdb2..2693042cda 100644
--- a/src/main/target/STM32F4DISCOVERY/target.h
+++ b/src/main/target/STM32F4DISCOVERY/target.h
@@ -21,7 +21,7 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "SDF4"
-#define USBD_PRODUCT_STRING "DISCF4"
+#define USBD_PRODUCT_STRING "STM32F4DISCOVERY"
#define USE_VTX_TABLE
#define USE_SPI_TRANSACTION
diff --git a/src/main/target/STM32F7X2/target.h b/src/main/target/STM32F7X2/target.h
index 23fbcc2ee0..f5795738bd 100644
--- a/src/main/target/STM32F7X2/target.h
+++ b/src/main/target/STM32F7X2/target.h
@@ -26,7 +26,7 @@
#define TARGET_BOARD_IDENTIFIER "S7X2"
-#define USBD_PRODUCT_STRING "S7X2"
+#define USBD_PRODUCT_STRING "Betaflight STM32F7x2"
#define USE_BEEPER
diff --git a/unified_targets/configs/CRAZYBEEF4FR.config b/unified_targets/configs/CRAZYBEEF4FR.config
index 4b1841aeed..0696788739 100644
--- a/unified_targets/configs/CRAZYBEEF4FR.config
+++ b/unified_targets/configs/CRAZYBEEF4FR.config
@@ -1,5 +1,7 @@
# Betaflight / CRAZYBEEF4FR (C4FR) 4.0.0 Feb 28 2019 / 18:10:50 (b63a3e117) MSP API: 1.41
+# This is not usable yet, as the SPI RX is not fully runtime configurable yet
+
board_name CRAZYBEEF4FR
manufacturer_id HAMO