diff --git a/src/main/target/AIKONF4/target.h b/src/main/target/AIKONF4/target.h
index 10936665de..0b261909ad 100644
--- a/src/main/target/AIKONF4/target.h
+++ b/src/main/target/AIKONF4/target.h
@@ -20,8 +20,10 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "AIK4"
-#define USBD_PRODUCT_STRING "AIKONF4"
+#define BOARD_NAME AIKONF4
+#define MANUFACTURER_ID AIKO
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
#define LED0_PIN PB4
#define USE_BEEPER
@@ -38,22 +40,32 @@
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU6000_CS_PIN SPI1_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI1
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_ACC
#define USE_ACC_SPI_MPU6000
+#define USE_ACC_SPI_ICM20602
+#define USE_GYRO_SPI_ICM20602
+#define USE_ACCGYRO_BMI270
+#define USE_GYRO_SPI_MPU6500
+#define USE_ACC_SPI_MPU6500
+
+#define MPU6000_CS_PIN SPI1_NSS_PIN
+#define MPU6000_SPI_INSTANCE SPI1
#define GYRO_MPU6000_ALIGN CW0_DEG
#define ACC_MPU6000_ALIGN CW0_DEG
-#define USE_GYRO_SPI_MPU6500
-#define USE_ACC_SPI_MPU6500
+// ICM2060x detected by MPU6500 driver
#define MPU6500_CS_PIN MPU6000_CS_PIN
#define MPU6500_SPI_INSTANCE MPU6000_SPI_INSTANCE
#define GYRO_MPU6500_ALIGN GYRO_MPU6000_ALIGN
#define ACC_MPU6500_ALIGN ACC_MPU6000_ALIGN
+#define ACC_BMI270_ALIGN CW0_DEG
+#define GYRO_BMI270_ALIGN CW0_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
+
#define USE_BARO
#define USE_BARO_BMP280
diff --git a/src/main/target/AIKONF4/target.mk b/src/main/target/AIKONF4/target.mk
index a93456300b..1c19914f81 100644
--- a/src/main/target/AIKONF4/target.mk
+++ b/src/main/target/AIKONF4/target.mk
@@ -4,5 +4,6 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp280.c \
drivers/max7456.c
diff --git a/src/main/target/AIKONF7/target.h b/src/main/target/AIKONF7/target.h
index 4a0165bf0a..e5adeca943 100644
--- a/src/main/target/AIKONF7/target.h
+++ b/src/main/target/AIKONF7/target.h
@@ -19,8 +19,11 @@
*/
#pragma once
-#define TARGET_BOARD_IDENTIFIER "AIKO"
-#define USBD_PRODUCT_STRING "AIKONF7"
+
+#define BOARD_NAME AIKONF7
+#define MANUFACTURER_ID AIKO
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define ENABLE_DSHOT_DMAR true
@@ -38,12 +41,16 @@
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
-//MPU-6000
+
#define USE_ACC
#define USE_ACC_SPI_MPU6000
+#define USE_ACC_SPI_ICM42688P
+#define USE_ACCGYRO_BMI270
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
+#define USE_GYRO_SPI_ICM42688P
+//MPU-6000
#define GYRO_MPU6000_ALIGN CW0_DEG
#define ACC_MPU6000_ALIGN CW0_DEG
#define MPU6000_CS_PIN PA4
@@ -60,6 +67,18 @@
#define MPU6500_CS_PIN SPI1_NSS_PIN
#define MPU6500_SPI_INSTANCE SPI1
+// ICM42688P
+#define ACC_ICM42688P_ALIGN CW0_DEG
+#define GYRO_ICM42688P_ALIGN CW0_DEG
+#define ICM42688P_CS_PIN PA4
+#define ICM42688P_SPI_INSTANCE SPI1
+
+// BMI270
+#define ACC_BMI270_ALIGN CW0_DEG
+#define GYRO_BMI270_ALIGN CW0_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
+
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
diff --git a/src/main/target/AIKONF7/target.mk b/src/main/target/AIKONF7/target.mk
index 3bae3aba77..7fde06276b 100644
--- a/src/main/target/AIKONF7/target.mk
+++ b/src/main/target/AIKONF7/target.mk
@@ -5,6 +5,8 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c \
drivers/compass/compass_hmc5883l.c \
diff --git a/src/main/target/AIRF7/target.h b/src/main/target/AIRF7/target.h
index 6c1df32bc2..4be0d9d176 100644
--- a/src/main/target/AIRF7/target.h
+++ b/src/main/target/AIRF7/target.h
@@ -20,8 +20,10 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "RAF7"
-#define USBD_PRODUCT_STRING "Racerstar AirF7"
+#define MANUFACTURER_ID RAST
+#define BOARD_NAME AIRF7
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define LED0_PIN PA3
@@ -44,16 +46,22 @@
#define USE_GYRO
#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
#define USE_GYRO_SPI_MPU6500
#define USE_MPU_DATA_READY_SIGNAL
+#define ACC_MPU6000_ALIGN CW90_DEG
+#define GYRO_MPU6000_ALIGN CW90_DEG
+#define MPU6000_CS_PIN PC4
+#define MPU6000_SPI_INSTANCE SPI1
+
#define MPU6500_CS_PIN PC4 //GYRO_1_CS_PIN
#define MPU6500_SPI_INSTANCE SPI1 //GYRO_1_SPI_INSTANCE
#define GYRO_MPU6500_ALIGN CW90_DEG
#define ACC_MPU6500_ALIGN CW90_DEG
-
// *************** OSD **************************
#define USE_SPI_DEVICE_3
diff --git a/src/main/target/AIRF7/target.mk b/src/main/target/AIRF7/target.mk
index b91dba39c6..6a61e399ef 100644
--- a/src/main/target/AIRF7/target.mk
+++ b/src/main/target/AIRF7/target.mk
@@ -3,6 +3,7 @@ FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/barometer/barometer_bmp280.c \
diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h
index 9a2b455b85..271be4c862 100644
--- a/src/main/target/ALIENFLIGHTF4/target.h
+++ b/src/main/target/ALIENFLIGHTF4/target.h
@@ -19,14 +19,17 @@
*/
#pragma once
-#define TARGET_BOARD_IDENTIFIER "AFF4"
+
#define USE_TARGET_CONFIG
+#define BOARD_NAME ALIENFLIGHTF4
+#define MANUFACTURER_ID AFNG
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+
#define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PC13
-#define USBD_PRODUCT_STRING "AlienFlight F4"
-
#define LED0_PIN PC12
#define LED1_PIN PD2
@@ -43,16 +46,22 @@
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
-
#define USE_ACC
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
-
#define USE_GYRO
+#define USE_ACC_SPI_MPU6500
#define USE_GYRO_SPI_MPU6500
+#define USE_GYRO_SPI_MPU9250
+#define USE_ACC_SPI_MPU9250
+
+#define ACC_MPU6500_ALIGN CW270_DEG
#define GYRO_MPU6500_ALIGN CW270_DEG
+#define MPU6500_CS_PIN SPI1_NSS_PIN
+#define MPU6500_SPI_INSTANCE SPI1
+
+#define ACC_MPU9250_ALIGN CW270_DEG
+#define GYRO_MPU9250_ALIGN CW270_DEG
+#define MPU9250_CS_PIN PA4
+#define MPU9250_SPI_INSTANCE SPI1
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/ALIENFLIGHTF4/target.mk b/src/main/target/ALIENFLIGHTF4/target.mk
index e733398ee9..a6592ec751 100644
--- a/src/main/target/ALIENFLIGHTF4/target.mk
+++ b/src/main/target/ALIENFLIGHTF4/target.mk
@@ -2,8 +2,10 @@ F405_TARGETS += $(TARGET)
FEATURES += SDCARD VCP ONBOARDFLASH
TARGET_SRC = \
+ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu9250.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_ak8963.c \
diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h
index a1aff1ce8e..149f47fef5 100644
--- a/src/main/target/ALIENFLIGHTNGF7/target.h
+++ b/src/main/target/ALIENFLIGHTNGF7/target.h
@@ -19,14 +19,17 @@
*/
#pragma once
-#define TARGET_BOARD_IDENTIFIER "AFF7"
+
#define USE_TARGET_CONFIG
+#define BOARD_NAME ALIENFLIGHTNGF7
+#define MANUFACTURER_ID AFNG
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
#define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PC13
-#define USBD_PRODUCT_STRING "AlienFlightNG F7"
-
#define LED0_PIN PC12
#define LED1_PIN PD2
@@ -41,16 +44,25 @@
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
+// ICM2060x detected by MPU6500 driver
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define USE_ACC_SPI_MPU9250
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
+#define USE_GYRO_SPI_MPU9250
+
+#define ACC_MPU6500_ALIGN CW270_DEG
#define GYRO_MPU6500_ALIGN CW270_DEG
+#define MPU6500_CS_PIN SPI1_NSS_PIN
+#define MPU6500_SPI_INSTANCE SPI1
+
+#define ACC_MPU9250_ALIGN CW270_DEG
+#define GYRO_MPU9250_ALIGN CW270_DEG
+#define MPU9250_CS_PIN PA4
+#define MPU9250_SPI_INSTANCE SPI1
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/ALIENFLIGHTNGF7/target.mk b/src/main/target/ALIENFLIGHTNGF7/target.mk
index 2d9d8709bd..0e1e591552 100644
--- a/src/main/target/ALIENFLIGHTNGF7/target.mk
+++ b/src/main/target/ALIENFLIGHTNGF7/target.mk
@@ -4,6 +4,7 @@ FEATURES += SDCARD VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu9250.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_ak8963.c \
diff --git a/src/main/target/AXISFLYINGF7/target.h b/src/main/target/AXISFLYINGF7/target.h
index c5ab781cde..776e303714 100644
--- a/src/main/target/AXISFLYINGF7/target.h
+++ b/src/main/target/AXISFLYINGF7/target.h
@@ -20,9 +20,10 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S7X7"
-
-#define USBD_PRODUCT_STRING "AXISFLYINGF7"
+#define BOARD_NAME AXISFLYINGF7
+#define MANUFACTURER_ID AXFL
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define CAMERA_CONTROL_PIN PA8
@@ -58,20 +59,27 @@
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
-#define MPU6000_CS_PIN PB12
-#define MPU6000_SPI_INSTANCE SPI2
-
//#define USE_EXTI
//#define MPU_INT_EXTI NONE
#define USE_MPU_DATA_READY_SIGNAL
+#define USE_ACC
#define USE_GYRO
-#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW0_DEG
-#define USE_ACC
+// MPU6000
#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_MPU6000
+#define GYRO_MPU6000_ALIGN CW0_DEG
#define ACC_MPU6000_ALIGN CW0_DEG
+#define MPU6000_CS_PIN PB12
+#define MPU6000_SPI_INSTANCE SPI2
+
+// BMI270
+#define USE_ACCGYRO_BMI270
+#define ACC_BMI270_ALIGN CW0_DEG
+#define GYRO_BMI270_ALIGN CW0_DEG
+#define BMI270_CS_PIN PB12
+#define BMI270_SPI_INSTANCE SPI2
#define LED0_PIN PB10
diff --git a/src/main/target/AXISFLYINGF7/target.mk b/src/main/target/AXISFLYINGF7/target.mk
index e85a9d587a..e30deb9896 100644
--- a/src/main/target/AXISFLYINGF7/target.mk
+++ b/src/main/target/AXISFLYINGF7/target.mk
@@ -1,13 +1,14 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_qmp6988.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
- drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip.c \
drivers/max7456.c
diff --git a/src/main/target/BETAFPVF405/config.c b/src/main/target/BETAFPVF405/config.c
new file mode 100644
index 0000000000..fb6b04d795
--- /dev/null
+++ b/src/main/target/BETAFPVF405/config.c
@@ -0,0 +1,34 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+
+#ifdef USE_TARGET_CONFIG
+
+#include "flight/mixer.h"
+
+void targetConfiguration(void) {
+ motorConfigMutable()->motorPoleCount = 12;
+}
+#endif
diff --git a/src/main/target/BETAFPVF405/target.h b/src/main/target/BETAFPVF405/target.h
index 4e6e213172..b49a1251da 100644
--- a/src/main/target/BETAFPVF405/target.h
+++ b/src/main/target/BETAFPVF405/target.h
@@ -20,8 +20,10 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "BEFH"
-#define USBD_PRODUCT_STRING "BetaFPV f405"
+#define BOARD_NAME BETAFPVF405
+#define MANUFACTURER_ID BEFH
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
#define USE_BEEPER
#define BEEPER_PIN PB4
@@ -98,9 +100,10 @@
#define USE_GYRO
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
#define USE_GYRO_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+#define USE_ACCGYRO_BMI270
// MPU6000 interrupts
#define USE_EXTI
@@ -108,8 +111,17 @@
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define ACC_1_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_EXTI_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define USE_DUAL_GYRO
+
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_ALIGN CW0_DEG
+#define GYRO_2_SPI_INSTANCE SPI1
#define USE_BARO
#define USE_BARO_BMP280
diff --git a/src/main/target/BETAFPVF405/target.mk b/src/main/target/BETAFPVF405/target.mk
index cd68232238..bb0a5ecf80 100644
--- a/src/main/target/BETAFPVF405/target.mk
+++ b/src/main/target/BETAFPVF405/target.mk
@@ -5,6 +5,8 @@ FEATURES += VCP SDCARD ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
diff --git a/src/main/target/BETAFPVF411RX/target.h b/src/main/target/BETAFPVF411RX/target.h
index 2a68447eda..1f6d46c96b 100644
--- a/src/main/target/BETAFPVF411RX/target.h
+++ b/src/main/target/BETAFPVF411RX/target.h
@@ -20,15 +20,16 @@
#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "BEFH"
-#define USBD_PRODUCT_STRING "BETAFPVF411RX"
+#define BOARD_NAME BETAFPVF411RX
+#define MANUFACTURER_ID BEFH
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
#define LED0_PIN PC14
-//#define USE_BEEPER
-//#define BEEPER_PIN P
-//#define BEEPER_INVERTED
+#define USE_BEEPER
+#define BEEPER_PIN PA14
+#define BEEPER_INVERTED
// *************** Gyro & ACC **********************
#define USE_SPI
@@ -68,24 +69,6 @@
#define BMI270_CS_PIN PA4
#define BMI270_SPI_INSTANCE SPI1
-// *************** Baro **************************
-//#define USE_I2C
-
-//#define USE_I2C_DEVICE_1
-//#define I2C_DEVICE (I2CDEV_1)
-//#define I2C1_SCL PB8 // SCL pad
-//#define I2C1_SDA PB9 // SDA pad
-//#define BARO_I2C_INSTANCE (I2CDEV_1)
-
-//#define USE_BARO //External, connect to I2C1
-//#define USE_BARO_BMP280
-//#define USE_BARO_MS5611
-//#define USE_BARO_BMP085
-
-//#define USE_MAG
-//#define USE_MAG_HMC5883 //External, connect to I2C1
-//#define USE_MAG_QMC5883
-
// *************** UART *****************************
#define USE_VCP
#define USE_USB_DETECT
@@ -98,15 +81,10 @@
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
-#define USE_SOFTSERIAL1
-#define SOFTSERIAL1_RX_PIN PA8
-#define SOFTSERIAL1_TX_PIN PA8
-
-#define SERIAL_PORT_COUNT 4
+#define SERIAL_PORT_COUNT 3
// *************** SPI3 CC2500 ***************************
-
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
@@ -151,16 +129,20 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_FLASHFS
#define USE_FLASH_M25P16
-#define FLASH_CS_PIN PB2
+#define FLASH_CS_PIN PA8
#define FLASH_SPI_INSTANCE SPI2
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
-//#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
+#define ADC1_DMA_OPT 1
#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
#define VBAT_ADC_PIN PA1
#define CURRENT_METER_ADC_PIN PB0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 179
+
//#define RSSI_ADC_PIN PB1
//#define EXTERNAL1_ADC_PIN PA4
@@ -174,10 +156,7 @@
//#define PINIO2_PIN PA15 // Camera switcher
//#define USE_PINIOBOX
-#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_SOFTSERIAL)
-#define CURRENT_METER_SCALE_DEFAULT 179
-#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
-#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h
index 595a08c5f2..ee4719dfc4 100644
--- a/src/main/target/BETAFPVF722/target.h
+++ b/src/main/target/BETAFPVF722/target.h
@@ -19,9 +19,11 @@
*/
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S7X2"
-#define USBD_PRODUCT_STRING "BETAFPVF722"
-#define TARGET_MANUFACTURER_IDENTIFIER "BEFH"
+
+#define BOARD_NAME BETAFPVF722
+#define MANUFACTURER_ID BEFH
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define ENABLE_DSHOT_DMAR true
@@ -40,23 +42,29 @@
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_GYRO_SPI_MPU6000
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+#define USE_ACCGYRO_BMI270
+
+#define USE_SPI_GYRO
#define USE_EXTI
+#define USE_GYRO_EXTI
+
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PC4 //MPU_INT_EXTI
-#define MPU6000_CS_PIN PA4 //GYRO_1_CS_PIN
-#define MPU6000_SPI_INSTANCE SPI1 //GYRO_1_SPI_INSTANCE
-#define GYRO_MPU6000_ALIGN CW180_DEG
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_EXTI_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define USE_DUAL_GYRO
-// ICM42688P
-#define USE_GYRO_SPI_ICM42688P
-#define USE_ACC_SPI_ICM42688P
-#define ICM42688P_CS_PIN PA4
-#define ICM42688P_SPI_INSTANCE SPI1
-#define GYRO_ICM42688P_ALIGN CW180_DEG
-#define ACC_ICM42688P_ALIGN CW180_DEG
+#define ACC_2_ALIGN CW180_DEG
+#define GYRO_2_ALIGN CW180_DEG
+#define GYRO_2_CS_PIN PC3
+#define GYRO_2_EXTI_PIN PB2
+#define GYRO_2_SPI_INSTANCE SPI1
// OSD
@@ -130,6 +138,8 @@
#define VBAT_ADC_PIN PC0
#define RSSI_ADC_PIN PC2
#define CURRENT_METER_SCALE_DEFAULT 450 // 3.3/120A = 25mv/A
+#define ADC1_DMA_OPT 0
+#define ADC1_DMA_STREAM DMA2_Stream0 //# ADC 1: DMA2 Stream 0 Channel 0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// SPI devices
diff --git a/src/main/target/BETAFPVF722/target.mk b/src/main/target/BETAFPVF722/target.mk
index 0da79a44b5..0a2bedfaed 100644
--- a/src/main/target/BETAFPVF722/target.mk
+++ b/src/main/target/BETAFPVF722/target.mk
@@ -5,6 +5,7 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_icm426xx.c \
+drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
diff --git a/src/main/target/EACHINEF722/target.c b/src/main/target/EACHINEF722/target.c
new file mode 100644
index 0000000000..da49309fd6
--- /dev/null
+++ b/src/main/target/EACHINEF722/target.c
@@ -0,0 +1,48 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 7
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 8
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // led
+ DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN; dma 0 assumed, please verify
+ DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // pwm RX_PWM1_PIN; dma 0 assumed, please verify
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // pwm RX_PWM2_PIN
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // pwm RX_PWM3_PIN
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/EACHINEF722/target.h b/src/main/target/EACHINEF722/target.h
new file mode 100644
index 0000000000..9de526f3ad
--- /dev/null
+++ b/src/main/target/EACHINEF722/target.h
@@ -0,0 +1,144 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#pragma once
+
+#define BOARD_NAME EACHINEF722
+#define MANUFACTURER_ID EACH
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_BARO
+#define USE_BARO_SPI_BMP280
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PA14
+#define LED1_PIN PA13
+#define LED_STRIP_PIN PA8
+#define USE_BEEPER
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+#define USE_USB_DETECT
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PC4
+
+#define ACC_MPU6000_ALIGN CW180_DEG_FLIP
+#define GYRO_MPU6000_ALIGN CW180_DEG_FLIP
+#define MPU6000_CS_PIN PB2
+#define MPU6000_SPI_INSTANCE SPI1
+
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 6
+
+#define BARO_CS_PIN PA4
+#define BARO_SPI_INSTANCE SPI1
+#define BMP280_CS_PIN PA4
+#define BMP280_SPI_INSTANCE SPI1
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PD2
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC2
+#define CURRENT_METER_ADC_PIN PC1
+#define RSSI_ADC_PIN PC0
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 179
+
+#define ENABLE_DSHOT_DMAR true
+
+#define PINIO1_PIN PC8
+#define PINIO2_PIN PC9
+#define PINIO1_BOX 40
+#define PINIO2_BOX 41
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 13
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(9) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/EACHINEF722/target.mk b/src/main/target/EACHINEF722/target.mk
new file mode 100644
index 0000000000..2916fa9d11
--- /dev/null
+++ b/src/main/target/EACHINEF722/target.mk
@@ -0,0 +1,14 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/barometer/barometer_bmp280.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/pinio.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 889ce5d
diff --git a/src/main/target/FF_RACEPITF7_MINI/target.c b/src/main/target/FF_RACEPITF7_MINI/target.c
new file mode 100644
index 0000000000..3ef89f5a4a
--- /dev/null
+++ b/src/main/target/FF_RACEPITF7_MINI/target.c
@@ -0,0 +1,40 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR, 0, 1), // motor 3
+ DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // led
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FF_RACEPITF7_MINI/target.h b/src/main/target/FF_RACEPITF7_MINI/target.h
new file mode 100644
index 0000000000..3e5b72d79c
--- /dev/null
+++ b/src/main/target/FF_RACEPITF7_MINI/target.h
@@ -0,0 +1,128 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME FF_RACEPITF7_MINI
+#define MANUFACTURER_ID FFPV
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PB9
+#define LED1_PIN PB8
+#define LED_STRIP_PIN PB6
+#define USE_BEEPER
+#define BEEPER_PIN PC3
+#define BEEPER_INVERTED
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PC4
+
+#define ACC_MPU6000_ALIGN CW180_DEG
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PB7
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PC10
+#define UART3_RX_PIN PC11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART5
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 7
+
+#define FLASH_CS_PIN PA15
+#define FLASH_SPI_INSTANCE SPI3
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC2
+#define CURRENT_METER_ADC_PIN PC1
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 170
+
+#define ENABLE_DSHOT_DMAR true
+
+#define PINIO1_PIN PC0
+#define PINIO1_BOX 40
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 5
+#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FF_RACEPITF7_MINI/target.mk b/src/main/target/FF_RACEPITF7_MINI/target.mk
new file mode 100644
index 0000000000..972094b702
--- /dev/null
+++ b/src/main/target/FF_RACEPITF7_MINI/target.mk
@@ -0,0 +1,12 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/pinio.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/FLYCOLORF7/target.c b/src/main/target/FLYCOLORF7/target.c
new file mode 100644
index 0000000000..eacb89af2a
--- /dev/null
+++ b/src/main/target/FLYCOLORF7/target.c
@@ -0,0 +1,47 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // led
+ DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), // cam ctrl
+ DEF_TIM(TIM2, CH3, PB10, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check
+ DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_ANY, 0, 1), // could not determine TIM_USE_xxxxx - please check
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FLYCOLORF7/target.h b/src/main/target/FLYCOLORF7/target.h
new file mode 100644
index 0000000000..7c27d4bf42
--- /dev/null
+++ b/src/main/target/FLYCOLORF7/target.h
@@ -0,0 +1,148 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME FLYCOLORF7
+#define MANUFACTURER_ID FLCO
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC15
+#define LED_STRIP_PIN PA8
+#define USE_BEEPER
+#define BEEPER_PIN PC14
+#define BEEPER_INVERTED
+#define CAMERA_CONTROL_PIN PB8
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PB5
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_1_ALIGN CW180_DEG_FLIP
+#define GYRO_1_ALIGN CW180_DEG_FLIP
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_EXTI_PIN PC3
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define USE_DUAL_GYRO
+
+#define ACC_2_ALIGN CW270_DEG
+#define GYRO_2_ALIGN CW270_DEG
+#define GYRO_2_CS_PIN PB2
+#define GYRO_2_EXTI_PIN PC4
+#define GYRO_2_SPI_INSTANCE SPI1
+
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART5
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 7
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
+
+#define FLASH_CS_PIN PC13
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC1
+#define CURRENT_METER_ADC_PIN PC0
+#define RSSI_ADC_PIN PC2
+#define ADC3_DMA_OPT 1
+#define ADC3_DMA_STREAM DMA2_Stream1 //# ADC 3: DMA2 Stream 1 Channel 2
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 170
+#define ADC_INSTANCE ADC3
+
+#define ENABLE_DSHOT_DMAR true
+
+#define PINIO1_PIN PB0
+#define PINIO2_PIN PB9
+#define PINIO1_BOX 40
+#define PINIO2_BOX 41
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 12
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FLYCOLORF7/target.mk b/src/main/target/FLYCOLORF7/target.mk
new file mode 100644
index 0000000000..de71ac0a2e
--- /dev/null
+++ b/src/main/target/FLYCOLORF7/target.mk
@@ -0,0 +1,13 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/pinio.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/FLYWOOF405/target.c b/src/main/target/FLYWOOF405/target.c
index 2353c95ae4..957352f8b4 100644
--- a/src/main/target/FLYWOOF405/target.c
+++ b/src/main/target/FLYWOOF405/target.c
@@ -28,18 +28,17 @@
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
-
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // MOTOR 1
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // MOTOR 2
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // MOTOR 1
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), // MOTOR 3
-
-
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // MOTOR 5
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // MOTOR 6
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // MOTOR 7
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // MOTOR 8
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0),
+
DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0, 0), // CAMERA CONTROL
};
diff --git a/src/main/target/FLYWOOF405/target.h b/src/main/target/FLYWOOF405/target.h
index e9952fcc5d..f3d9770e33 100644
--- a/src/main/target/FLYWOOF405/target.h
+++ b/src/main/target/FLYWOOF405/target.h
@@ -20,8 +20,10 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S405"
-#define USBD_PRODUCT_STRING "FLYWOOF405 - MPU6000"
+#define BOARD_NAME FLYWOOF405
+#define MANUFACTURER_ID FLWO
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
//----------------------------------------
#define USE_TARGET_CONFIG
@@ -36,8 +38,11 @@
#define CAMERA_CONTROL_PIN PA9
#define USE_PINIO
-#define PINIO1_PIN PB12
#define USE_PINIOBOX
+#define PINIO1_PIN PB12
+#define PINIO2_PIN PB13
+#define PINIO1_BOX 40
+#define PINIO2_BOX 41
//SPI DEVICE-------------------------------
#define USE_SPI
@@ -54,8 +59,9 @@
#define SPI3_MOSI_PIN PC12
//Gyro & ACC-------------------------------
+#define USE_SPI_GYRO
#define USE_EXTI
-#define MPU_INT_EXTI PC5
+#define USE_GYRO_EXTI
#define USE_MPU_DATA_READY_SIGNAL
//MPU-6000
@@ -63,11 +69,22 @@
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_GYRO_SPI_MPU6000
+#define USE_GYRO_SPI_ICM20689
+#define USE_ACC_SPI_ICM20689
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
-#define MPU6000_CS_PIN PC4
-#define MPU6000_SPI_INSTANCE SPI1
-#define GYRO_MPU6000_ALIGN CW270_DEG
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
+#define GYRO_1_CS_PIN PC4
+#define GYRO_1_EXTI_PIN PC5
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define USE_DUAL_GYRO
+
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_ALIGN CW0_DEG
+#define GYRO_2_SPI_INSTANCE SPI1
//Baro & MAG-------------------------------
#define USE_I2C
@@ -155,6 +172,7 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
-#define USABLE_TIMER_CHANNEL_COUNT 9
-#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(8)|TIM_N(12))
+#define USABLE_TIMER_CHANNEL_COUNT 10
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
diff --git a/src/main/target/FLYWOOF405/target.mk b/src/main/target/FLYWOOF405/target.mk
index 598c7de4e5..876b2861dc 100644
--- a/src/main/target/FLYWOOF405/target.mk
+++ b/src/main/target/FLYWOOF405/target.mk
@@ -1,11 +1,13 @@
F405_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
+ drivers/pinio.c \
drivers/max7456.c
diff --git a/src/main/target/FLYWOOF405S_AIO/target.c b/src/main/target/FLYWOOF405S_AIO/target.c
new file mode 100644
index 0000000000..a12b51ef56
--- /dev/null
+++ b/src/main/target/FLYWOOF405S_AIO/target.c
@@ -0,0 +1,44 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // motor 3
+ DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 7
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 8
+ DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 0, 0), // led
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FLYWOOF405S_AIO/target.h b/src/main/target/FLYWOOF405S_AIO/target.h
new file mode 100644
index 0000000000..08c3cd52ae
--- /dev/null
+++ b/src/main/target/FLYWOOF405S_AIO/target.h
@@ -0,0 +1,143 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME FLYWOOF405S_AIO
+#define MANUFACTURER_ID FLWO
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_ACC_SPI_ICM42688P
+#define USE_ACCGYRO_BMI270
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_GYRO_SPI_ICM42688P
+#define USE_BARO
+#define USE_BARO_BMP280
+#define USE_BARO_DPS310
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC14
+#define LED_STRIP_PIN PA9
+#define USE_BEEPER
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+#define USE_USB_DETECT
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_EXTI_PIN PB13
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define USE_DUAL_GYRO
+
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_ALIGN CW0_DEG
+#define GYRO_2_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PB6
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PD5
+#define UART2_RX_PIN PD6
+#define USE_UART3
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART5
+#define UART5_RX_PIN PD2
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 7
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define DASHBOARD_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PB3
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB14
+#define MAX7456_SPI_INSTANCE SPI3
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC3
+#define CURRENT_METER_ADC_PIN PC2
+#define RSSI_ADC_PIN PC0
+#define ADC1_DMA_OPT 0
+#define ADC1_DMA_STREAM DMA2_Stream0 //# ADC 1: DMA2 Stream 0 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 170
+
+#define USE_ESCSERIAL
+#define ESCSERIAL_TIMER_TX_PIN PB8
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FLYWOOF405S_AIO/target.mk b/src/main/target/FLYWOOF405S_AIO/target.mk
new file mode 100644
index 0000000000..c17c00ab23
--- /dev/null
+++ b/src/main/target/FLYWOOF405S_AIO/target.mk
@@ -0,0 +1,15 @@
+F405_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_spi_icm426xx.c \
+drivers/accgyro/accgyro_spi_bmi270.c \
+drivers/barometer/barometer_bmp280.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/FLYWOOF411EVO_HD/target.c b/src/main/target/FLYWOOF411EVO_HD/target.c
new file mode 100644
index 0000000000..633637bce8
--- /dev/null
+++ b/src/main/target/FLYWOOF411EVO_HD/target.c
@@ -0,0 +1,44 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 1), // motor 1
+ DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 1), // motor 2
+ DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR, 0, 1), // motor 3
+ DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM9, CH1, PA2, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN; dma 0 assumed, please verify
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0, 0), // pwm RX_PWM1_PIN
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_LED, 0, 0), // led
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FLYWOOF411EVO_HD/target.h b/src/main/target/FLYWOOF411EVO_HD/target.h
new file mode 100644
index 0000000000..ac4dab1f88
--- /dev/null
+++ b/src/main/target/FLYWOOF411EVO_HD/target.h
@@ -0,0 +1,125 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME FLYWOOF411EVO_HD
+#define MANUFACTURER_ID FLWO
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC13
+#define LED_STRIP_PIN PB5
+#define USE_BEEPER
+#define BEEPER_PIN PC14
+#define BEEPER_INVERTED
+#define USE_USB_DETECT
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_EXTI_PIN PB3
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define USE_DUAL_GYRO
+
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_ALIGN CW0_DEG
+#define GYRO_2_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PB6
+#define UART1_RX_PIN PB7
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define SERIAL_PORT_COUNT 3
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PB2
+#define FLASH_SPI_INSTANCE SPI2
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PA0
+#define CURRENT_METER_ADC_PIN PA1
+#define RSSI_ADC_PIN PB1
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 170
+#define ADC_INSTANCE ADC1
+
+#define ENABLE_DSHOT_DMAR true
+
+#define PINIO1_PIN PB5
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(9) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FLYWOOF411EVO_HD/target.mk b/src/main/target/FLYWOOF411EVO_HD/target.mk
new file mode 100644
index 0000000000..d986dff19b
--- /dev/null
+++ b/src/main/target/FLYWOOF411EVO_HD/target.mk
@@ -0,0 +1,13 @@
+F411_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/pinio.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/FLYWOOF411_5IN1_AIO/target.h b/src/main/target/FLYWOOF411_5IN1_AIO/target.h
index 33c06dde11..d67900c710 100644
--- a/src/main/target/FLYWOOF411_5IN1_AIO/target.h
+++ b/src/main/target/FLYWOOF411_5IN1_AIO/target.h
@@ -21,8 +21,10 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "FLWO"
-#define USBD_PRODUCT_STRING "FLYWOOF411_5IN1_AIO"
+#define BOARD_NAME FLYWOOF411_5IN1_AIO
+#define MANUFACTURER_ID FLWO
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
#define LED0_PIN PC13
@@ -39,11 +41,6 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define MPU6000_CS_PIN PA4
-//#define ICM20689_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-//#define ICM20689_SPI_INSTANCE SPI1
-
#define USE_EXTI
#define USE_GYRO_EXTI
#define MPU_INT_EXTI PB2
@@ -52,24 +49,23 @@
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW0_DEG_FLIP
-//#define USE_GYRO_SPI_ICM20689
-//#define ACC_ICM20689_ALIGN CW180_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW0_DEG_FLIP
-//#define USE_ACC_SPI_ICM20689
-//#define ACC_ICM20689_ALIGN CW180_DEG
-
#define USE_GYRO_SPI_ICM42688P
#define USE_ACC_SPI_ICM42688P
+#define USE_ACCGYRO_BMI270
+#define USE_SPI_GYRO
+
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_MPU6000_ALIGN CW0_DEG_FLIP
+#define ACC_MPU6000_ALIGN CW0_DEG_FLIP
#define ICM42688P_SPI_INSTANCE SPI1
#define ICM42688P_CS_PIN PA4
#define ACC_ICM42688P_ALIGN CW0_DEG_FLIP
#define GYRO_ICM42688P_ALIGN CW0_DEG_FLIP
-#define USE_SPI_GYRO
#define BMI270_SPI_INSTANCE SPI1
#define BMI270_CS_PIN PA4
#define ACC_BMI270_ALIGN CW0_DEG_FLIP
diff --git a/src/main/target/FLYWOOF411_5IN1_AIO/target.mk b/src/main/target/FLYWOOF411_5IN1_AIO/target.mk
index a0f0b8aff2..2969ae3970 100644
--- a/src/main/target/FLYWOOF411_5IN1_AIO/target.mk
+++ b/src/main/target/FLYWOOF411_5IN1_AIO/target.mk
@@ -5,7 +5,6 @@ FEATURES += VCP
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_bmi270.c \
- drivers/accgyro/accgyro_spi_icm20689.c \
drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_bmp085.c \
diff --git a/src/main/target/FLYWOOF745NANO/target.c b/src/main/target/FLYWOOF745NANO/target.c
new file mode 100644
index 0000000000..c000a77129
--- /dev/null
+++ b/src/main/target/FLYWOOF745NANO/target.c
@@ -0,0 +1,46 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR, 0, 2), // motor 3
+ DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR, 0, 1), // motor 4
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 7
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 8
+ DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // ppm RX_PPM_PIN
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check
+ DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // led
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FLYWOOF745NANO/target.h b/src/main/target/FLYWOOF745NANO/target.h
new file mode 100644
index 0000000000..b267abb1ab
--- /dev/null
+++ b/src/main/target/FLYWOOF745NANO/target.h
@@ -0,0 +1,147 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME FLYWOOF745NANO
+#define MANUFACTURER_ID FLWO
+#define TARGET_BOARD_IDENTIFIER "S745" // generic ID
+#define FC_TARGET_MCU STM32F745 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_BARO_BMP280
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+#define USE_BARO
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PA2
+#define LED_STRIP_PIN PD12
+#define USE_BEEPER
+#define BEEPER_PIN PD15
+#define BEEPER_INVERTED
+#define USE_USB_DETECT
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_4
+#define SPI4_SCK_PIN PE2
+#define SPI4_MISO_PIN PE5
+#define SPI4_MOSI_PIN PE6
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PE1
+
+#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_MPU6000_ALIGN CW270_DEG
+#define MPU6000_CS_PIN PE4
+#define MPU6000_SPI_INSTANCE SPI4
+
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PD5
+#define UART2_RX_PIN PD6
+#define USE_UART3
+#define UART3_TX_PIN PD8
+#define UART3_RX_PIN PD9
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART5
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define USE_UART7
+#define UART7_TX_PIN PE8
+#define UART7_RX_PIN PE7
+#define SERIAL_PORT_COUNT 8
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define DASHBOARD_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
+#define USE_I2C_DEVICE_2
+#define I2C_DEVICE_2 (I2CDEV_2)
+#define I2C2_SCL PB10
+#define I2C2_SDA PB11
+
+#define FLASH_CS_PIN PA4
+#define FLASH_SPI_INSTANCE SPI1
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC3
+#define CURRENT_METER_ADC_PIN PC2
+#define RSSI_ADC_PIN PC5
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 175
+
+#define PINIO1_PIN PC0
+
+#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
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 11
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FLYWOOF745NANO/target.mk b/src/main/target/FLYWOOF745NANO/target.mk
new file mode 100644
index 0000000000..7555338742
--- /dev/null
+++ b/src/main/target/FLYWOOF745NANO/target.mk
@@ -0,0 +1,14 @@
+F7X5XG_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/barometer/barometer_bmp280.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/pinio.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/FLYWOOF7DUAL/target.c b/src/main/target/FLYWOOF7DUAL/target.c
index fc62d5b12d..f28ff33b00 100755
--- a/src/main/target/FLYWOOF7DUAL/target.c
+++ b/src/main/target/FLYWOOF7DUAL/target.c
@@ -36,7 +36,10 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), // S4 (1,5)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), // S5 (2,4)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S6 (2,1)
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP(2,6)
DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), // FC CAM(1,7)
-
+ DEF_TIM(TIM2, CH3, PB10, TIM_USE_PWM, 0, 0), // pwm RX_PWM1_PIN
+ DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // pwm RX_PWM2_PIN
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_PWM, 0, 1), // pwm RX_PWM3_PIN
};
diff --git a/src/main/target/FLYWOOF7DUAL/target.h b/src/main/target/FLYWOOF7DUAL/target.h
index f138afabe7..943d6ab3c8 100755
--- a/src/main/target/FLYWOOF7DUAL/target.h
+++ b/src/main/target/FLYWOOF7DUAL/target.h
@@ -20,8 +20,10 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "FWF7"
-#define USBD_PRODUCT_STRING "FLYWOOF7DUAL"
+#define BOARD_NAME FLYWOOF7DUAL
+#define MANUFACTURER_ID FLWO
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define ENABLE_DSHOT_DMAR true
@@ -66,37 +68,40 @@
#define CAMERA_CONTROL_PIN PB8
-#define USE_DUAL_GYRO
+#define USE_SPI_GYRO
#define USE_EXTI
-#define GYRO_1_EXTI_PIN PC3
-#define GYRO_2_EXTI_PIN PC4
-#define MPU_INT_EXTI PC3
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+#define ENSURE_MPU_DATA_READY_IS_LOW
#define GYRO_1_CS_PIN PA4
#define GYRO_1_SPI_INSTANCE SPI1
#define GYRO_2_CS_PIN PB2
#define GYRO_2_SPI_INSTANCE SPI1
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
-
#define USE_GYRO
-#define USE_GYRO_SPI_MPU6000
-#define USE_GYRO_SPI_ICM20689
-
#define USE_ACC
+#define USE_GYRO_SPI_MPU6000
#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_ICM20689
#define USE_ACC_SPI_ICM20689
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+
+#define ACC_1_ALIGN CW180_DEG_FLIP
+#define GYRO_1_ALIGN CW180_DEG_FLIP
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_EXTI_PIN PC3
+#define GYRO_1_SPI_INSTANCE SPI1
-#define ACC_MPU6000_1_ALIGN CW180_DEG_FLIP
-#define GYRO_MPU6000_1_ALIGN CW180_DEG_FLIP
-#define GYRO_1_ALIGN GYRO_MPU6000_1_ALIGN
-#define ACC_1_ALIGN ACC_MPU6000_1_ALIGN
+#define USE_DUAL_GYRO
-#define ACC_ICM20689_2_ALIGN CW270_DEG
-#define GYRO_ICM20689_2_ALIGN CW270_DEG
-#define GYRO_2_ALIGN GYRO_ICM20689_2_ALIGN
-#define ACC_2_ALIGN ACC_ICM20689_2_ALIGN
+#define ACC_2_ALIGN CW270_DEG
+#define GYRO_2_ALIGN CW270_DEG
+#define GYRO_2_CS_PIN PB2
+#define GYRO_2_EXTI_PIN PC4
+#define GYRO_2_SPI_INSTANCE SPI1
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
@@ -156,7 +161,7 @@
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define DEFAULT_FEATURES (FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP)
+#define DEFAULT_FEATURES (FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_AIRMODE | FEATURE_LED_STRIP)
#define SERIALRX_UART SERIAL_PORT_USART1
#define SERIALRX_PROVIDER SERIALRX_SBUS
@@ -174,5 +179,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
-#define USABLE_TIMER_CHANNEL_COUNT 9
-#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) |TIM_N(11) )
+#define USABLE_TIMER_CHANNEL_COUNT 12
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(10) )
diff --git a/src/main/target/FLYWOOF7DUAL/target.mk b/src/main/target/FLYWOOF7DUAL/target.mk
index e9705d855a..6b5db65c94 100755
--- a/src/main/target/FLYWOOF7DUAL/target.mk
+++ b/src/main/target/FLYWOOF7DUAL/target.mk
@@ -5,6 +5,7 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
diff --git a/src/main/target/FOXEERF745V2_AIO/target.c b/src/main/target/FOXEERF745V2_AIO/target.c
new file mode 100644
index 0000000000..4de1871efa
--- /dev/null
+++ b/src/main/target/FOXEERF745V2_AIO/target.c
@@ -0,0 +1,41 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // led
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // cam ctrl
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FOXEERF745V2_AIO/target.h b/src/main/target/FOXEERF745V2_AIO/target.h
new file mode 100644
index 0000000000..b5c328c80a
--- /dev/null
+++ b/src/main/target/FOXEERF745V2_AIO/target.h
@@ -0,0 +1,131 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME FOXEERF745V2_AIO
+#define MANUFACTURER_ID FOXE
+#define TARGET_BOARD_IDENTIFIER "S745" // generic ID
+#define FC_TARGET_MCU STM32F745 // not used in EmuF
+
+#define USE_GYRO
+#define USE_ACC
+#define USE_ACCGYRO_BMI270
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC13
+#define LED_STRIP_PIN PA8
+#define USE_BEEPER
+#define BEEPER_PIN PD2
+#define BEEPER_INVERTED
+#define CAMERA_CONTROL_PIN PB3
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+#define USE_SPI_DEVICE_4
+#define SPI4_SCK_PIN PE2
+#define SPI4_MISO_PIN PE5
+#define SPI4_MOSI_PIN PE6
+
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define MPU_INT_EXTI PD0
+
+#define USE_SPI_GYRO
+#define ACC_BMI270_ALIGN CW0_DEG
+#define GYRO_BMI270_ALIGN CW0_DEG
+#define BMI270_CS_PIN PA15
+#define BMI270_SPI_INSTANCE SPI3
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART7
+#define UART7_TX_PIN PE8
+#define UART7_RX_PIN PE7
+#define SERIAL_PORT_COUNT 6
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PE4
+#define FLASH_SPI_INSTANCE SPI4
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PA4
+#define MAX7456_SPI_INSTANCE SPI1
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC3
+#define CURRENT_METER_ADC_PIN PC2
+#define RSSI_ADC_PIN PC5
+#define ADC1_DMA_OPT 0
+#define ADC1_DMA_STREAM DMA2_Stream0 //# ADC 1: DMA2 Stream 0 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 100
+
+#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
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 6
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FOXEERF745V2_AIO/target.mk b/src/main/target/FOXEERF745V2_AIO/target.mk
new file mode 100644
index 0000000000..7cca4ddbf8
--- /dev/null
+++ b/src/main/target/FOXEERF745V2_AIO/target.mk
@@ -0,0 +1,12 @@
+F7X5XG_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_bmi270.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/FULLSPEEDF411/target.c b/src/main/target/FULLSPEEDF411/target.c
new file mode 100644
index 0000000000..44de231806
--- /dev/null
+++ b/src/main/target/FULLSPEEDF411/target.c
@@ -0,0 +1,41 @@
+/*
+ * 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/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN
+
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S1_OUT
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S2_OUT
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // S3_OUT
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // S4_OUT
+
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // S5
+ DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), // S6
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // RSSI pad
+ DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), // TX2
+
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED
+};
diff --git a/src/main/target/FULLSPEEDF411/target.h b/src/main/target/FULLSPEEDF411/target.h
new file mode 100644
index 0000000000..e1a2fe7370
--- /dev/null
+++ b/src/main/target/FULLSPEEDF411/target.h
@@ -0,0 +1,129 @@
+/*
+ * 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 BOARD_NAME FULLSPEEDF411
+#define MANUFACTURER_ID CUST
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
+
+#define LED0_PIN PC13
+#define LED1_PIN PC14
+
+#define USE_BEEPER
+#define BEEPER_PIN PB2
+#define BEEPER_INVERTED
+
+// *************** Gyro & ACC **********************
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define MPU6500_CS_PIN PA4
+#define MPU6500_SPI_INSTANCE SPI1
+
+#define USE_EXTI
+#define MPU_INT_EXTI PA1
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define ACC_MPU6000_ALIGN CW180_DEG
+
+#define USE_GYRO_SPI_MPU6500
+#define GYRO_MPU6500_ALIGN CW0_DEG
+#define USE_ACC_SPI_MPU6500
+#define ACC_MPU6500_ALIGN CW0_DEG
+
+// *************** Baro **************************
+#define USE_I2C
+
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE (I2CDEV_1)
+#define I2C1_SCL PB8 // SCL pad
+#define I2C1_SDA PB9 // SDA pad
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+
+#define USE_BARO
+#define USE_BARO_BMP280
+#define USE_BARO_MS5611
+#define USE_BARO_BMP085
+
+// *************** UART *****************************
+#define USE_VCP
+#define VBUS_SENSING_PIN PC15
+#define VBUS_SENSING_ENABLED
+
+#define USE_UART1
+#define UART1_RX_PIN PA10
+#define UART1_TX_PIN PA9
+
+#define USE_UART2
+#define UART2_RX_PIN PA3
+#define UART2_TX_PIN PA2
+
+#define USE_SOFTSERIAL1
+#define USE_SOFTSERIAL2
+
+#define SERIAL_PORT_COUNT 5
+
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+#define SERIALRX_PROVIDER SERIALRX_SBUS
+#define SERIALRX_UART SERIAL_PORT_USART1
+
+// *************** OSD *****************************
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_MAX7456
+#define MAX7456_SPI_INSTANCE SPI2
+#define MAX7456_SPI_CS_PIN PB12
+
+// *************** ADC *****************************
+#define USE_ADC
+#define ADC1_DMA_STREAM DMA2_Stream0
+#define VBAT_ADC_PIN PB0
+#define CURRENT_METER_ADC_PIN PB1
+//#define RSSI_ADC_PIN PA0
+
+#define USE_ESCSERIAL
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD (BIT(2))
+
+#define USABLE_TIMER_CHANNEL_COUNT 10
+#define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(5)|TIM_N(9) )
+
diff --git a/src/main/target/FULLSPEEDF411/target.mk b/src/main/target/FULLSPEEDF411/target.mk
new file mode 100644
index 0000000000..548aef1968
--- /dev/null
+++ b/src/main/target/FULLSPEEDF411/target.mk
@@ -0,0 +1,11 @@
+F411_TARGETS += $(TARGET)
+FEATURES += SDCARD VCP
+
+TARGET_SRC = \
+ drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/barometer/barometer_bmp085.c \
+ drivers/barometer/barometer_bmp280.c \
+ drivers/barometer/barometer_ms5611.c \
+ drivers/max7456.c
diff --git a/src/main/target/GEPRCF405/target.h b/src/main/target/GEPRCF405/target.h
index c4ce6fd344..34ce84070f 100644
--- a/src/main/target/GEPRCF405/target.h
+++ b/src/main/target/GEPRCF405/target.h
@@ -21,9 +21,10 @@
#define USE_TARGET_CONFIG
-#define TARGET_BOARD_IDENTIFIER "GPR4"
-#define TARGET_MANUFACTURER_IDENTIFIER "GEPR"
-#define USBD_PRODUCT_STRING "GEPRCF405"
+#define BOARD_NAME GEPRCF405
+#define MANUFACTURER_ID GEPR
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
#define LED0_PIN PC14
#define LED1_PIN PC15
@@ -32,21 +33,36 @@
#define BEEPER_PIN PC13
#define BEEPER_INVERTED
+#define USE_SPI_GYRO
#define USE_EXTI
+#define USE_GYRO_EXTI
+
#define MPU_INT_EXTI PC3
#define USE_MPU_DATA_READY_SIGNAL
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_1_ALIGN CW270_DEG
-
+#define USE_ACC_SPI_ICM42688P
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACCGYRO_BMI270
+#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_MPU6000_ALIGN CW270_DEG
#define MPU6000_CS_PIN PA15
#define MPU6000_SPI_INSTANCE SPI3
+#define ACC_ICM42688P_ALIGN CW180_DEG
+#define GYRO_ICM42688P_ALIGN CW180_DEG
+#define ICM42688P_CS_PIN PA15
+#define ICM42688P_SPI_INSTANCE SPI3
+
+#define ACC_BMI270_ALIGN CW180_DEG
+#define GYRO_BMI270_ALIGN CW180_DEG
+#define BMI270_CS_PIN PA15
+#define BMI270_SPI_INSTANCE SPI3
+
//-------------------------------------SPI2 FLASH------------------------------
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_FLASHFS
diff --git a/src/main/target/GEPRCF405/target.mk b/src/main/target/GEPRCF405/target.mk
index d195664d8a..7ff7b2b71b 100644
--- a/src/main/target/GEPRCF405/target.mk
+++ b/src/main/target/GEPRCF405/target.mk
@@ -3,10 +3,12 @@ FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
- drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip.c \
drivers/max7456.c
diff --git a/src/main/target/GEPRCF722/target.c b/src/main/target/GEPRCF722/target.c
new file mode 100644
index 0000000000..2d4b6bfeb8
--- /dev/null
+++ b/src/main/target/GEPRCF722/target.c
@@ -0,0 +1,44 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // led
+ DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN; dma 0 assumed, please verify
+ DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // pwm RX_PWM1_PIN; dma 0 assumed, please verify
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/GEPRCF722/target.h b/src/main/target/GEPRCF722/target.h
new file mode 100644
index 0000000000..04f4d1c9be
--- /dev/null
+++ b/src/main/target/GEPRCF722/target.h
@@ -0,0 +1,153 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#pragma once
+
+#define BOARD_NAME GEPRCF722
+#define MANUFACTURER_ID GEPR
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_ACC_SPI_ICM42688P
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_GYRO_SPI_ICM42688P
+#define USE_BARO
+#define USE_BARO_BMP280
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PA13
+#define LED1_PIN PA14
+#define LED_STRIP_PIN PA8
+#define USE_BEEPER
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+#define USE_USB_DETECT
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
+#define GYRO_1_CS_PIN PA15
+#define GYRO_1_EXTI_PIN PC3
+#define GYRO_1_SPI_INSTANCE SPI3
+
+#define USE_DUAL_GYRO
+
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_ALIGN CW0_DEG
+#define GYRO_2_CS_PIN PD2
+#define GYRO_2_EXTI_PIN PC4
+#define GYRO_2_SPI_INSTANCE SPI3
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 6
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+#define USE_I2C_DEVICE_2
+#define I2C_DEVICE_2 (I2CDEV_2)
+#define I2C2_SCL PB10
+#define I2C2_SDA PB11
+
+#define FLASH_CS_PIN PB12
+#define FLASH_SPI_INSTANCE SPI2
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB2
+#define MAX7456_SPI_INSTANCE SPI1
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC0
+#define CURRENT_METER_ADC_PIN PC1
+#define RSSI_ADC_PIN PC2
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 179
+
+#define ENABLE_DSHOT_DMAR true
+
+#define PINIO1_PIN PC8
+#define PINIO2_PIN PC9
+#define PINIO1_BOX 40
+#define PINIO2_BOX 41
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(9) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/GEPRCF722/target.mk b/src/main/target/GEPRCF722/target.mk
new file mode 100644
index 0000000000..af7157e9ea
--- /dev/null
+++ b/src/main/target/GEPRCF722/target.mk
@@ -0,0 +1,15 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_spi_icm426xx.c \
+drivers/barometer/barometer_bmp280.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/pinio.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 889ce5d
diff --git a/src/main/target/GEPRCF722BT/target.h b/src/main/target/GEPRCF722BT/target.h
index 589aa9a2d5..d39262c4f9 100644
--- a/src/main/target/GEPRCF722BT/target.h
+++ b/src/main/target/GEPRCF722BT/target.h
@@ -23,9 +23,10 @@
#define USE_TARGET_CONFIG
-#define TARGET_BOARD_IDENTIFIER "S7X2"
-#define USBD_PRODUCT_STRING "GEPRCF722BT"
-#define TARGET_MANUFACTURER_IDENTIFIER "GEPR"
+#define BOARD_NAME GEPRCF722BT
+#define MANUFACTURER_ID GEPR
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define LED0_PIN PC15
#define LED1_PIN PC14
@@ -42,14 +43,27 @@
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-#define GYRO_1_ALIGN CW0_DEG
-
+#define USE_GYRO_SPI_MPU6500
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6000_ALIGN CW0_DEG
+#define USE_ACCGYRO_BMI270
+
+#define ACC_MPU6000_ALIGN CW0_DEG
+#define GYRO_MPU6000_ALIGN CW0_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+// MPU6500 validity is doubtful
+#define ACC_MPU6500_ALIGN CW0_DEG
+#define GYRO_MPU6500_ALIGN CW0_DEG
+#define MPU6500_CS_PIN PA4
+#define MPU6500_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW0_DEG
+#define GYRO_BMI270_ALIGN CW0_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
#define USE_BARO
#define USE_BARO_BMP280
diff --git a/src/main/target/GEPRCF722BT/target.mk b/src/main/target/GEPRCF722BT/target.mk
index 8c9eb1dcd7..6133656041 100644
--- a/src/main/target/GEPRCF722BT/target.mk
+++ b/src/main/target/GEPRCF722BT/target.mk
@@ -1,14 +1,15 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_mpu6500.c \
- drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_spi_mpu6500.c \
- drivers/barometer/barometer_ms5611.c \
- drivers/barometer/barometer_bmp280.c \
- drivers/barometer/barometer_bmp085.c \
- drivers/compass/compass_hmc5883l.c \
- drivers/compass/compass_qmc5883l.c \
- drivers/max7456.c\
- drivers/light_ws2811strip.c
+ drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
+ drivers/barometer/barometer_ms5611.c \
+ drivers/barometer/barometer_bmp280.c \
+ drivers/barometer/barometer_bmp085.c \
+ drivers/compass/compass_hmc5883l.c \
+ drivers/compass/compass_qmc5883l.c \
+ drivers/max7456.c\
+ drivers/light_ws2811strip.c
diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h
index 2cb368bae7..7ecfbac2c1 100644
--- a/src/main/target/GEPRC_F722_AIO/target.h
+++ b/src/main/target/GEPRC_F722_AIO/target.h
@@ -21,9 +21,10 @@
*/
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S7X2"
-#define USBD_PRODUCT_STRING "GEPRC_F722_AIO"
-#define TARGET_MANUFACTURER_IDENTIFIER "GEPR"
+#define BOARD_NAME GEPRC_F722_AIO
+#define MANUFACTURER_ID GEPR
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define LED0_PIN PC4
@@ -33,30 +34,35 @@
#define ENABLE_DSHOT_DMAR true
-#define USE_EXTI
-#define MPU_INT_EXTI PA8
-#define USE_MPU_DATA_READY_SIGNAL
-
#define USE_GYRO
-
+#define USE_GYRO_SPI_MPU6000
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_ACCGYRO_BMI270
#define USE_GYRO_SPI_ICM42688P
-#define ICM42688P_CS_PIN PA15
-#define ICM42688P_SPI_INSTANCE SPI1
-#define GYRO_ICM42688P_ALIGN CW90_DEG
+#define USE_ACC_SPI_ICM42688P
-#define USE_GYRO_SPI_MPU6000
-#define MPU6000_CS_PIN PA15
-#define MPU6000_SPI_INSTANCE SPI1
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define USE_EXTI
+#define USE_SPI_GYRO
+#define USE_GYRO_EXTI
-#define USE_ACC
+#define MPU_INT_EXTI PA8
+#define USE_MPU_DATA_READY_SIGNAL
-#define USE_ACC_SPI_ICM42688P
-#define ACC_ICM42688P_ALIGN CW90_DEG
+#define ACC_MPU6000_ALIGN CW90_DEG
+#define GYRO_MPU6000_ALIGN CW90_DEG
+#define MPU6000_CS_PIN PA15
+#define MPU6000_SPI_INSTANCE SPI1
-#define USE_ACC_SPI_MPU6000
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define ACC_ICM42688P_ALIGN CW90_DEG
+#define GYRO_ICM42688P_ALIGN CW90_DEG
+#define ICM42688P_CS_PIN PA15
+#define ICM42688P_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW90_DEG
+#define GYRO_BMI270_ALIGN CW90_DEG
+#define BMI270_CS_PIN PA15
+#define BMI270_SPI_INSTANCE SPI1
#define USE_BARO
#define USE_BARO_BMP280
diff --git a/src/main/target/GEPRC_F722_AIO/target.mk b/src/main/target/GEPRC_F722_AIO/target.mk
index ed078d59ff..c7a53a047e 100644
--- a/src/main/target/GEPRC_F722_AIO/target.mk
+++ b/src/main/target/GEPRC_F722_AIO/target.mk
@@ -1,11 +1,10 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_bmp085.c \
diff --git a/src/main/target/HAKRCF722D/target.h b/src/main/target/HAKRCF722D/target.h
index 7bfd7d6ede..aa5d6bbb2f 100644
--- a/src/main/target/HAKRCF722D/target.h
+++ b/src/main/target/HAKRCF722D/target.h
@@ -22,8 +22,10 @@
#define USE_TARGET_CONFIG
-#define TARGET_BOARD_IDENTIFIER "HK7D"
-#define USBD_PRODUCT_STRING "HAKRCF722D"
+#define BOARD_NAME HAKRCF722D
+#define MANUFACTURER_ID HARC
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define ENABLE_DSHOT_DMAR true
@@ -42,34 +44,36 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define USE_DUAL_GYRO
#define USE_EXTI
-#define GYRO_1_EXTI_PIN PC4
-#define GYRO_2_EXTI_PIN PC3
-#define MPU_INT_EXTI
-
-#define GYRO_1_CS_PIN PB2
-#define GYRO_1_SPI_INSTANCE SPI1
-#define GYRO_2_CS_PIN PC15
-#define GYRO_2_SPI_INSTANCE SPI1
+#define USE_SPI_GYRO
+#define USE_GYRO_EXTI
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_MPU6500
+#define USE_GYRO_SPI_ICM42688P
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
+#define USE_ACC_SPI_ICM42688P
+#define USE_ACCGYRO_BMI270
-#define GYRO_MPU6000_1_ALIGN CW180_DEG
-#define ACC_MPU6000_1_ALIGN CW180_DEG
-#define GYRO_1_ALIGN GYRO_MPU6000_1_ALIGN
-#define ACC_1_ALIGN ACC_MPU6000_1_ALIGN
+#define ACC_1_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
+#define GYRO_1_CS_PIN PB2
+#define GYRO_1_EXTI_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_MPU6000_1_ALIGN CW180_DEG
+#define ACC_MPU6000_1_ALIGN CW180_DEG
+
+#define USE_DUAL_GYRO
-#define GYRO_MPU6500_2_ALIGN CW90_DEG
-#define ACC_MPU6500_2_ALIGN CW90_DEG
-#define GYRO_2_ALIGN GYRO_MPU6500_2_ALIGN
-#define ACC_2_ALIGN ACC_MPU6500_2_ALIGN
+#define ACC_2_ALIGN CW90_DEG
+#define GYRO_2_ALIGN CW90_DEG
+#define GYRO_2_CS_PIN PC15
+#define GYRO_2_EXTI_PIN PC3
+#define GYRO_2_SPI_INSTANCE SPI1
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
diff --git a/src/main/target/HAKRCF722D/target.mk b/src/main/target/HAKRCF722D/target.mk
index 18775ea3cb..1091c44d10 100644
--- a/src/main/target/HAKRCF722D/target.mk
+++ b/src/main/target/HAKRCF722D/target.mk
@@ -6,10 +6,12 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
- drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip.c \
drivers/max7456.c
diff --git a/src/main/target/HGLRCF405V2/target.c b/src/main/target/HGLRCF405V2/target.c
new file mode 100644
index 0000000000..95e04229cb
--- /dev/null
+++ b/src/main/target/HGLRCF405V2/target.c
@@ -0,0 +1,45 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 1), // motor 1
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1), // motor 2
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), // motor 3
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 1), // motor 6
+ DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), // motor 7
+ DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR, 0, 0), // motor 8
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // led
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/HGLRCF405V2/target.h b/src/main/target/HGLRCF405V2/target.h
new file mode 100644
index 0000000000..cf58254d4d
--- /dev/null
+++ b/src/main/target/HGLRCF405V2/target.h
@@ -0,0 +1,136 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#pragma once
+
+#define BOARD_NAME HGLRCF405V2
+#define MANUFACTURER_ID HGLRC
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_BARO
+#define USE_BARO_BMP280
+#define USE_BARO_DPS310
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC13
+#define LED_STRIP_PIN PB1
+#define USE_BEEPER
+#define BEEPER_PIN PB8
+#define BEEPER_INVERTED
+#define USE_USB_DETECT
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PC4
+
+#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_MPU6000_ALIGN CW270_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PC10
+#define UART3_RX_PIN PC11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART5
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+#define SERIAL_PORT_COUNT 6
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
+
+#define FLASH_CS_PIN PC0
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PA13
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC2
+#define CURRENT_METER_ADC_PIN PC1
+#define RSSI_ADC_PIN PC3
+#define ADC1_DMA_OPT 0
+#define ADC1_DMA_STREAM DMA2_Stream0 //# ADC 1: DMA2 Stream 0 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define ADC_INSTANCE ADC1
+
+#define USE_ESCSERIAL
+#define ESCSERIAL_TIMER_TX_PIN PC11
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 10
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/HGLRCF405V2/target.mk b/src/main/target/HGLRCF405V2/target.mk
new file mode 100644
index 0000000000..412fb865e0
--- /dev/null
+++ b/src/main/target/HGLRCF405V2/target.mk
@@ -0,0 +1,13 @@
+F405_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/barometer/barometer_bmp280.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 889ce5d
diff --git a/src/main/target/HGLRCF411/target.h b/src/main/target/HGLRCF411/target.h
index bae2f2a557..7b97170a1c 100644
--- a/src/main/target/HGLRCF411/target.h
+++ b/src/main/target/HGLRCF411/target.h
@@ -19,9 +19,11 @@
*/
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S411"
-#define USBD_PRODUCT_STRING "HGLRCF411"
-#define TARGET_MANUFACTURER_IDENTIFIER "HGLR"
+
+#define BOARD_NAME HGLRCF411
+#define MANUFACTURER_ID HGLR
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
#define ENABLE_DSHOT_DMAR true
@@ -39,14 +41,26 @@
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_GYRO_SPI_MPU6000
+#define USE_ACC_SPI_ICM42688P
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACCGYRO_BMI270
+
+#define USE_SPI_GYRO
#define USE_EXTI
+#define USE_GYRO_EXTI
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PA1 //MPU_INT_EXTI
-#define MPU6000_CS_PIN PA4 //GYRO_1_CS_PIN
-#define MPU6000_SPI_INSTANCE SPI1 //GYRO_1_SPI_INSTANCE
-#define GYRO_MPU6000_ALIGN CW180_DEG
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_EXTI_PIN PA1
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define USE_DUAL_GYRO
+
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_ALIGN CW0_DEG
+#define GYRO_2_SPI_INSTANCE SPI1
// OSD
#define USE_MAX7456
diff --git a/src/main/target/HGLRCF411/target.mk b/src/main/target/HGLRCF411/target.mk
index eb151d2940..dc80441d2f 100644
--- a/src/main/target/HGLRCF411/target.mk
+++ b/src/main/target/HGLRCF411/target.mk
@@ -4,6 +4,8 @@ FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/max7456.c
diff --git a/src/main/target/HGLRCF722/target.h b/src/main/target/HGLRCF722/target.h
index 20c581ef07..e354b80adc 100644
--- a/src/main/target/HGLRCF722/target.h
+++ b/src/main/target/HGLRCF722/target.h
@@ -22,8 +22,10 @@
#define USE_TARGET_CONFIG
+#define BOARD_NAME HGLRCF722
+#define MANUFACTURER_ID HGLR
#define TARGET_BOARD_IDENTIFIER "S7X2"
-#define USBD_PRODUCT_STRING "HGLRCF722"
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define ENABLE_DSHOT_DMAR true
@@ -42,20 +44,27 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
+#define USE_SPI_GYRO
#define USE_EXTI
+#define USE_GYRO_EXTI
#define MPU_INT_EXTI PC4
-#define MPU6000_CS_PIN PB2
-#define MPU6000_SPI_INSTANCE SPI1
-
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_ACC
#define USE_ACC_SPI_MPU6000
+#define USE_ACCGYRO_BMI270
#define GYRO_MPU6000_ALIGN CW180_DEG_FLIP
#define ACC_MPU6000_ALIGN CW180_DEG_FLIP
+#define MPU6000_CS_PIN PB2
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW180_DEG_FLIP
+#define GYRO_BMI270_ALIGN CW180_DEG_FLIP
+#define BMI270_CS_PIN PB2
+#define BMI270_SPI_INSTANCE SPI1
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
diff --git a/src/main/target/HGLRCF722/target.mk b/src/main/target/HGLRCF722/target.mk
index aec47e708a..6d9fcdcf0c 100644
--- a/src/main/target/HGLRCF722/target.mk
+++ b/src/main/target/HGLRCF722/target.mk
@@ -3,6 +3,7 @@ FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/accgyro/accgyro_mpu.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.c b/src/main/target/IFLIGHT_BLITZ_F722/target.c
new file mode 100644
index 0000000000..130f5797ca
--- /dev/null
+++ b/src/main/target/IFLIGHT_BLITZ_F722/target.c
@@ -0,0 +1,45 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), // motor 3
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), // motor 7
+ DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR, 0, 1), // motor 8
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 1), // ppm RX_PPM_PIN
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // led
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.h b/src/main/target/IFLIGHT_BLITZ_F722/target.h
new file mode 100644
index 0000000000..4c18fbcda1
--- /dev/null
+++ b/src/main/target/IFLIGHT_BLITZ_F722/target.h
@@ -0,0 +1,148 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME IFLIGHT_BLITZ_F722
+#define MANUFACTURER_ID IFRC
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_ACCGYRO_BMI270
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+#define USE_BARO_DPS310
+#define USE_FLASH
+#define USE_FLASH_M25P16
+#define USE_FLASH_W25N01G
+#define USE_MAX7456
+#define USE_BARO
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC15
+#define LED_STRIP_PIN PA8
+#define USE_BEEPER
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+#define USE_USB_DETECT
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PC4
+
+#define ACC_MPU6000_ALIGN CW0_DEG
+#define GYRO_MPU6000_ALIGN CW0_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_ICM42688P_ALIGN CW0_DEG
+#define GYRO_ICM42688P_ALIGN CW0_DEG
+#define ICM42688P_CS_PIN PA4
+#define ICM42688P_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW0_DEG
+#define GYRO_BMI270_ALIGN CW0_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PC10
+#define UART3_RX_PIN PC11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART5
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 7
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PA15
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC2
+#define CURRENT_METER_ADC_PIN PC1
+#define ADC1_DMA_OPT 0
+#define ADC1_DMA_STREAM DMA2_Stream0 //# ADC 1: DMA2 Stream 0 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 200
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 10
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.mk b/src/main/target/IFLIGHT_BLITZ_F722/target.mk
new file mode 100644
index 0000000000..f7e38b229e
--- /dev/null
+++ b/src/main/target/IFLIGHT_BLITZ_F722/target.mk
@@ -0,0 +1,14 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_spi_icm426xx.c \
+drivers/accgyro/accgyro_spi_bmi270.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/IFLIGHT_F411_PRO/target.h b/src/main/target/IFLIGHT_F411_PRO/target.h
index 2539723608..b740ec1e53 100644
--- a/src/main/target/IFLIGHT_F411_PRO/target.h
+++ b/src/main/target/IFLIGHT_F411_PRO/target.h
@@ -20,11 +20,10 @@
#pragma once
-#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
-#define USBD_PRODUCT_STRING "IFLIGHT_F411_PRO"
-
-#define FC_TARGET_MCU STM32F411 // not used in EmuF
+#define BOARD_NAME IFLIGHT_F411_PRO
+#define MANUFACTURER_ID IFRC
#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
#define ENABLE_DSHOT_DMAR true
@@ -35,20 +34,43 @@
#define BEEPER_PIN PB2
#define BEEPER_INVERTED
-//MPU-6000
-#define USE_GYRO
#define USE_ACC
+#define USE_ACC_SPI_ICM20689
+#define USE_ACC_SPI_ICM42688P
#define USE_ACC_SPI_MPU6000
+#define USE_ACCGYRO_BMI270
+#define USE_GYRO
+#define USE_GYRO_SPI_ICM20689
+#define USE_GYRO_SPI_ICM42688P
#define USE_GYRO_SPI_MPU6000
+
+#define USE_SPI_GYRO
#define USE_EXTI
+#define USE_GYRO_EXTI
+
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PA1 //MPU_INT_EXTI
-#define MPU6000_CS_PIN PA4 //GYRO_1_CS_PIN
-#define MPU6000_SPI_INSTANCE SPI1 //GYRO_1_SPI_INSTANCE
-#define GYRO_MPU6000_ALIGN CW0_DEG
-#define ACC_MPU6000_ALIGN CW0_DEG
+#define MPU_INT_EXTI PA1
+
+#define ACC_MPU6000_ALIGN CW0_DEG
+#define GYRO_MPU6000_ALIGN CW0_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_ICM20689_ALIGN CW0_DEG
+#define GYRO_ICM20689_ALIGN CW0_DEG
+#define ICM20689_CS_PIN PA4
+#define ICM20689_SPI_INSTANCE SPI1
+
+#define ACC_ICM42688P_ALIGN CW0_DEG
+#define GYRO_ICM42688P_ALIGN CW0_DEG
+#define ICM42688P_CS_PIN PA4
+#define ICM42688P_SPI_INSTANCE SPI1
+#define ACC_BMI270_ALIGN CW0_DEG
+#define GYRO_BMI270_ALIGN CW0_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
// *************** Baro **************************
#define USE_I2C
diff --git a/src/main/target/IFLIGHT_F411_PRO/target.mk b/src/main/target/IFLIGHT_F411_PRO/target.mk
index 8edaee8ecd..3a7f4c8a40 100644
--- a/src/main/target/IFLIGHT_F411_PRO/target.mk
+++ b/src/main/target/IFLIGHT_F411_PRO/target.mk
@@ -4,7 +4,10 @@ FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/barometer/barometer_bmp085.c \
+ drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
+ drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
diff --git a/src/main/target/JHEF405PRO/target.h b/src/main/target/JHEF405PRO/target.h
index 39494e436c..ca0e7ffe69 100644
--- a/src/main/target/JHEF405PRO/target.h
+++ b/src/main/target/JHEF405PRO/target.h
@@ -18,136 +18,151 @@
* If not, see .
*/
- #pragma once
-
- #define TARGET_BOARD_IDENTIFIER "JH4P"
- #define USBD_PRODUCT_STRING "JHEF405PRO"
- #define TARGET_MANUFACTURER_IDENTIFIER "JHEM"
-
- #define USE_TARGET_CONFIG
-
- #define LED0_PIN PC14
-
- #define USE_BEEPER
- #define BEEPER_PIN PC13
- #define BEEPER_INVERTED
-
- #define ENABLE_DSHOT_DMAR true
-
- #define USE_EXTI
- #define MPU_INT_EXTI PB13
- #define USE_MPU_DATA_READY_SIGNAL
-
- #define USE_GYRO
- #define USE_GYRO_SPI_MPU6000
- #define MPU6000_CS_PIN PB12
- #define MPU6000_SPI_INSTANCE SPI1
- #define GYRO_MPU6000_ALIGN CW180_DEG
- #define USE_GYRO_SPI_MPU6500
- #define GYRO_MPU6500_ALIGN CW180_DEG
- #define MPU6500_CS_PIN MPU6000_CS_PIN
- #define MPU6500_SPI_INSTANCE MPU6000_SPI_INSTANCE
-
- #define USE_ACC
- #define USE_ACC_SPI_MPU6000
- #define ACC_MPU6000_ALIGN CW180_DEG
- #define USE_ACC_SPI_MPU6500
- #define ACC_MPU6500_ALIGN CW180_DEG
-
-
- #define USE_BARO
- #define USE_BARO_BMP280
- #define USE_BARO_BMP085
- #define USE_BARO_ms5611
- #define BARO_I2C_INSTANCE (I2CDEV_1)
-
- #define USE_MAG
- #define USE_MAG_HMC5883
- #define USE_MAG_QMC5883
- #define MAG_I2C_INSTANCE (I2CDEV_1)
-
- #define USE_MAX7456
- #define MAX7456_SPI_INSTANCE SPI3
- #define MAX7456_SPI_CS_PIN PB14
-
- #define USE_FLASHFS
- #define USE_FLASH_M25P16
- #define FLASH_SPI_INSTANCE SPI3
- #define FLASH_CS_PIN PB3
- #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-
- #define USE_VCP
- #define USE_USB_DETECT
- #define USB_DETECT_PIN PA8
-
- #define USE_UART1
- #define UART1_RX_PIN PA10
- #define UART1_TX_PIN PB6
-
- #define USE_UART2
- #define UART2_RX_PIN PD6
- #define UART2_TX_PIN PD5
-
- #define USE_UART3
- #define UART3_RX_PIN PB11
- #define UART3_TX_PIN PB10
-
- #define USE_UART4
- #define UART4_RX_PIN PA1
- #define UART4_TX_PIN PA0
-
- #define USE_UART6
- #define UART6_RX_PIN PC7
- #define UART6_TX_PIN PC6
-
- #define SERIAL_PORT_COUNT 6 //USB + 5 UARTS
-
- #define USE_ESCSERIAL //PPM
- #define ESCSERIAL_TIMER_TX_PIN PB8
- #define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
- #define USE_SPI
- #define USE_SPI_DEVICE_1
- #define SPI1_SCK_PIN PA5
- #define SPI1_MISO_PIN PA6
- #define SPI1_MOSI_PIN PA7
-
- #define USE_SPI_DEVICE_3
- #define SPI3_SCK_PIN PC10
- #define SPI3_MISO_PIN PC11
- #define SPI3_MOSI_PIN PC12
-
- #define USE_I2C
- #define USE_I2C_DEVICE_1
- #define I2C2_SCL PB8
- #define I2C2_SDA PB9
- #define I2C_DEVICE (I2CDEV_1)
-
- #define USE_PINIO
- #define USE_PINIOBOX
-
- #define USE_DASHBOARD
- #define USE_I2C_OLED_DISPLAY
-
- #define USE_ADC
- #define ADC1_DMA_STREAM DMA2_Stream0
- #define VBAT_ADC_PIN PC3
- #define CURRENT_METER_ADC_PIN PC2
- #define RSSI_ADC_PIN PC0
- #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
- #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
- #define CURRENT_METER_SCALE_DEFAULT 170
-
- #define SERIALRX_PROVIDER SERIALRX_SBUS
- #define SERIALRX_UART SERIAL_PORT_USART1
-
- #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
- #define DEFAULT_FEATURES ( FEATURE_OSD )
-
- #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 9
- #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8))
+#pragma once
+
+#define BOARD_NAME JHEF405PRO
+#define MANUFACTURER_ID JHEF
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+
+#define USE_TARGET_CONFIG
+
+#define LED0_PIN PC14
+
+#define USE_BEEPER
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+
+#define ENABLE_DSHOT_DMAR true
+
+#define USE_EXTI
+#define MPU_INT_EXTI PB13
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_GYRO_SPI_MPU6500
+#define USE_GYRO_SPI_ICM42688P
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_ACC_SPI_MPU6500
+#define USE_ACCGYRO_BMI270
+#define USE_ACC_SPI_ICM42688P
+
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define ACC_MPU6000_ALIGN CW180_DEG
+#define MPU6000_CS_PIN PB12
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define GYRO_MPU6500_ALIGN CW180_DEG
+#define ACC_MPU6500_ALIGN CW180_DEG
+#define MPU6500_CS_PIN PB12
+#define MPU6500_SPI_INSTANCE SPI1
+
+#define ACC_ICM42688P_ALIGN CW90_DEG
+#define GYRO_ICM42688P_ALIGN CW90_DEG
+#define ICM42688P_CS_PIN PB12
+#define ICM42688P_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW90_DEG
+#define GYRO_BMI270_ALIGN CW90_DEG
+#define BMI270_CS_PIN PB12
+#define BMI270_SPI_INSTANCE SPI1
+
+#define USE_BARO
+#define USE_BARO_BMP280
+#define USE_BARO_BMP085
+#define USE_BARO_ms5611
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+
+#define USE_MAG
+#define USE_MAG_HMC5883
+#define USE_MAG_QMC5883
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+
+#define USE_MAX7456
+#define MAX7456_SPI_INSTANCE SPI3
+#define MAX7456_SPI_CS_PIN PB14
+
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+#define FLASH_SPI_INSTANCE SPI3
+#define FLASH_CS_PIN PB3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define USE_VCP
+#define USE_USB_DETECT
+#define USB_DETECT_PIN PA8
+
+#define USE_UART1
+#define UART1_RX_PIN PA10
+#define UART1_TX_PIN PB6
+
+#define USE_UART2
+#define UART2_RX_PIN PD6
+#define UART2_TX_PIN PD5
+
+#define USE_UART3
+#define UART3_RX_PIN PB11
+#define UART3_TX_PIN PB10
+
+#define USE_UART4
+#define UART4_RX_PIN PA1
+#define UART4_TX_PIN PA0
+
+#define USE_UART6
+#define UART6_RX_PIN PC7
+#define UART6_TX_PIN PC6
+
+#define SERIAL_PORT_COUNT 6 //USB + 5 UARTS
+
+#define USE_ESCSERIAL //PPM
+#define ESCSERIAL_TIMER_TX_PIN PB8
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C2_SCL PB8
+#define I2C2_SDA PB9
+#define I2C_DEVICE (I2CDEV_1)
+
+#define USE_PINIO
+#define USE_PINIOBOX
+
+#define USE_DASHBOARD
+#define USE_I2C_OLED_DISPLAY
+
+#define USE_ADC
+#define ADC1_DMA_STREAM DMA2_Stream0
+#define VBAT_ADC_PIN PC3
+#define CURRENT_METER_ADC_PIN PC2
+#define RSSI_ADC_PIN PC0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define CURRENT_METER_SCALE_DEFAULT 170
+
+#define SERIALRX_PROVIDER SERIALRX_SBUS
+#define SERIALRX_UART SERIAL_PORT_USART1
+
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+#define DEFAULT_FEATURES ( FEATURE_OSD )
+
+#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 9
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8))
diff --git a/src/main/target/JHEF405PRO/target.mk b/src/main/target/JHEF405PRO/target.mk
index f0e8fa3671..b4a787048c 100644
--- a/src/main/target/JHEF405PRO/target.mk
+++ b/src/main/target/JHEF405PRO/target.mk
@@ -4,12 +4,14 @@ FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_mpu6500.c \
- drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/max7456.c \
- drivers/light_ws2811strip.c
+ drivers/light_ws2811strip.c
diff --git a/src/main/target/JHEF411/target.h b/src/main/target/JHEF411/target.h
index 7db7a91a6d..d8367838a6 100644
--- a/src/main/target/JHEF411/target.h
+++ b/src/main/target/JHEF411/target.h
@@ -22,8 +22,10 @@
#define USE_TARGET_CONFIG
-#define TARGET_BOARD_IDENTIFIER "JHE"
-#define USBD_PRODUCT_STRING "JHEF411"
+#define BOARD_NAME JHEF411
+#define MANUFACTURER_ID JHEF
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
#define LED0_PIN PC13
@@ -41,28 +43,33 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
#define USE_EXTI
#define USE_GYRO_EXTI
-#define MPU_INT_EXTI PB3
+#define USE_SPI_GYRO
+
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define USE_GYRO
-#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
#define USE_ACC
-#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-
#define USE_ACC_SPI_ICM42688P
+#define USE_ACC_SPI_MPU6000
+#define USE_ACCGYRO_BMI270
+#define USE_GYRO
#define USE_GYRO_SPI_ICM42688P
-#define ICM42688P_CS_PIN PA4
-#define ICM42688P_SPI_INSTANCE SPI1
-#define ACC_ICM42688P_ALIGN CW180_DEG
-#define GYRO_ICM42688P_ALIGN CW180_DEG
+#define USE_GYRO_SPI_MPU6000
+
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_EXTI_PIN PB3
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define USE_DUAL_GYRO
+
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_ALIGN CW0_DEG
+#define GYRO_2_SPI_INSTANCE SPI1
+
// *************** Baro **************************
#define USE_I2C
diff --git a/src/main/target/JHEF411/target.mk b/src/main/target/JHEF411/target.mk
index 04a1ea3283..a172452ff2 100644
--- a/src/main/target/JHEF411/target.mk
+++ b/src/main/target/JHEF411/target.mk
@@ -5,6 +5,7 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
diff --git a/src/main/target/LUXF7HDV/target.c b/src/main/target/LUXF7HDV/target.c
new file mode 100644
index 0000000000..7a09465acc
--- /dev/null
+++ b/src/main/target/LUXF7HDV/target.c
@@ -0,0 +1,41 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // led
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/LUXF7HDV/target.h b/src/main/target/LUXF7HDV/target.h
new file mode 100644
index 0000000000..34e473b02e
--- /dev/null
+++ b/src/main/target/LUXF7HDV/target.h
@@ -0,0 +1,116 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#pragma once
+
+#define BOARD_NAME LUXF7HDV
+#define MANUFACTURER_ID LMNR
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+
+#define USE_LED
+#define LED0_PIN PA3
+#define LED_STRIP_PIN PA15
+#define USE_BEEPER
+#define BEEPER_PIN PB2
+#define BEEPER_INVERTED
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_SPI_GYRO
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_MPU6000_ALIGN CW270_DEG
+#define MPU6000_CS_PIN PC4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define USE_UART3
+#define UART3_TX_PIN PC10
+#define UART3_RX_PIN PC11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART5
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 7
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PB12
+#define FLASH_SPI_INSTANCE SPI2
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC0
+#define CURRENT_METER_ADC_PIN PC1
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 179
+
+#define ENABLE_DSHOT_DMAR true
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 6
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/LUXF7HDV/target.mk b/src/main/target/LUXF7HDV/target.mk
new file mode 100644
index 0000000000..9255bdc816
--- /dev/null
+++ b/src/main/target/LUXF7HDV/target.mk
@@ -0,0 +1,11 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 889ce5d
diff --git a/src/main/target/MAMBAF405_2022A/target.c b/src/main/target/MAMBAF405_2022A/target.c
new file mode 100644
index 0000000000..867571ea26
--- /dev/null
+++ b/src/main/target/MAMBAF405_2022A/target.c
@@ -0,0 +1,44 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check; dma 0 assumed, please verify
+ DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0), // led
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/MAMBAF405_2022A/target.h b/src/main/target/MAMBAF405_2022A/target.h
new file mode 100644
index 0000000000..2c8fa68c67
--- /dev/null
+++ b/src/main/target/MAMBAF405_2022A/target.h
@@ -0,0 +1,156 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME MAMBAF405_2022A
+#define MANUFACTURER_ID DIAT
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_ACC_SPI_MPU6500
+#define USE_GYRO_SPI_MPU6500
+#define USE_ACCGYRO_BMI270
+#define USE_BARO
+#define USE_BARO_DSP310
+#define USE_FLASH
+#define USE_FLASH_M25P16
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC15
+#define LED1_PIN PC14
+#define LED_STRIP_PIN PB3
+#define USE_BEEPER
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PB5
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PC4
+
+#define ACC_MPU6000_ALIGN CW180_DEG
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_MPU6500_ALIGN CW180_DEG
+#define GYRO_MPU6500_ALIGN CW180_DEG
+#define MPU6500_CS_PIN PA4
+#define MPU6500_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW180_DEG
+#define GYRO_BMI270_ALIGN CW180_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PB6
+#define UART1_RX_PIN PB7
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART5
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define INVERTER_PIN_UART1 PC0
+#define SERIAL_PORT_COUNT 7
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PA15
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC1
+#define CURRENT_METER_ADC_PIN PC3
+#define ADC3_DMA_OPT 0
+#define ADC3_DMA_STREAM DMA2_Stream0 //# ADC 3: DMA2 Stream 0 Channel 2
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define ADC_INSTANCE ADC3
+
+#define ENABLE_DSHOT_DMAR true
+
+#define PINIO1_PIN PC2
+#define PINIO2_PIN PC5
+#define PINIO1_CONFIG 129
+#define PINIO2_CONFIG 129
+#define PINIO1_BOX 0
+#define PINIO2_BOX 40
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(11) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/MAMBAF405_2022A/target.mk b/src/main/target/MAMBAF405_2022A/target.mk
new file mode 100644
index 0000000000..37428b07b7
--- /dev/null
+++ b/src/main/target/MAMBAF405_2022A/target.mk
@@ -0,0 +1,16 @@
+F405_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_mpu6500.c \
+drivers/accgyro/accgyro_spi_mpu6500.c \
+drivers/accgyro/accgyro_spi_bmi270.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/pinio.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/NBD_INFINITYAIO/target.c b/src/main/target/NBD_INFINITYAIO/target.c
new file mode 100644
index 0000000000..5f2a9e87b3
--- /dev/null
+++ b/src/main/target/NBD_INFINITYAIO/target.c
@@ -0,0 +1,40 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // led
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/NBD_INFINITYAIO/target.h b/src/main/target/NBD_INFINITYAIO/target.h
new file mode 100644
index 0000000000..06c839b143
--- /dev/null
+++ b/src/main/target/NBD_INFINITYAIO/target.h
@@ -0,0 +1,108 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME NBD_INFINITYAIO
+#define MANUFACTURER_ID NEBD
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+
+#define USE_LED
+#define LED0_PIN PA15
+#define LED_STRIP_PIN PA8
+#define USE_BEEPER
+#define BEEPER_PIN PC15
+#define BEEPER_INVERTED
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PC4
+
+#define ACC_MPU6000_ALIGN CW180_DEG
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define MPU6000_CS_PIN PB12
+#define MPU6000_SPI_INSTANCE SPI2
+
+#define USE_UART1
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+#define USE_UART5
+#define UART5_RX_PIN PD2
+#define SERIAL_PORT_COUNT 5
+
+#define FLASH_CS_PIN PA4
+#define FLASH_SPI_INSTANCE SPI1
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC0
+#define CURRENT_METER_ADC_PIN PC1
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 230
+
+#define ENABLE_DSHOT_DMAR true
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 5
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/NBD_INFINITYAIO/target.mk b/src/main/target/NBD_INFINITYAIO/target.mk
new file mode 100644
index 0000000000..307925a4bb
--- /dev/null
+++ b/src/main/target/NBD_INFINITYAIO/target.mk
@@ -0,0 +1,11 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/SKYSTARSF405/target.c b/src/main/target/SKYSTARSF405/target.c
new file mode 100644
index 0000000000..e5382a74d4
--- /dev/null
+++ b/src/main/target/SKYSTARSF405/target.c
@@ -0,0 +1,44 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // led
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), // cam ctrl
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN; dma 0 assumed, please verify
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/SKYSTARSF405/target.h b/src/main/target/SKYSTARSF405/target.h
new file mode 100644
index 0000000000..2dbfc9e807
--- /dev/null
+++ b/src/main/target/SKYSTARSF405/target.h
@@ -0,0 +1,153 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME SKYSTARSF405
+#define MANUFACTURER_ID SKST
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_ACC_SPI_ICM42688P
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACCGYRO_BMI270
+#define USE_BARO_SPI_BMP280
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+#define USE_BARO
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC14
+#define LED1_PIN PC15
+#define LED_STRIP_PIN PC8
+#define USE_BEEPER
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+#define CAMERA_CONTROL_PIN PC9
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PB5
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PC4
+
+#define ACC_MPU6000_ALIGN CW180_DEG_FLIP
+#define GYRO_MPU6000_ALIGN CW180_DEG_FLIP
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_ICM42688P_ALIGN CW180_DEG_FLIP
+#define GYRO_ICM42688P_ALIGN CW180_DEG_FLIP
+#define ICM42688P_CS_PIN PA4
+#define ICM42688P_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW180_DEG_FLIP
+#define GYRO_BMI270_ALIGN CW180_DEG_FLIP
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART5
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define INVERTER_PIN_UART3 PC3
+#define SERIAL_PORT_COUNT 7
+
+#define BARO_CS_PIN PC5
+#define BARO_SPI_INSTANCE SPI2
+#define BMP280_CS_PIN PC5
+#define BMP280_SPI_INSTANCE SPI2
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PA15
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC0
+#define CURRENT_METER_ADC_PIN PC1
+#define RSSI_ADC_PIN PC2
+#define ADC2_DMA_OPT 1
+#define ADC2_DMA_STREAM DMA2_Stream3 //# ADC 2: DMA2 Stream 3 Channel 1
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define ADC_INSTANCE ADC2
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/SKYSTARSF405/target.mk b/src/main/target/SKYSTARSF405/target.mk
new file mode 100644
index 0000000000..c17c00ab23
--- /dev/null
+++ b/src/main/target/SKYSTARSF405/target.mk
@@ -0,0 +1,15 @@
+F405_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_spi_icm426xx.c \
+drivers/accgyro/accgyro_spi_bmi270.c \
+drivers/barometer/barometer_bmp280.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/SPEEDYBEEF7MINI/target.c b/src/main/target/SPEEDYBEEF7MINI/target.c
new file mode 100644
index 0000000000..32ecb42b0d
--- /dev/null
+++ b/src/main/target/SPEEDYBEEF7MINI/target.c
@@ -0,0 +1,48 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 7
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 8
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // led
+ DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN
+ DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // pwm RX_PWM1_PIN; dma 0 assumed, please verify
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // pwm RX_PWM2_PIN
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // cam ctrl
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/SPEEDYBEEF7MINI/target.h b/src/main/target/SPEEDYBEEF7MINI/target.h
new file mode 100644
index 0000000000..6e88c683f0
--- /dev/null
+++ b/src/main/target/SPEEDYBEEF7MINI/target.h
@@ -0,0 +1,135 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 522aa66
+
+#pragma once
+
+#define BOARD_NAME SPEEDYBEEF7MINI
+#define MANUFACTURER_ID SPBE
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PA14
+#define LED_STRIP_PIN PC8
+#define USE_BEEPER
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+#define CAMERA_CONTROL_PIN PA0
+#define USE_USB_DETECT
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PC4
+
+#define ACC_MPU6000_ALIGN CW0_DEG
+#define GYRO_MPU6000_ALIGN CW0_DEG
+#define MPU6000_CS_PIN PB2
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART3
+#define UART3_TX_PIN PB10
+#define UART3_RX_PIN PB11
+#define USE_UART4
+#define UART4_RX_PIN PA1
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 6
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PD2
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC2
+#define CURRENT_METER_ADC_PIN PC1
+#define RSSI_ADC_PIN PC0
+#define ADC1_DMA_OPT 0
+#define ADC1_DMA_STREAM DMA2_Stream0 //# ADC 1: DMA2 Stream 0 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 250
+
+#define ENABLE_DSHOT_DMAR true
+
+#define PINIO1_PIN PC9
+#define PINIO1_CONFIG 129
+#define PINIO1_BOX 0
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 13
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/SPEEDYBEEF7MINI/target.mk b/src/main/target/SPEEDYBEEF7MINI/target.mk
new file mode 100644
index 0000000000..de71ac0a2e
--- /dev/null
+++ b/src/main/target/SPEEDYBEEF7MINI/target.mk
@@ -0,0 +1,13 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/pinio.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 522aa66
diff --git a/src/main/target/TMOTORF411/target.c b/src/main/target/TMOTORF411/target.c
new file mode 100644
index 0000000000..d3678d4a29
--- /dev/null
+++ b/src/main/target/TMOTORF411/target.c
@@ -0,0 +1,41 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // led
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/TMOTORF411/target.h b/src/main/target/TMOTORF411/target.h
new file mode 100644
index 0000000000..51d5ad61c9
--- /dev/null
+++ b/src/main/target/TMOTORF411/target.h
@@ -0,0 +1,122 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#pragma once
+
+#define BOARD_NAME TMOTORF411
+#define MANUFACTURER_ID TMTR
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
+
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_ACCGYRO_BMI270
+#define USE_FLASH
+#define USE_FLASH_M25P16
+#define USE_MAX7456
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC13
+#define LED_STRIP_PIN PA8
+#define USE_BEEPER
+#define BEEPER_PIN PB2
+#define BEEPER_INVERTED
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define MPU_INT_EXTI PC15
+
+#define ACC_MPU6000_ALIGN CW180_DEG_FLIP
+#define GYRO_MPU6000_ALIGN CW180_DEG_FLIP
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW180_DEG_FLIP
+#define GYRO_BMI270_ALIGN CW180_DEG_FLIP
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define SERIAL_PORT_COUNT 3
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PA15
+#define FLASH_SPI_INSTANCE SPI3
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PB12
+#define MAX7456_SPI_INSTANCE SPI2
+
+#define USE_ADC
+#define VBAT_ADC_PIN PA1
+#define CURRENT_METER_ADC_PIN PA0
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 250
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 6
+#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/TMOTORF411/target.mk b/src/main/target/TMOTORF411/target.mk
new file mode 100644
index 0000000000..0060aa8457
--- /dev/null
+++ b/src/main/target/TMOTORF411/target.mk
@@ -0,0 +1,12 @@
+F411_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_spi_bmi270.c \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 889ce5d
diff --git a/src/main/target/TMOTORF7V2/target.h b/src/main/target/TMOTORF7V2/target.h
index 4b1a404184..a55dfbeaed 100644
--- a/src/main/target/TMOTORF7V2/target.h
+++ b/src/main/target/TMOTORF7V2/target.h
@@ -23,9 +23,10 @@
#define USE_TARGET_CONFIG
-#define TARGET_BOARD_IDENTIFIER "TMR7"
-#define USBD_PRODUCT_STRING "TMOTORF7V2"
-#define TARGET_MANUFACTURER_IDENTIFIER "TMTR"
+#define BOARD_NAME TMOTORF7V2
+#define MANUFACTURER_ID TMTR
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define LED0_PIN PC14
@@ -37,20 +38,42 @@
#define ENABLE_DSHOT_DMAR true
+#define USE_SPI_GYRO
#define USE_EXTI
+#define USE_GYRO_EXTI
+
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
-#define USE_GYRO
-#define USE_GYRO_SPI_MPU6000
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-#define GYRO_1_ALIGN CW0_DEG
-
#define USE_ACC
+#define USE_ACC_SPI_ICM42688P
#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6000_ALIGN CW0_DEG
+#define USE_ACCGYRO_BMI270
+#define USE_GYRO
+#define USE_GYRO_SPI_ICM42688P
+#define USE_GYRO_SPI_MPU6000
+#define USE_GYRO_SPI_MPU6500
+
+#define ACC_MPU6000_ALIGN CW0_DEG
+#define GYRO_MPU6000_ALIGN CW0_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_MPU6500_ALIGN CW0_DEG
+#define GYRO_MPU6500_ALIGN CW0_DEG
+#define MPU6500_CS_PIN PA4
+#define MPU6500_SPI_INSTANCE SPI1
+
+#define ACC_ICM42688P_ALIGN CW0_DEG
+#define GYRO_ICM42688P_ALIGN CW0_DEG
+#define ICM42688P_CS_PIN PA4
+#define ICM42688P_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW0_DEG
+#define GYRO_BMI270_ALIGN CW0_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
#define USE_BARO
#define USE_BARO_BMP280
diff --git a/src/main/target/TMOTORF7V2/target.mk b/src/main/target/TMOTORF7V2/target.mk
index 1ad2e0fd8e..ee497211af 100644
--- a/src/main/target/TMOTORF7V2/target.mk
+++ b/src/main/target/TMOTORF7V2/target.mk
@@ -1,11 +1,13 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_mpu6500.c \
- drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_spi_mpu6500.c \
- drivers/barometer/barometer_bmp280.c \
- drivers/compass/compass_hmc5883l.c \
- drivers/compass/compass_qmc5883l.c \
- drivers/max7456.c\
- drivers/light_ws2811strip.c \
+ drivers/accgyro/accgyro_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
+ drivers/barometer/barometer_bmp280.c \
+ drivers/compass/compass_hmc5883l.c \
+ drivers/compass/compass_qmc5883l.c \
+ drivers/max7456.c\
+ drivers/light_ws2811strip.c \
diff --git a/src/main/target/VGOODF722DUAL/target.c b/src/main/target/VGOODF722DUAL/target.c
new file mode 100644
index 0000000000..2d4b6bfeb8
--- /dev/null
+++ b/src/main/target/VGOODF722DUAL/target.c
@@ -0,0 +1,44 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // led
+ DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // ppm RX_PPM_PIN; dma 0 assumed, please verify
+ DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // pwm RX_PWM1_PIN; dma 0 assumed, please verify
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/VGOODF722DUAL/target.h b/src/main/target/VGOODF722DUAL/target.h
new file mode 100644
index 0000000000..02cb2f8bc8
--- /dev/null
+++ b/src/main/target/VGOODF722DUAL/target.h
@@ -0,0 +1,143 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is 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.
+ * This software 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 this software.
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: 889ce5d
+
+#pragma once
+
+#define BOARD_NAME VGOODF722DUAL
+#define MANUFACTURER_ID VGRC
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_BARO
+#define USE_BARO_BMP280
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 driver; drives all unless QSPI
+
+#define USE_LED
+#define LED0_PIN PA13
+#define LED1_PIN PA14
+#define LED_STRIP_PIN PA8
+#define USE_BEEPER
+#define BEEPER_PIN PC13
+#define BEEPER_INVERTED
+#define USE_USB_DETECT
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+
+#define USE_SPI_GYRO
+#define USE_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
+#define GYRO_1_CS_PIN PA15
+#define GYRO_1_EXTI_PIN PC3
+#define GYRO_1_SPI_INSTANCE SPI3
+
+#define USE_DUAL_GYRO
+
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_ALIGN CW0_DEG
+#define GYRO_2_CS_PIN PD2
+#define GYRO_2_EXTI_PIN PC4
+#define GYRO_2_SPI_INSTANCE SPI3
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+#define USE_UART2
+#define UART2_TX_PIN PA2
+#define UART2_RX_PIN PA3
+#define USE_UART4
+#define UART4_TX_PIN PA0
+#define UART4_RX_PIN PA1
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+#define SERIAL_PORT_COUNT 5
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE_1 (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+#define USE_I2C_DEVICE_2
+#define I2C_DEVICE_2 (I2CDEV_2)
+#define MAG_I2C_INSTANCE (I2CDEV_2)
+#define I2C2_SCL PB10
+#define I2C2_SDA PB11
+
+#define FLASH_CS_PIN PB12
+#define FLASH_SPI_INSTANCE SPI2
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define USE_ADC
+#define VBAT_ADC_PIN PC0
+#define CURRENT_METER_ADC_PIN PC1
+#define RSSI_ADC_PIN PC2
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 179
+
+#define ENABLE_DSHOT_DMAR true
+
+#define PINIO1_PIN PC8
+#define PINIO2_PIN PC9
+#define PINIO1_BOX 40
+#define PINIO2_BOX 41
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(9) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/VGOODF722DUAL/target.mk b/src/main/target/VGOODF722DUAL/target.mk
new file mode 100644
index 0000000000..2916fa9d11
--- /dev/null
+++ b/src/main/target/VGOODF722DUAL/target.mk
@@ -0,0 +1,14 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/barometer/barometer_bmp280.c \
+$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/pinio.c \
+drivers/max7456.c \
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: 889ce5d
diff --git a/src/main/target/XILOF4/target.h b/src/main/target/XILOF4/target.h
index 285799be2e..5ebdcd5ac0 100644
--- a/src/main/target/XILOF4/target.h
+++ b/src/main/target/XILOF4/target.h
@@ -22,8 +22,10 @@
//#define USE_TARGET_CONFIG
-#define TARGET_BOARD_IDENTIFIER "XILO"
-#define USBD_PRODUCT_STRING "XiloF4"
+#define BOARD_NAME XILOF4
+#define MANUFACTURER_ID GEFP
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
#define LED0_PIN PC15
#define USE_BEEPER
@@ -40,19 +42,32 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_ACC_SPI_MPU6500
+#define USE_ACCGYRO_BMI270
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_MPU6500
-#define MPU6000_CS_PIN SPI1_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI1
-#define MPU6500_SPI_INSTANCE SPI1
-#define GYRO_MPU6000_ALIGN CW180_DEG
-//#define MPU_INT_EXTI NONE
-//#define GYRO_1_EXTI_PIN NONE
-#define USE_ACC
-#define USE_ACC_SPI_MPU6000
-#define USE_ACC_SPI_MPU6500
+#define USE_SPI_GYRO
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_MPU6000_ALIGN CW180_DEG
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define MPU6000_CS_PIN PC4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_MPU6500_ALIGN CW180_DEG
+#define GYRO_MPU6500_ALIGN CW180_DEG
+#define MPU6500_CS_PIN PC4
+#define MPU6500_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW180_DEG
+#define GYRO_BMI270_ALIGN CW180_DEG
+#define BMI270_CS_PIN PC4
+#define BMI270_SPI_INSTANCE SPI1
+
// *************** Flash **************************
#define USE_SPI_DEVICE_2
diff --git a/src/main/target/XILOF4/target.mk b/src/main/target/XILOF4/target.mk
index 8d72d0600b..7d202b2706 100644
--- a/src/main/target/XILOF4/target.mk
+++ b/src/main/target/XILOF4/target.mk
@@ -6,4 +6,5 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/max7456.c
diff --git a/src/main/target/ZEEZ_ZEEZF7V2/target.c b/src/main/target/ZEEZF7V2/target.c
similarity index 100%
rename from src/main/target/ZEEZ_ZEEZF7V2/target.c
rename to src/main/target/ZEEZF7V2/target.c
diff --git a/src/main/target/ZEEZ_ZEEZF7V2/target.h b/src/main/target/ZEEZF7V2/target.h
similarity index 100%
rename from src/main/target/ZEEZ_ZEEZF7V2/target.h
rename to src/main/target/ZEEZF7V2/target.h
diff --git a/src/main/target/ZEEZ_ZEEZF7V2/target.mk b/src/main/target/ZEEZF7V2/target.mk
similarity index 100%
rename from src/main/target/ZEEZ_ZEEZF7V2/target.mk
rename to src/main/target/ZEEZF7V2/target.mk
diff --git a/src/main/target/ZEUSF4EVO/target.h b/src/main/target/ZEUSF4EVO/target.h
index 317e7ce5ac..e4418dfdd2 100644
--- a/src/main/target/ZEUSF4EVO/target.h
+++ b/src/main/target/ZEUSF4EVO/target.h
@@ -19,9 +19,11 @@
*/
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S411"
-#define USBD_PRODUCT_STRING "ZEUSF4EVO"
-#define TARGET_MANUFACTURER_IDENTIFIER "HGLR"
+
+#define BOARD_NAME ZEUSF4EVO
+#define MANUFACTURER_ID HGLR
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
#define ENABLE_DSHOT_DMAR true
@@ -34,19 +36,29 @@
//define camera control
//#define CAMERA_CONTROL_PIN PB10
-//MPU-6000
#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define USE_GYRO_SPI_MPU6000
+#define USE_ACCGYRO_BMI270
+
+#define USE_SPI_GYRO
#define USE_EXTI
+#define USE_GYRO_EXTI
+
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PA1 //MPU_INT_EXTI
-#define MPU6000_CS_PIN PA4 //GYRO_1_CS_PIN
-#define MPU6000_SPI_INSTANCE SPI1 //GYRO_1_SPI_INSTANCE
-#define GYRO_MPU6000_ALIGN CW180_DEG
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define MPU_INT_EXTI PA1
+
+#define ACC_MPU6000_ALIGN CW180_DEG
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW180_DEG
+#define GYRO_BMI270_ALIGN CW180_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
// OSD
#define USE_MAX7456
@@ -124,6 +136,8 @@
#define USE_LED_STRIP
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
//#define SERIALRX_UART SERIAL_PORT_USART2
diff --git a/src/main/target/ZEUSF4EVO/target.mk b/src/main/target/ZEUSF4EVO/target.mk
index 5677bee39e..4e4ef6defc 100644
--- a/src/main/target/ZEUSF4EVO/target.mk
+++ b/src/main/target/ZEUSF4EVO/target.mk
@@ -2,12 +2,13 @@ F411_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
- drivers/compass/compass_hmc5883l.c \
- drivers/compass/compass_qmc5883l.c\
- drivers/light_ws2811strip.c\
+ drivers/compass/compass_hmc5883l.c \
+ drivers/compass/compass_qmc5883l.c\
+ drivers/light_ws2811strip.c\
drivers/max7456.c
diff --git a/src/main/target/ZEUSF4FR/target.h b/src/main/target/ZEUSF4FR/target.h
index 2c2cd5ef58..c90692692f 100644
--- a/src/main/target/ZEUSF4FR/target.h
+++ b/src/main/target/ZEUSF4FR/target.h
@@ -20,9 +20,10 @@
#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "HGLR"
-#define USBD_PRODUCT_STRING "ZEUSF4FR"
+#define BOARD_NAME ZEUSF4FR
+#define MANUFACTURER_ID HGLR
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
#define LED0_PIN PC13
@@ -38,27 +39,28 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define MPU6000_CS_PIN PA4
-//#define ICM20689_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-//#define ICM20689_SPI_INSTANCE SPI1
-
#define USE_EXTI
#define USE_GYRO_EXTI
-#define MPU_INT_EXTI PA1
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define USE_GYRO
-#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
-//#define USE_GYRO_SPI_ICM20689
-//#define ACC_ICM20689_ALIGN CW180_DEG
+#define MPU_INT_EXTI PA1
+
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-//#define USE_ACC_SPI_ICM20689
-//#define ACC_ICM20689_ALIGN CW180_DEG
+#define USE_ACCGYRO_BMI270
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+
+#define ACC_MPU6000_ALIGN CW180_DEG
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_BMI270_ALIGN CW180_DEG
+#define GYRO_BMI270_ALIGN CW180_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
// *************** Baro **************************
//#define USE_I2C
diff --git a/src/main/target/ZEUSF4FR/target.mk b/src/main/target/ZEUSF4FR/target.mk
index df43c583c6..932e0aed7a 100644
--- a/src/main/target/ZEUSF4FR/target.mk
+++ b/src/main/target/ZEUSF4FR/target.mk
@@ -3,17 +3,18 @@ F411_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp280.c \
drivers/max7456.c \
drivers/rx/rx_cc2500.c \
- rx/cc2500_common.c \
+ rx/cc2500_common.c \
rx/cc2500_frsky_shared.c \
rx/cc2500_frsky_d.c \
- rx/cc2500_frsky_x.c \
- rx/cc2500_redpine.c \
+ rx/cc2500_frsky_x.c \
+ rx/cc2500_redpine.c \
rx/cc2500_sfhss.c \
drivers/rx/rx_a7105.c \
- drivers/light_ws2811strip.c
+ drivers/light_ws2811strip.c
diff --git a/src/main/target/ZEUSF722_AIO/target.h b/src/main/target/ZEUSF722_AIO/target.h
index e447ffaf41..3952f620ca 100644
--- a/src/main/target/ZEUSF722_AIO/target.h
+++ b/src/main/target/ZEUSF722_AIO/target.h
@@ -22,8 +22,10 @@
#define USE_TARGET_CONFIG
-#define TARGET_BOARD_IDENTIFIER "S7X2"
-#define USBD_PRODUCT_STRING "ZEUSF722_AIO"
+#define BOARD_NAME ZEUSF722_AIO
+#define MANUFACTURER_ID HGLR
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
#define ENABLE_DSHOT_DMAR true
@@ -43,22 +45,30 @@
#define SPI1_MOSI_PIN PA7
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_SPI_GYRO
+#define USE_GYRO_EXTI
-#define MPU6000_CS_PIN PB2
-#define MPU6000_SPI_INSTANCE SPI1
+#define USE_MPU_DATA_READY_SIGNAL
+#define ENSURE_MPU_DATA_READY_IS_LOW
+
+#define MPU_INT_EXTI PC4
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_ACC
#define USE_ACC_SPI_MPU6000
+#define USE_ACCGYRO_BMI270
-#define GYRO_MPU6000_ALIGN CW180_DEG
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_MPU6000_ALIGN CW180_DEG
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define MPU6000_CS_PIN PB2
+#define MPU6000_SPI_INSTANCE SPI1
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
+#define ACC_BMI270_ALIGN CW180_DEG
+#define GYRO_BMI270_ALIGN CW180_DEG
+#define BMI270_CS_PIN PB2
+#define BMI270_SPI_INSTANCE SPI1
// *************** I2C /Baro/Mag *********************
diff --git a/src/main/target/ZEUSF722_AIO/target.mk b/src/main/target/ZEUSF722_AIO/target.mk
index 5e915bb8bc..56c919b48b 100644
--- a/src/main/target/ZEUSF722_AIO/target.mk
+++ b/src/main/target/ZEUSF722_AIO/target.mk
@@ -2,14 +2,13 @@ F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_spi_mpu6500.c \
- drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
- drivers/light_ws2811strip.c \
- drivers/light_ws2811strip_hal.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_hal.c \
drivers/max7456.c