diff --git a/src/main/drivers/accgyro/accgyro.h b/src/main/drivers/accgyro/accgyro.h
index aa2d53b9ff..636dd05c80 100644
--- a/src/main/drivers/accgyro/accgyro.h
+++ b/src/main/drivers/accgyro/accgyro.h
@@ -35,10 +35,6 @@
#pragma GCC diagnostic warning "-Wpadded"
#endif
-#ifndef MPU_I2C_INSTANCE
-#define MPU_I2C_INSTANCE I2C_DEVICE
-#endif
-
typedef enum {
GYRO_NONE = 0,
GYRO_DEFAULT,
diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c
index 2c3132a245..66ec254b86 100644
--- a/src/main/drivers/accgyro/accgyro_mpu.c
+++ b/src/main/drivers/accgyro/accgyro_mpu.c
@@ -54,9 +54,8 @@
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
#include "drivers/accgyro/accgyro_mpu.h"
-#ifndef MPU_I2C_INSTANCE
-#define MPU_I2C_INSTANCE I2C_DEVICE
-#endif
+#include "pg/pg.h"
+#include "pg/gyrodev.h"
#ifndef MPU_ADDRESS
#define MPU_ADDRESS 0x68
@@ -64,7 +63,7 @@
#define MPU_INQUIRY_MASK 0x7E
-#ifdef USE_I2C
+#ifdef USE_I2C_GYRO
static void mpu6050FindRevision(gyroDev_t *gyro)
{
// There is a map of revision contained in the android source tree which is quite comprehensive and may help to understand this code
@@ -103,7 +102,7 @@ static void mpu6050FindRevision(gyroDev_t *gyro)
/*
* Gyro interrupt service routine
*/
-#if defined(MPU_INT_EXTI)
+#ifdef USE_GYRO_EXTI
static void mpuIntExtiHandler(extiCallbackRec_t *cb)
{
#ifdef DEBUG_MPU_DATA_READY_INTERRUPT
@@ -136,11 +135,11 @@ static void mpuIntExtiInit(gyroDev_t *gyro)
#endif
#if defined (STM32F7)
- IOInit(mpuIntIO, OWNER_MPU_EXTI, 0);
+ IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ?
#else
- IOInit(mpuIntIO, OWNER_MPU_EXTI, 0);
+ IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler);
@@ -182,6 +181,7 @@ bool mpuGyroRead(gyroDev_t *gyro)
return true;
}
+#ifdef USE_SPI_GYRO
bool mpuGyroReadSPI(gyroDev_t *gyro)
{
static const uint8_t dataToSend[7] = {MPU_RA_GYRO_XOUT_H | 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
@@ -199,120 +199,78 @@ bool mpuGyroReadSPI(gyroDev_t *gyro)
return true;
}
-#ifdef USE_SPI
-static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
+typedef uint8_t (*gyroSpiDetectFn_t)(const busDevice_t *bus);
+
+static gyroSpiDetectFn_t gyroSpiDetectFnTable[] = {
+#ifdef USE_GYRO_SPI_MPU6000
+ mpu6000SpiDetect,
+#endif
+#ifdef USE_GYRO_SPI_MPU6500
+ mpu6500SpiDetect, // some targets using MPU_9250_SPI, ICM_20608_SPI or ICM_20602_SPI state sensor is MPU_65xx_SPI
+#endif
+#ifdef USE_GYRO_SPI_MPU9250
+ mpu9250SpiDetect,
+#endif
+#ifdef USE_GYRO_SPI_ICM20649
+ icm20649SpiDetect,
+#endif
+#ifdef USE_GYRO_SPI_ICM20689
+ icm20689SpiDetect, // icm20689SpiDetect detects ICM20602 and ICM20689
+#endif
+#ifdef USE_ACCGYRO_BMI160
+ bmi160Detect,
+#endif
+ NULL // Avoid an empty array
+};
+
+static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
{
- UNUSED(gyro); // since there are FCs which have gyro on I2C but other devices on SPI
+ gyro->bus.bustype = BUSTYPE_SPI;
+
+ spiBusSetInstance(&gyro->bus, spiInstanceByDevice(SPI_CFG_TO_DEV(config->spiBus)));
+ gyro->bus.busdev_u.spi.csnPin = IOGetByTag(config->csnTag);
+ IOInit(gyro->bus.busdev_u.spi.csnPin, OWNER_GYRO_CS, RESOURCE_INDEX(config->index));
+ IOConfigGPIO(gyro->bus.busdev_u.spi.csnPin, SPI_IO_CS_CFG);
+ IOHi(gyro->bus.busdev_u.spi.csnPin); // Ensure device is disabled, important when two devices are on the same bus.
uint8_t sensor = MPU_NONE;
- UNUSED(sensor);
- // note, when USE_DUAL_GYRO is enabled the gyro->bus must already be initialised.
+ // It is hard to use hardware to optimize the detection loop here,
+ // as hardware type and detection function name doesn't match.
+ // May need a bitmap of hardware to detection function to do it right?
-#ifdef USE_GYRO_SPI_MPU6000
-#ifndef USE_DUAL_GYRO
- spiBusSetInstance(&gyro->bus, MPU6000_SPI_INSTANCE);
-#endif
-#ifdef MPU6000_CS_PIN
- gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU6000_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
-#endif
- sensor = mpu6000SpiDetect(&gyro->bus);
- if (sensor != MPU_NONE) {
- gyro->mpuDetectionResult.sensor = sensor;
- return true;
+ for (size_t index = 0 ; gyroSpiDetectFnTable[index] ; index++) {
+ sensor = (gyroSpiDetectFnTable[index])(&gyro->bus);
+ if (sensor != MPU_NONE) {
+ gyro->mpuDetectionResult.sensor = sensor;
+ return true;
+ }
}
-#endif
-#ifdef USE_GYRO_SPI_MPU6500
-#ifndef USE_DUAL_GYRO
- spiBusSetInstance(&gyro->bus, MPU6500_SPI_INSTANCE);
-#endif
-#ifdef MPU6500_CS_PIN
- gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU6500_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
-#endif
- sensor = mpu6500SpiDetect(&gyro->bus);
- // some targets using MPU_9250_SPI, ICM_20608_SPI or ICM_20602_SPI state sensor is MPU_65xx_SPI
- if (sensor != MPU_NONE) {
- gyro->mpuDetectionResult.sensor = sensor;
- return true;
- }
-#endif
-
-#ifdef USE_GYRO_SPI_MPU9250
-#ifndef USE_DUAL_GYRO
- spiBusSetInstance(&gyro->bus, MPU9250_SPI_INSTANCE);
-#endif
-#ifdef MPU9250_CS_PIN
- gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU9250_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
-#endif
- sensor = mpu9250SpiDetect(&gyro->bus);
- if (sensor != MPU_NONE) {
- gyro->mpuDetectionResult.sensor = sensor;
- return true;
- }
-#endif
-
-#ifdef USE_GYRO_SPI_ICM20649
-#ifdef ICM20649_SPI_INSTANCE
- spiBusSetInstance(&gyro->bus, ICM20649_SPI_INSTANCE);
-#endif
-#ifdef ICM20649_CS_PIN
- gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(ICM20649_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
-#endif
- sensor = icm20649SpiDetect(&gyro->bus);
- if (sensor != MPU_NONE) {
- gyro->mpuDetectionResult.sensor = sensor;
- return true;
- }
-#endif
-
-#ifdef USE_GYRO_SPI_ICM20689
-#ifndef USE_DUAL_GYRO
- spiBusSetInstance(&gyro->bus, ICM20689_SPI_INSTANCE);
-#endif
-#ifdef ICM20689_CS_PIN
- gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(ICM20689_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
-#endif
- sensor = icm20689SpiDetect(&gyro->bus);
- // icm20689SpiDetect detects ICM20602 and ICM20689
- if (sensor != MPU_NONE) {
- gyro->mpuDetectionResult.sensor = sensor;
- return true;
- }
-#endif
-
-#ifdef USE_ACCGYRO_BMI160
-#ifndef USE_DUAL_GYRO
- spiBusSetInstance(&gyro->bus, BMI160_SPI_INSTANCE);
-#endif
-#ifdef BMI160_CS_PIN
- gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(BMI160_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
-#endif
- sensor = bmi160Detect(&gyro->bus);
- if (sensor != MPU_NONE) {
- gyro->mpuDetectionResult.sensor = sensor;
- return true;
- }
-#endif
+ spiPreinitCsByTag(config->csnTag);
return false;
}
#endif
-void mpuDetect(gyroDev_t *gyro)
+void mpuDetect(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
{
// MPU datasheet specifies 30ms.
delay(35);
-#ifdef USE_I2C
- if (gyro->bus.bustype == BUSTYPE_NONE) {
- // if no bustype is selected try I2C first.
- gyro->bus.bustype = BUSTYPE_I2C;
+ if (config->bustype == BUSTYPE_NONE) {
+ return;
}
+ if (config->bustype == BUSTYPE_GYRO_AUTO) {
+ gyro->bus.bustype = BUSTYPE_I2C;
+ } else {
+ gyro->bus.bustype = config->bustype;
+ }
+
+#ifdef USE_I2C_GYRO
if (gyro->bus.bustype == BUSTYPE_I2C) {
- gyro->bus.busdev_u.i2c.device = MPU_I2C_INSTANCE;
- gyro->bus.busdev_u.i2c.address = MPU_ADDRESS;
+ gyro->bus.busdev_u.i2c.address = config->i2cAddress ? config->i2cAddress : MPU_ADDRESS;
uint8_t sig = 0;
bool ack = busReadRegisterBuffer(&gyro->bus, MPU_RA_WHO_AM_I, &sig, 1);
@@ -339,15 +297,15 @@ void mpuDetect(gyroDev_t *gyro)
}
#endif
-#ifdef USE_SPI
+#ifdef USE_SPI_GYRO
gyro->bus.bustype = BUSTYPE_SPI;
- detectSPISensorsAndUpdateDetectionResult(gyro);
+ detectSPISensorsAndUpdateDetectionResult(gyro, config);
#endif
}
void mpuGyroInit(gyroDev_t *gyro)
{
-#ifdef MPU_INT_EXTI
+#ifdef USE_GYRO_EXTI
mpuIntExtiInit(gyro);
#else
UNUSED(gyro);
diff --git a/src/main/drivers/accgyro/accgyro_mpu.h b/src/main/drivers/accgyro/accgyro_mpu.h
index 44912b1676..845401f6de 100644
--- a/src/main/drivers/accgyro/accgyro_mpu.h
+++ b/src/main/drivers/accgyro/accgyro_mpu.h
@@ -218,10 +218,11 @@ typedef struct mpuDetectionResult_s {
} mpuDetectionResult_t;
struct gyroDev_s;
+struct gyroDeviceConfig_s;
void mpuGyroInit(struct gyroDev_s *gyro);
bool mpuGyroRead(struct gyroDev_s *gyro);
bool mpuGyroReadSPI(struct gyroDev_s *gyro);
-void mpuDetect(struct gyroDev_s *gyro);
+void mpuDetect(struct gyroDev_s *gyro, const struct gyroDeviceConfig_s *config);
uint8_t mpuGyroDLPF(struct gyroDev_s *gyro);
uint8_t mpuGyroFCHOICE(struct gyroDev_s *gyro);
uint8_t mpuGyroReadRegister(const busDevice_t *bus, uint8_t reg);
diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi160.c b/src/main/drivers/accgyro/accgyro_spi_bmi160.c
index 643cfad57f..ac0af59796 100644
--- a/src/main/drivers/accgyro/accgyro_spi_bmi160.c
+++ b/src/main/drivers/accgyro/accgyro_spi_bmi160.c
@@ -97,11 +97,6 @@ uint8_t bmi160Detect(const busDevice_t *bus)
return BMI_160_SPI;
}
-#ifndef USE_DUAL_GYRO
- IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
- IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
- IOHi(bus->busdev_u.spi.csnPin);
-#endif
spiSetDivisor(bus->busdev_u.spi.instance, BMI160_SPI_DIVISOR);
@@ -250,22 +245,18 @@ void bmi160ExtiHandler(extiCallbackRec_t *cb)
static void bmi160IntExtiInit(gyroDev_t *gyro)
{
- static bool bmi160ExtiInitDone = false;
-
- if (bmi160ExtiInitDone) {
+ if (gyro->mpuIntExtiTag == IO_TAG_NONE) {
return;
}
- IO_t mpuIntIO = IOGetByTag(IO_TAG(BMI160_INT_EXTI));
+ IO_t mpuIntIO = IOGetByTag(gyro->mpuIntExtiTag);
- IOInit(mpuIntIO, OWNER_MPU_EXTI, 0);
+ IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
EXTIHandlerInit(&gyro->exti, bmi160ExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(mpuIntIO, true);
-
- bmi160ExtiInitDone = true;
}
diff --git a/src/main/drivers/accgyro/accgyro_spi_icm20649.c b/src/main/drivers/accgyro/accgyro_spi_icm20649.c
index 802e492342..6a809840f3 100644
--- a/src/main/drivers/accgyro/accgyro_spi_icm20649.c
+++ b/src/main/drivers/accgyro/accgyro_spi_icm20649.c
@@ -45,11 +45,6 @@ static void icm20649SpiInit(const busDevice_t *bus)
return;
}
-#ifndef USE_DUAL_GYRO
- IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
- IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
- IOHi(bus->busdev_u.spi.csnPin);
-#endif
// all registers can be read/written at full speed (7MHz +-10%)
// TODO verify that this works at 9MHz and 10MHz on non F7
diff --git a/src/main/drivers/accgyro/accgyro_spi_icm20689.c b/src/main/drivers/accgyro/accgyro_spi_icm20689.c
index af1407bf19..22b8a1bfbb 100644
--- a/src/main/drivers/accgyro/accgyro_spi_icm20689.c
+++ b/src/main/drivers/accgyro/accgyro_spi_icm20689.c
@@ -45,11 +45,6 @@ static void icm20689SpiInit(const busDevice_t *bus)
return;
}
-#ifndef USE_DUAL_GYRO
- IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
- IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
- IOHi(bus->busdev_u.spi.csnPin);
-#endif
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_STANDARD);
diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro/accgyro_spi_mpu6000.c
index 6ca1a114a5..4dae96384c 100644
--- a/src/main/drivers/accgyro/accgyro_spi_mpu6000.c
+++ b/src/main/drivers/accgyro/accgyro_spi_mpu6000.c
@@ -127,11 +127,6 @@ void mpu6000SpiAccInit(accDev_t *acc)
uint8_t mpu6000SpiDetect(const busDevice_t *bus)
{
-#ifndef USE_DUAL_GYRO
- IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
- IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
- IOHi(bus->busdev_u.spi.csnPin);
-#endif
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON);
diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro/accgyro_spi_mpu6500.c
index 808ec6d789..25e84822d4 100644
--- a/src/main/drivers/accgyro/accgyro_spi_mpu6500.c
+++ b/src/main/drivers/accgyro/accgyro_spi_mpu6500.c
@@ -41,11 +41,6 @@
static void mpu6500SpiInit(const busDevice_t *bus)
{
-#ifndef USE_DUAL_GYRO
- IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
- IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
- IOHi(bus->busdev_u.spi.csnPin);
-#endif
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_FAST);
}
diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro/accgyro_spi_mpu9250.c
index 3788f6c6a4..da3e6ce984 100644
--- a/src/main/drivers/accgyro/accgyro_spi_mpu9250.c
+++ b/src/main/drivers/accgyro/accgyro_spi_mpu9250.c
@@ -151,11 +151,6 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro) {
uint8_t mpu9250SpiDetect(const busDevice_t *bus)
{
-#ifndef USE_DUAL_GYRO
- IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
- IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
- IOHi(bus->busdev_u.spi.csnPin);
-#endif
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON); //low speed
mpu9250SpiWriteRegister(bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
diff --git a/src/main/drivers/accgyro_legacy/accgyro_l3gd20.c b/src/main/drivers/accgyro_legacy/accgyro_l3gd20.c
index d78944cb33..b1ea9b168d 100644
--- a/src/main/drivers/accgyro_legacy/accgyro_l3gd20.c
+++ b/src/main/drivers/accgyro_legacy/accgyro_l3gd20.c
@@ -82,12 +82,6 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx)
UNUSED(SPIx); // FIXME
mpul3gd20CsPin = IOGetByTag(IO_TAG(L3GD20_CS_PIN));
-#ifndef USE_DUAL_GYRO
- IOInit(mpul3gd20CsPin, OWNER_MPU_CS, 0);
- IOConfigGPIO(mpul3gd20CsPin, SPI_IO_CS_CFG);
-
- DISABLE_L3GD20;
-#endif
spiSetDivisor(L3GD20_SPI, SPI_CLOCK_STANDARD);
}
diff --git a/src/main/drivers/accgyro_legacy/accgyro_mma845x.c b/src/main/drivers/accgyro_legacy/accgyro_mma845x.c
index 25c869b6c6..69419bba93 100644
--- a/src/main/drivers/accgyro_legacy/accgyro_mma845x.c
+++ b/src/main/drivers/accgyro_legacy/accgyro_mma845x.c
@@ -86,7 +86,7 @@ static uint8_t device_id;
static inline void mma8451ConfigureInterrupt(void)
{
#ifdef MMA8451_INT_PIN
- IOInit(IOGetByTag(IO_TAG(MMA8451_INT_PIN)), OWNER_MPU_EXTI, 0);
+ IOInit(IOGetByTag(IO_TAG(MMA8451_INT_PIN)), OWNER_GYRO_EXTI, 0);
// TODO - maybe pullup / pulldown ?
IOConfigGPIO(IOGetByTag(IO_TAG(MMA8451_INT_PIN)), IOCFG_IN_FLOATING);
#endif
diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h
index cd2195959e..1dad078006 100644
--- a/src/main/drivers/bus.h
+++ b/src/main/drivers/bus.h
@@ -29,7 +29,8 @@ typedef enum {
BUSTYPE_NONE = 0,
BUSTYPE_I2C,
BUSTYPE_SPI,
- BUSTYPE_MPU_SLAVE // Slave I2C on SPI master
+ BUSTYPE_MPU_SLAVE, // Slave I2C on SPI master
+ BUSTYPE_GYRO_AUTO // Only used by acc/gyro bus auto detection code
} busType_e;
typedef struct busDevice_s {
diff --git a/src/main/drivers/resource.c b/src/main/drivers/resource.c
index 91161e028f..5270705baa 100644
--- a/src/main/drivers/resource.c
+++ b/src/main/drivers/resource.c
@@ -49,11 +49,11 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
"SDCARD_DETECT",
"FLASH_CS",
"BARO_CS",
- "MPU_CS",
+ "GYRO_CS",
"OSD_CS",
"RX_SPI_CS",
"SPI_CS",
- "MPU_EXTI",
+ "GYRO_EXTI",
"BARO_EXTI",
"COMPASS_EXTI",
"USB",
@@ -76,4 +76,6 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
"USB_MSC_PIN",
"SPI_PREINIT_IPU",
"SPI_PREINIT_OPU",
+ "GYRO1_CS",
+ "GYRO2_CS",
};
diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h
index 8b8daaf6a8..84a451c440 100644
--- a/src/main/drivers/resource.h
+++ b/src/main/drivers/resource.h
@@ -49,11 +49,11 @@ typedef enum {
OWNER_SDCARD_DETECT,
OWNER_FLASH_CS,
OWNER_BARO_CS,
- OWNER_MPU_CS,
+ OWNER_GYRO_CS,
OWNER_OSD_CS,
OWNER_RX_SPI_CS,
OWNER_SPI_CS,
- OWNER_MPU_EXTI,
+ OWNER_GYRO_EXTI,
OWNER_BARO_EXTI,
OWNER_COMPASS_EXTI,
OWNER_USB,
@@ -76,6 +76,8 @@ typedef enum {
OWNER_USB_MSC_PIN,
OWNER_SPI_PREINIT_IPU,
OWNER_SPI_PREINIT_OPU,
+ OWNER_GYRO1_CS,
+ OWNER_GYRO2_CS,
OWNER_TOTAL_COUNT
} resourceOwner_e;
diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c
index 6fd74c8d91..b4cf79cc01 100644
--- a/src/main/interface/cli.c
+++ b/src/main/interface/cli.c
@@ -126,6 +126,7 @@ extern uint8_t __config_end;
#include "pg/board.h"
#include "pg/bus_i2c.h"
#include "pg/bus_spi.h"
+#include "pg/gyrodev.h"
#include "pg/max7456.h"
#include "pg/pinio.h"
#include "pg/pg.h"
@@ -2701,7 +2702,7 @@ static void cliPrintGyroRegisters(uint8_t whichSensor)
static void cliDumpGyroRegisters(char *cmdline)
{
-#ifdef USE_DUAL_GYRO
+#ifdef USE_MULTI_GYRO
if ((gyroConfig()->gyro_to_use == GYRO_CONFIG_USE_GYRO_1) || (gyroConfig()->gyro_to_use == GYRO_CONFIG_USE_GYRO_BOTH)) {
cliPrintLinef("\r\n# Gyro 1");
cliPrintGyroRegisters(GYRO_CONFIG_USE_GYRO_1);
@@ -2712,7 +2713,7 @@ static void cliDumpGyroRegisters(char *cmdline)
}
#else
cliPrintGyroRegisters(GYRO_CONFIG_USE_GYRO_1);
-#endif // USE_DUAL_GYRO
+#endif
UNUSED(cmdline);
}
#endif
@@ -3823,6 +3824,8 @@ const cliResourceValue_t resourceTable[] = {
#ifdef USE_RX_SPI
DEFS( OWNER_RX_SPI_CS, PG_RX_SPI_CONFIG, rxSpiConfig_t, csnTag ),
#endif
+#define PG_ARRAY_OFFSET(type, index, member) (index * sizeof(type) + offsetof(type, member))
+ DEFW( OWNER_GYRO_CS, PG_GYRO_DEVICE_CONFIG, gyroDeviceConfig_t, csnTag, 2 ),
};
#undef DEFS
diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c
index 49eb1b356d..b2a8f9ff5e 100644
--- a/src/main/interface/settings.c
+++ b/src/main/interface/settings.c
@@ -70,6 +70,7 @@
#include "pg/beeper_dev.h"
#include "pg/dashboard.h"
#include "pg/flash.h"
+#include "pg/gyrodev.h"
#include "pg/max7456.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
@@ -158,7 +159,7 @@ static const char * const lookupTableAlignment[] = {
"CW270FLIP"
};
-#ifdef USE_DUAL_GYRO
+#ifdef USE_MULTI_GYRO
static const char * const lookupTableGyro[] = {
"FIRST", "SECOND", "BOTH"
};
@@ -289,7 +290,10 @@ static const char * const lookupTableFailsafeSwitchMode[] = {
};
static const char * const lookupTableBusType[] = {
- "NONE", "I2C", "SPI", "SLAVE"
+ "NONE", "I2C", "SPI", "SLAVE",
+#if defined(USE_SPI_GYRO) && defined(USE_I2C_GYRO)
+ "GYROAUTO"
+#endif
};
#ifdef USE_MAX7456
@@ -458,7 +462,7 @@ const lookupTableEntry_t lookupTables[] = {
#ifdef USE_LED_STRIP
LOOKUP_TABLE_ENTRY(lookupLedStripFormatRGB),
#endif
-#ifdef USE_DUAL_GYRO
+#ifdef USE_MULTI_GYRO
LOOKUP_TABLE_ENTRY(lookupTableGyro),
#endif
LOOKUP_TABLE_ENTRY(lookupTableThrottleLimitType),
@@ -485,6 +489,7 @@ const lookupTableEntry_t lookupTables[] = {
#ifdef USE_VTX_COMMON
LOOKUP_TABLE_ENTRY(lookupTableVtxLowPowerDisarm),
#endif
+ LOOKUP_TABLE_ENTRY(lookupTableGyroHardware),
};
#undef LOOKUP_TABLE_ENTRY
@@ -526,7 +531,8 @@ const clivalue_t valueTable[] = {
#if defined(GYRO_USES_SPI) && defined(USE_32K_CAPABLE_GYRO)
{ "gyro_use_32khz", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_use_32khz) },
#endif
-#ifdef USE_DUAL_GYRO
+#endif
+#ifdef USE_MULTI_GYRO
{ "gyro_to_use", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GYRO }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_to_use) },
#endif
#if defined(USE_GYRO_DATA_ANALYSE)
@@ -1153,6 +1159,20 @@ const clivalue_t valueTable[] = {
{ "rcdevice_init_dev_attempts", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 10 }, PG_RCDEVICE_CONFIG, offsetof(rcdeviceConfig_t, initDeviceAttempts) },
{ "rcdevice_init_dev_attempt_interval", VAR_UINT32 | MASTER_VALUE, .config.minmax = { 500, 5000 }, PG_RCDEVICE_CONFIG, offsetof(rcdeviceConfig_t, initDeviceAttemptInterval) }
#endif
+
+#define PG_ARRAY_OFFSET(type, index, member) (index * sizeof(type) + offsetof(type, member))
+
+// PG_GYRO_DEVICE_CONFIG
+ { "gyro_1_bustype", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BUS_TYPE }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_OFFSET(gyroDeviceConfig_t, 0, bustype) },
+ { "gyro_1_spibus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, SPIDEV_COUNT }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_OFFSET(gyroDeviceConfig_t, 0, spiBus) },
+ { "gyro_1_i2cBus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2CDEV_COUNT }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_OFFSET(gyroDeviceConfig_t, 0, i2cBus) },
+ { "gyro_1_i2c_address", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2C_ADDR7_MAX }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_OFFSET(gyroDeviceConfig_t, 0, i2cAddress) },
+#ifdef USE_MULTI_GYRO
+ { "gyro_2_bustype", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BUS_TYPE }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_OFFSET(gyroDeviceConfig_t, 1, bustype) },
+ { "gyro_2_spibus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, SPIDEV_COUNT }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_OFFSET(gyroDeviceConfig_t, 1, spiBus) },
+ { "gyro_2_i2cBus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2CDEV_COUNT }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_OFFSET(gyroDeviceConfig_t, 1, i2cBus) },
+ { "gyro_2_i2c_address", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2C_ADDR7_MAX }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_OFFSET(gyroDeviceConfig_t, 1, i2cAddress) },
+#endif
};
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
diff --git a/src/main/interface/settings.h b/src/main/interface/settings.h
index 013e7649e7..f159bec67e 100644
--- a/src/main/interface/settings.h
+++ b/src/main/interface/settings.h
@@ -92,7 +92,7 @@ typedef enum {
#ifdef USE_LED_STRIP
TABLE_RGB_GRB,
#endif
-#ifdef USE_DUAL_GYRO
+#ifdef USE_MULTI_GYRO
TABLE_GYRO,
#endif
TABLE_THROTTLE_LIMIT_TYPE,
@@ -119,6 +119,7 @@ typedef enum {
#ifdef USE_VTX_COMMON
TABLE_VTX_LOW_POWER_DISARM,
#endif
+ TABLE_GYRO_HARDWARE,
LOOKUP_TABLE_COUNT
} lookupTableIndex_e;
diff --git a/src/main/pg/gyrodev.c b/src/main/pg/gyrodev.c
new file mode 100644
index 0000000000..ad82c17a07
--- /dev/null
+++ b/src/main/pg/gyrodev.c
@@ -0,0 +1,89 @@
+/*
+ * 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 "platform.h"
+
+#include "pg/pg.h"
+#include "pg/pg_ids.h"
+
+#include "drivers/io.h"
+#include "drivers/bus_spi.h"
+
+#include "pg/gyrodev.h"
+
+ioTag_t selectMPUIntExtiConfigByHardwareRevision(void); // XXX Should be gone
+
+#if defined(USE_SPI_GYRO) || defined(USE_I2C_GYRO)
+static void gyroResetCommonDeviceConfig(gyroDeviceConfig_t *devconf, ioTag_t extiTag, sensor_align_e align)
+{
+ devconf->extiTag = extiTag;
+ devconf->align = align;
+}
+#endif
+
+#ifdef USE_SPI_GYRO
+static void gyroResetSpiDeviceConfig(gyroDeviceConfig_t *devconf, SPI_TypeDef *instance, ioTag_t csnTag, ioTag_t extiTag, sensor_align_e align)
+{
+ devconf->bustype = BUSTYPE_SPI;
+ devconf->spiBus = SPI_DEV_TO_CFG(spiDeviceByInstance(instance));
+ devconf->csnTag = csnTag;
+ gyroResetCommonDeviceConfig(devconf, extiTag, align);
+}
+#endif
+
+#ifdef USE_I2C_GYRO
+static void gyroResetI2cDeviceConfig(gyroDeviceConfig_t *devconf, I2CDevice i2cbus, ioTag_t extiTag, sensor_align_e align)
+{
+ devconf->bustype = BUSTYPE_I2C;
+ devconf->i2cBus = I2C_DEV_TO_CFG(i2cbus);
+ devconf->i2cAddress = GYRO_I2C_ADDRESS;
+ gyroResetCommonDeviceConfig(devconf, extiTag, align);
+}
+#endif
+
+PG_REGISTER_ARRAY_WITH_RESET_FN(gyroDeviceConfig_t, MAX_GYRODEV_COUNT, gyroDeviceConfig, PG_GYRO_DEVICE_CONFIG, 0);
+
+void pgResetFn_gyroDeviceConfig(gyroDeviceConfig_t *devconf)
+{
+ devconf[0].index = 0;
+
+ // All multi-gyro boards use SPI based gyros.
+#ifdef USE_SPI_GYRO
+ gyroResetSpiDeviceConfig(&devconf[0], GYRO_1_SPI_INSTANCE, IO_TAG(GYRO_1_CS_PIN), IO_TAG(GYRO_1_EXTI_PIN), GYRO_1_ALIGN);
+#ifdef USE_MULTI_GYRO
+ gyroResetSpiDeviceConfig(&devconf[1], GYRO_2_SPI_INSTANCE, IO_TAG(GYRO_2_CS_PIN), IO_TAG(GYRO_2_EXTI_PIN), GYRO_2_ALIGN);
+ devconf[1].index = 1;
+#endif
+#endif
+
+ // I2C gyros appear as a sole gyro in single gyro boards.
+#if defined(USE_I2C_GYRO) && !defined(USE_MULTI_GYRO)
+ devconf[0].i2cBus = I2C_DEV_TO_CFG(I2CINVALID); // XXX Not required?
+ gyroResetI2cDeviceConfig(&devconf[0], I2C_DEVICE, IO_TAG(GYRO_1_EXTI_PIN), GYRO_1_ALIGN);
+#endif
+
+// Special treatment for very rare F3 targets with variants having either I2C or SPI acc/gyro chip; mark it for run time detection.
+#if defined(USE_SPI_GYRO) && defined(USE_I2C_GYRO)
+ devconf[0].bustype = BUSTYPE_GYRO_AUTO;
+#endif
+}
diff --git a/src/main/pg/gyrodev.h b/src/main/pg/gyrodev.h
new file mode 100644
index 0000000000..22fd36da56
--- /dev/null
+++ b/src/main/pg/gyrodev.h
@@ -0,0 +1,49 @@
+/*
+ * This file is part of Cleanflight and Betaflight.
+ *
+ * Cleanflight and Betaflight are free software. You can redistribute
+ * this software and/or modify this software under the terms of the
+ * GNU General Public License as published by the Free Software
+ * Foundation, either version 3 of the License, or (at your option)
+ * any later version.
+ *
+ * Cleanflight and Betaflight are distributed in the hope that they
+ * will be useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ * See the GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this software.
+ *
+ * If not, see .
+ */
+
+#pragma once
+
+
+#include
+//#include
+
+#include "pg/pg.h"
+#include "drivers/io_types.h"
+#include "drivers/sensor.h"
+#include "sensors/gyro.h"
+
+typedef struct gyroDeviceConfig_s {
+ int8_t index;
+ uint8_t bustype;
+ uint8_t spiBus;
+ ioTag_t csnTag;
+ uint8_t i2cBus;
+ uint8_t i2cAddress;
+ ioTag_t extiTag;
+ sensor_align_e align;
+} gyroDeviceConfig_t;
+
+#ifdef USE_MULTI_GYRO
+#define MAX_GYRODEV_COUNT 2
+#else
+#define MAX_GYRODEV_COUNT 1
+#endif
+
+PG_DECLARE_ARRAY(gyroDeviceConfig_t, MAX_GYRODEV_COUNT, gyroDeviceConfig);
diff --git a/src/main/pg/pg_ids.h b/src/main/pg/pg_ids.h
index 8b762af70c..d174482294 100644
--- a/src/main/pg/pg_ids.h
+++ b/src/main/pg/pg_ids.h
@@ -134,7 +134,8 @@
#define PG_RX_SPI_CONFIG 537
#define PG_BOARD_CONFIG 538
#define PG_RCDEVICE_CONFIG 539
-#define PG_BETAFLIGHT_END 539
+#define PG_GYRO_DEVICE_CONFIG 540
+#define PG_BETAFLIGHT_END 540
// OSD configuration (subject to change)
diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c
index e1626e535c..8826e3607a 100644
--- a/src/main/sensors/acceleration.c
+++ b/src/main/sensors/acceleration.c
@@ -347,14 +347,11 @@ bool accInit(uint32_t gyroSamplingInverval)
acc.dev.mpuDetectionResult = *gyroMpuDetectionResult();
acc.dev.acc_high_fsr = accelerometerConfig()->acc_high_fsr;
-#ifdef USE_DUAL_GYRO
+ acc.dev.accAlign = ACC_1_ALIGN;
+#ifdef ACC_2_ALIGN
if (gyroConfig()->gyro_to_use == GYRO_CONFIG_USE_GYRO_2) {
acc.dev.accAlign = ACC_2_ALIGN;
- } else {
- acc.dev.accAlign = ACC_1_ALIGN;
}
-#else
- acc.dev.accAlign = ALIGN_DEFAULT;
#endif
if (!accDetect(&acc.dev, accelerometerConfig()->acc_hardware)) {
diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c
index 8c6dff4c16..5d2eedf2e5 100644
--- a/src/main/sensors/gyro.c
+++ b/src/main/sensors/gyro.c
@@ -36,6 +36,7 @@
#include "pg/pg.h"
#include "pg/pg_ids.h"
+#include "pg/gyrodev.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_fake.h"
@@ -77,10 +78,6 @@
#endif
#include "sensors/sensors.h"
-#ifdef USE_HARDWARE_REVISION_DETECTION
-#include "hardware_revision.h"
-#endif
-
#if ((FLASH_SIZE > 128) && (defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6500)))
#define USE_GYRO_SLEW_LIMITER
#endif
@@ -152,7 +149,7 @@ typedef struct gyroSensor_s {
} gyroSensor_t;
STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT gyroSensor_t gyroSensor1;
-#ifdef USE_DUAL_GYRO
+#ifdef USE_MULTI_GYRO
STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT gyroSensor_t gyroSensor2;
#endif
@@ -211,47 +208,34 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
.dyn_filter_range = DYN_FILTER_RANGE_MEDIUM,
);
+#ifdef USE_MULTI_GYRO
+#define ACTIVE_GYRO ((gyroToUse == GYRO_CONFIG_USE_GYRO_2) ? &gyroSensor2 : &gyroSensor1)
+#else
+#define ACTIVE_GYRO (&gyroSensor1)
+#endif
const busDevice_t *gyroSensorBus(void)
{
-#ifdef USE_DUAL_GYRO
- if (gyroToUse == GYRO_CONFIG_USE_GYRO_2) {
- return &gyroSensor2.gyroDev.bus;
- } else {
- return &gyroSensor1.gyroDev.bus;
- }
-#else
- return &gyroSensor1.gyroDev.bus;
-#endif
+ return &ACTIVE_GYRO->gyroDev.bus;
}
#ifdef USE_GYRO_REGISTER_DUMP
const busDevice_t *gyroSensorBusByDevice(uint8_t whichSensor)
{
-#ifdef USE_DUAL_GYRO
+#ifdef USE_MULTI_GYRO
if (whichSensor == GYRO_CONFIG_USE_GYRO_2) {
return &gyroSensor2.gyroDev.bus;
- } else {
- return &gyroSensor1.gyroDev.bus;
}
#else
UNUSED(whichSensor);
- return &gyroSensor1.gyroDev.bus;
#endif
+ return &gyroSensor1.gyroDev.bus;
}
#endif // USE_GYRO_REGISTER_DUMP
const mpuDetectionResult_t *gyroMpuDetectionResult(void)
{
-#ifdef USE_DUAL_GYRO
- if (gyroToUse == GYRO_CONFIG_USE_GYRO_2) {
- return &gyroSensor2.gyroDev.mpuDetectionResult;
- } else {
- return &gyroSensor1.gyroDev.mpuDetectionResult;
- }
-#else
- return &gyroSensor1.gyroDev.mpuDetectionResult;
-#endif
+ return &ACTIVE_GYRO->gyroDev.mpuDetectionResult;
}
STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
@@ -266,9 +250,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
case GYRO_MPU6050:
if (mpu6050GyroDetect(dev)) {
gyroHardware = GYRO_MPU6050;
-#ifdef GYRO_MPU6050_ALIGN
- dev->gyroAlign = GYRO_MPU6050_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -278,9 +259,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
case GYRO_L3G4200D:
if (l3g4200dDetect(dev)) {
gyroHardware = GYRO_L3G4200D;
-#ifdef GYRO_L3G4200D_ALIGN
- dev->gyroAlign = GYRO_L3G4200D_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -290,9 +268,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
case GYRO_MPU3050:
if (mpu3050Detect(dev)) {
gyroHardware = GYRO_MPU3050;
-#ifdef GYRO_MPU3050_ALIGN
- dev->gyroAlign = GYRO_MPU3050_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -302,9 +277,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
case GYRO_L3GD20:
if (l3gd20Detect(dev)) {
gyroHardware = GYRO_L3GD20;
-#ifdef GYRO_L3GD20_ALIGN
- dev->gyroAlign = GYRO_L3GD20_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -314,9 +286,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
case GYRO_MPU6000:
if (mpu6000SpiGyroDetect(dev)) {
gyroHardware = GYRO_MPU6000;
-#ifdef GYRO_MPU6000_ALIGN
- dev->gyroAlign = GYRO_MPU6000_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -348,9 +317,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
default:
gyroHardware = GYRO_MPU6500;
}
-#ifdef GYRO_MPU6500_ALIGN
- dev->gyroAlign = GYRO_MPU6500_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -360,9 +326,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
case GYRO_MPU9250:
if (mpu9250SpiGyroDetect(dev)) {
gyroHardware = GYRO_MPU9250;
-#ifdef GYRO_MPU9250_ALIGN
- dev->gyroAlign = GYRO_MPU9250_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -372,9 +335,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
case GYRO_ICM20649:
if (icm20649SpiGyroDetect(dev)) {
gyroHardware = GYRO_ICM20649;
-#ifdef GYRO_ICM20649_ALIGN
- dev->gyroAlign = GYRO_ICM20649_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -384,9 +344,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
case GYRO_ICM20689:
if (icm20689SpiGyroDetect(dev)) {
gyroHardware = GYRO_ICM20689;
-#ifdef GYRO_ICM20689_ALIGN
- dev->gyroAlign = GYRO_ICM20689_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -396,9 +353,6 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
case GYRO_BMI160:
if (bmi160SpiGyroDetect(dev)) {
gyroHardware = GYRO_BMI160;
-#ifdef GYRO_BMI160_ALIGN
- dev->gyroAlign = GYRO_BMI160_ALIGN;
-#endif
break;
}
FALLTHROUGH;
@@ -426,14 +380,16 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
return gyroHardware;
}
-static bool gyroInitSensor(gyroSensor_t *gyroSensor)
+static bool gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
{
gyroSensor->gyroDev.gyro_high_fsr = gyroConfig()->gyro_high_fsr;
+ gyroSensor->gyroDev.gyroAlign = config->align;
+ gyroSensor->gyroDev.mpuIntExtiTag = config->extiTag;
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) \
|| defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689)
- mpuDetect(&gyroSensor->gyroDev);
+ mpuDetect(&gyroSensor->gyroDev, config);
#endif
const gyroHardware_e gyroHardware = gyroDetect(&gyroSensor->gyroDev);
@@ -536,79 +492,23 @@ bool gyroInit(void)
bool ret = false;
gyroToUse = gyroConfig()->gyro_to_use;
-#if defined(USE_DUAL_GYRO) && defined(GYRO_1_CS_PIN)
if (gyroToUse == GYRO_CONFIG_USE_GYRO_1 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
- gyroSensor1.gyroDev.bus.busdev_u.spi.csnPin = IOGetByTag(IO_TAG(GYRO_1_CS_PIN));
- IOInit(gyroSensor1.gyroDev.bus.busdev_u.spi.csnPin, OWNER_MPU_CS, RESOURCE_INDEX(0));
- IOHi(gyroSensor1.gyroDev.bus.busdev_u.spi.csnPin); // Ensure device is disabled, important when two devices are on the same bus.
- IOConfigGPIO(gyroSensor1.gyroDev.bus.busdev_u.spi.csnPin, SPI_IO_CS_CFG);
- }
-#endif
-
-#if defined(USE_DUAL_GYRO) && defined(GYRO_2_CS_PIN)
- if (gyroToUse == GYRO_CONFIG_USE_GYRO_2 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
- gyroSensor2.gyroDev.bus.busdev_u.spi.csnPin = IOGetByTag(IO_TAG(GYRO_2_CS_PIN));
- IOInit(gyroSensor2.gyroDev.bus.busdev_u.spi.csnPin, OWNER_MPU_CS, RESOURCE_INDEX(1));
- IOHi(gyroSensor2.gyroDev.bus.busdev_u.spi.csnPin); // Ensure device is disabled, important when two devices are on the same bus.
- IOConfigGPIO(gyroSensor2.gyroDev.bus.busdev_u.spi.csnPin, SPI_IO_CS_CFG);
- }
-#endif
-
- gyroSensor1.gyroDev.gyroAlign = ALIGN_DEFAULT;
-
-#if defined(GYRO_1_EXTI_PIN)
- gyroSensor1.gyroDev.mpuIntExtiTag = IO_TAG(GYRO_1_EXTI_PIN);
-#elif defined(MPU_INT_EXTI)
- gyroSensor1.gyroDev.mpuIntExtiTag = IO_TAG(MPU_INT_EXTI);
-#elif defined(USE_HARDWARE_REVISION_DETECTION)
- gyroSensor1.gyroDev.mpuIntExtiTag = selectMPUIntExtiConfigByHardwareRevision();
-#else
- gyroSensor1.gyroDev.mpuIntExtiTag = IO_TAG_NONE;
-#endif // GYRO_1_EXTI_PIN
-#ifdef USE_DUAL_GYRO
-#ifdef GYRO_1_ALIGN
- gyroSensor1.gyroDev.gyroAlign = GYRO_1_ALIGN;
-#endif
- gyroSensor1.gyroDev.bus.bustype = BUSTYPE_SPI;
- spiBusSetInstance(&gyroSensor1.gyroDev.bus, GYRO_1_SPI_INSTANCE);
- if (gyroToUse == GYRO_CONFIG_USE_GYRO_1 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
- ret = gyroInitSensor(&gyroSensor1);
+ ret = gyroInitSensor(&gyroSensor1, gyroDeviceConfig(0));
if (!ret) {
return false; // TODO handle failure of first gyro detection better. - Perhaps update the config to use second gyro then indicate a new failure mode and reboot.
}
gyroHasOverflowProtection = gyroHasOverflowProtection && gyroSensor1.gyroDev.gyroHasOverflowProtection;
}
-#else // USE_DUAL_GYRO
- ret = gyroInitSensor(&gyroSensor1);
- gyroHasOverflowProtection = gyroHasOverflowProtection && gyroSensor1.gyroDev.gyroHasOverflowProtection;
-#endif // USE_DUAL_GYRO
-#ifdef USE_DUAL_GYRO
-
- gyroSensor2.gyroDev.gyroAlign = ALIGN_DEFAULT;
-
-#if defined(GYRO_2_EXTI_PIN)
- gyroSensor2.gyroDev.mpuIntExtiTag = IO_TAG(GYRO_2_EXTI_PIN);
-#elif defined(USE_HARDWARE_REVISION_DETECTION)
- gyroSensor2.gyroDev.mpuIntExtiTag = selectMPUIntExtiConfigByHardwareRevision();
-#else
- gyroSensor2.gyroDev.mpuIntExtiTag = IO_TAG_NONE;
-#endif // GYRO_2_EXTI_PIN
-#ifdef GYRO_2_ALIGN
- gyroSensor2.gyroDev.gyroAlign = GYRO_2_ALIGN;
-#endif
- gyroSensor2.gyroDev.bus.bustype = BUSTYPE_SPI;
- spiBusSetInstance(&gyroSensor2.gyroDev.bus, GYRO_2_SPI_INSTANCE);
+#ifdef USE_MULTI_GYRO
if (gyroToUse == GYRO_CONFIG_USE_GYRO_2 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
- ret = gyroInitSensor(&gyroSensor2);
+ ret = gyroInitSensor(&gyroSensor2, gyroDeviceConfig(1));
if (!ret) {
return false; // TODO handle failure of second gyro detection better. - Perhaps update the config to use first gyro then indicate a new failure mode and reboot.
}
gyroHasOverflowProtection = gyroHasOverflowProtection && gyroSensor2.gyroDev.gyroHasOverflowProtection;
}
-#endif // USE_DUAL_GYRO
-#ifdef USE_DUAL_GYRO
// Only allow using both gyros simultaneously if they are the same hardware type.
// If the user selected "BOTH" and they are not the same type, then reset to using only the first gyro.
if (gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
@@ -620,7 +520,8 @@ bool gyroInit(void)
}
}
-#endif // USE_DUAL_GYRO
+#endif
+
return ret;
}
@@ -778,7 +679,7 @@ static void gyroInitSensorFilters(gyroSensor_t *gyroSensor)
void gyroInitFilters(void)
{
gyroInitSensorFilters(&gyroSensor1);
-#ifdef USE_DUAL_GYRO
+#ifdef USE_MULTI_GYRO
gyroInitSensorFilters(&gyroSensor2);
#endif
}
@@ -790,22 +691,20 @@ FAST_CODE bool isGyroSensorCalibrationComplete(const gyroSensor_t *gyroSensor)
FAST_CODE bool isGyroCalibrationComplete(void)
{
-#ifdef USE_DUAL_GYRO
switch (gyroToUse) {
default:
case GYRO_CONFIG_USE_GYRO_1: {
return isGyroSensorCalibrationComplete(&gyroSensor1);
}
+#ifdef USE_MULTI_GYRO
case GYRO_CONFIG_USE_GYRO_2: {
return isGyroSensorCalibrationComplete(&gyroSensor2);
}
case GYRO_CONFIG_USE_GYRO_BOTH: {
return isGyroSensorCalibrationComplete(&gyroSensor1) && isGyroSensorCalibrationComplete(&gyroSensor2);
}
- }
-#else
- return isGyroSensorCalibrationComplete(&gyroSensor1);
#endif
+ }
}
static bool isOnFinalGyroCalibrationCycle(const gyroCalibration_t *gyroCalibration)
@@ -832,7 +731,7 @@ void gyroStartCalibration(bool isFirstArmingCalibration)
{
if (!(isFirstArmingCalibration && firstArmingCalibrationWasStarted)) {
gyroSetCalibrationCycles(&gyroSensor1);
-#ifdef USE_DUAL_GYRO
+#ifdef USE_MULTI_GYRO
gyroSetCalibrationCycles(&gyroSensor2);
#endif
@@ -1073,7 +972,6 @@ static FAST_CODE FAST_CODE_NOINLINE void gyroUpdateSensor(gyroSensor_t *gyroSens
FAST_CODE void gyroUpdate(timeUs_t currentTimeUs)
{
-#ifdef USE_DUAL_GYRO
switch (gyroToUse) {
case GYRO_CONFIG_USE_GYRO_1:
gyroUpdateSensor(&gyroSensor1, currentTimeUs);
@@ -1089,6 +987,7 @@ FAST_CODE void gyroUpdate(timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_DUAL_GYRO_COMBINE, 0, lrintf(gyro.gyroADCf[X]));
DEBUG_SET(DEBUG_DUAL_GYRO_COMBINE, 1, lrintf(gyro.gyroADCf[Y]));
break;
+#ifdef USE_MULTI_GYRO
case GYRO_CONFIG_USE_GYRO_2:
gyroUpdateSensor(&gyroSensor2, currentTimeUs);
if (isGyroSensorCalibrationComplete(&gyroSensor2)) {
@@ -1125,13 +1024,8 @@ FAST_CODE void gyroUpdate(timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 1, lrintf(gyroSensor1.gyroDev.gyroADCf[Y] - gyroSensor2.gyroDev.gyroADCf[Y]));
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 2, lrintf(gyroSensor1.gyroDev.gyroADCf[Z] - gyroSensor2.gyroDev.gyroADCf[Z]));
break;
- }
-#else
- gyroUpdateSensor(&gyroSensor1, currentTimeUs);
- gyro.gyroADCf[X] = gyroSensor1.gyroDev.gyroADCf[X];
- gyro.gyroADCf[Y] = gyroSensor1.gyroDev.gyroADCf[Y];
- gyro.gyroADCf[Z] = gyroSensor1.gyroDev.gyroADCf[Z];
#endif
+ }
}
bool gyroGetAccumulationAverage(float *accumulationAverage)
@@ -1166,15 +1060,7 @@ int16_t gyroGetTemperature(void)
int16_t gyroRateDps(int axis)
{
-#ifdef USE_DUAL_GYRO
- if (gyroToUse == GYRO_CONFIG_USE_GYRO_2) {
- return lrintf(gyro.gyroADCf[axis] / gyroSensor2.gyroDev.scale);
- } else {
- return lrintf(gyro.gyroADCf[axis] / gyroSensor1.gyroDev.scale);
- }
-#else
- return lrintf(gyro.gyroADCf[axis] / gyroSensor1.gyroDev.scale);
-#endif
+ return lrintf(gyro.gyroADCf[axis] / ACTIVE_GYRO->gyroDev.scale);
}
bool gyroOverflowDetected(void)
diff --git a/src/main/target/AG3X/target.h b/src/main/target/AG3X/target.h
index df8090c285..7e19a0fc1c 100644
--- a/src/main/target/AG3X/target.h
+++ b/src/main/target/AG3X/target.h
@@ -42,21 +42,28 @@
#define BEEPER_INVERTED
#define USE_ACC
-#define USE_GYRO
-
#define USE_ACC_SPI_MPU6000
-#define USE_GYRO_SPI_MPU6000
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-#define ACC_MPU6000_ALIGN CW0_DEG_FLIP
-#define GYRO_MPU6000_ALIGN CW0_DEG_FLIP
-
#define USE_ACC_SPI_MPU6500
+
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_MPU6500
-#define MPU6500_CS_PIN MPU6000_CS_PIN
-#define MPU6500_SPI_INSTANCE MPU6000_SPI_INSTANCE
-#define ACC_MPU6500_ALIGN CW0_DEG_FLIP
-#define GYRO_MPU6500_ALIGN CW0_DEG_FLIP
+
+#define USE_MULTI_GYRO
+
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_EXTI_PIN NONE
+
+#define ACC_1_ALIGN CW0_DEG_FLIP
+#define GYRO_1_ALIGN CW0_DEG_FLIP
+
+#define GYRO_2_SPI_INSTANCE SPI1
+#define GYRO_2_CS_PIN PC15
+#define GYRO_2_EXTI_PIN NONE
+
+#define ACC_2_ALIGN CW0_DEG_FLIP
+#define GYRO_2_ALIGN CW0_DEG_FLIP
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/AIKONF4/target.h b/src/main/target/AIKONF4/target.h
index 728c51b987..699ad334c7 100644
--- a/src/main/target/AIKONF4/target.h
+++ b/src/main/target/AIKONF4/target.h
@@ -33,24 +33,22 @@
#define INVERTER_PIN_UART1 PC0
#define USE_EXTI
-#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_GYRO_SPI_MPU6500
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_1_ALIGN CW0_DEG
+
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW0_DEG
-#define ACC_MPU6000_ALIGN CW0_DEG
-
-#define USE_GYRO_SPI_MPU6500
#define USE_ACC_SPI_MPU6500
-#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_1_ALIGN CW0_DEG
+
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
+#define USE_MPU_DATA_READY_SIGNAL
#define USE_BARO
#define USE_BARO_BMP280
diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h
index 182954485d..90d23d4b7f 100644
--- a/src/main/target/AIR32/target.h
+++ b/src/main/target/AIR32/target.h
@@ -30,26 +30,27 @@
// MPU6050 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PA15
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA15
#define USE_MPU_DATA_READY_SIGNAL
//#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_GYRO
#define USE_ACC
-#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW180_DEG
-
-#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW180_DEG
+// MPU6050 support has been dropped according to board wiki
+// https://github.com/betaflight/betaflight/wiki/Board---AIR32
+//#define USE_GYRO_MPU6050
+//#define USE_ACC_MPU6050
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-#define MPU6000_CS_PIN PB12
-#define MPU6000_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
+
+#define GYRO_1_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
//#define USE_BARO
//#define USE_BARO_MS5611
diff --git a/src/main/target/AIRHEROF3/target.h b/src/main/target/AIRHEROF3/target.h
index f0304fcd74..ba51f2d047 100644
--- a/src/main/target/AIRHEROF3/target.h
+++ b/src/main/target/AIRHEROF3/target.h
@@ -32,23 +32,24 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_SPI
#define USE_SPI_DEVICE_2
-#define MPU6500_CS_PIN PB12
-#define MPU6500_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_BARO
#define USE_BARO_SPI_BMP280
diff --git a/src/main/target/ALIENFLIGHTF1/target.h b/src/main/target/ALIENFLIGHTF1/target.h
index 5c630d116e..0615867136 100644
--- a/src/main/target/ALIENFLIGHTF1/target.h
+++ b/src/main/target/ALIENFLIGHTF1/target.h
@@ -37,12 +37,12 @@
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_UART1
#define USE_UART2
diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c
index 9e485e97cb..ba444b8098 100644
--- a/src/main/target/ALIENFLIGHTF3/config.c
+++ b/src/main/target/ALIENFLIGHTF3/config.c
@@ -37,6 +37,7 @@
#include "flight/pid.h"
#include "pg/beeper_dev.h"
+#include "pg/gyrodev.h"
#include "pg/rx.h"
#include "rx/rx.h"
@@ -60,6 +61,8 @@
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void)
{
+ gyroDeviceConfigMutable(0)->extiTag = selectMPUIntExtiConfigByHardwareRevision();
+
/* depending on revision ... depends on the LEDs to be utilised. */
if (hardwareRevision == AFF3_REV_2) {
statusLedConfigMutable()->inversion = 0
diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h
index 9005315741..2ad4e1171e 100644
--- a/src/main/target/ALIENFLIGHTF3/target.h
+++ b/src/main/target/ALIENFLIGHTF3/target.h
@@ -49,15 +49,15 @@
#define USE_GYRO_MPU6050
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6050_ALIGN CW270_DEG
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_MPU6050
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6050_ALIGN CW270_DEG
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
// No baro support.
//#define USE_BARO
@@ -106,8 +106,8 @@
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
-#define MPU6500_CS_PIN SPI3_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI3
+#define GYRO_1_CS_PIN SPI3_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI3
#define USE_ADC
diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h
index 9c472a681b..00c9d937de 100644
--- a/src/main/target/ALIENFLIGHTF4/target.h
+++ b/src/main/target/ALIENFLIGHTF4/target.h
@@ -38,21 +38,22 @@
// MPU interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC14
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC14
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#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 GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h
index a45b916549..82b7349dbf 100644
--- a/src/main/target/ALIENFLIGHTNGF7/target.h
+++ b/src/main/target/ALIENFLIGHTNGF7/target.h
@@ -36,21 +36,22 @@
// MPU interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC14
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC14
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#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 GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/ALIENWHOOP/target.h b/src/main/target/ALIENWHOOP/target.h
index d5b04e3b1e..e30b085592 100644
--- a/src/main/target/ALIENWHOOP/target.h
+++ b/src/main/target/ALIENWHOOP/target.h
@@ -121,10 +121,11 @@
*/
// Interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC14
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC14
// MPU
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
// MAG
@@ -136,11 +137,11 @@
// GYRO
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
// ACC
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
/* Optional Digital Pressure Sensor (barometer) - Bosch BMP280
* TODO: not implemented on V1 or V2 pcb
diff --git a/src/main/target/ANYFCF7/target.h b/src/main/target/ANYFCF7/target.h
index ef9fc4e30c..fac0ebf5bc 100644
--- a/src/main/target/ANYFCF7/target.h
+++ b/src/main/target/ANYFCF7/target.h
@@ -31,20 +31,22 @@
#define BEEPER_PIN PB2 // Unused pin, can be mapped to elsewhere
#define BEEPER_INVERTED
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PC4
+#define USE_EXTI
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPC4
#define USE_EXTI
#define USE_MAG
diff --git a/src/main/target/ANYFCM7/target.h b/src/main/target/ANYFCM7/target.h
index d9e3cf20d7..b8ac7a9913 100644
--- a/src/main/target/ANYFCM7/target.h
+++ b/src/main/target/ANYFCM7/target.h
@@ -31,20 +31,22 @@
#define BEEPER_PIN PB2 // Unused pin, can be mapped to elsewhere
#define BEEPER_INVERTED
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PC4
+#define USE_EXTI
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPC4
#define USE_EXTI
#define USE_MAG
diff --git a/src/main/target/BEEBRAIN_V2F/target.h b/src/main/target/BEEBRAIN_V2F/target.h
index 8f30494188..4bd12eb93c 100644
--- a/src/main/target/BEEBRAIN_V2F/target.h
+++ b/src/main/target/BEEBRAIN_V2F/target.h
@@ -32,23 +32,24 @@
#define LED1_PIN PB2
#define USE_EXTI
-#define MPU_INT_EXTI PB6
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PB6
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
#if defined(BEESTORM)
-#define GYRO_MPU6500_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#else
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#endif
#define USE_ACC
#define USE_ACC_SPI_MPU6500
#if defined(BEESTORM)
-#define ACC_MPU6500_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
#else
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#endif
#define SERIAL_PORT_COUNT 4
@@ -85,8 +86,8 @@
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
-#define MPU6500_CS_PIN PA15
-#define MPU6500_SPI_INSTANCE SPI3
+#define GYRO_1_CS_PIN PA15
+#define GYRO_1_SPI_INSTANCE SPI3
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI1
diff --git a/src/main/target/BEEROTORF4/target.h b/src/main/target/BEEROTORF4/target.h
index bb5592055f..6212b6e01a 100644
--- a/src/main/target/BEEROTORF4/target.h
+++ b/src/main/target/BEEROTORF4/target.h
@@ -33,21 +33,22 @@
// ICM20689 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PA8
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA8
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define ICM20689_CS_PIN SPI1_NSS_PIN
-#define ICM20689_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_BARO
#define USE_BARO_BMP280
diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h
index f7267ad9db..afe82fb489 100644
--- a/src/main/target/BETAFLIGHTF3/target.h
+++ b/src/main/target/BETAFLIGHTF3/target.h
@@ -51,20 +51,22 @@
#define USABLE_TIMER_CHANNEL_COUNT 10
-#define MPU6000_CS_PIN PA15
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA15
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PC13
+#define USE_EXTI
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_EXTI
#define REMAP_TIM16_DMA
diff --git a/src/main/target/BETAFLIGHTF4/target.h b/src/main/target/BETAFLIGHTF4/target.h
index 04b0b7a4ed..0d2be3064a 100644
--- a/src/main/target/BETAFLIGHTF4/target.h
+++ b/src/main/target/BETAFLIGHTF4/target.h
@@ -32,22 +32,23 @@
// PC13 used as inverter select GPIO for UART2
#define INVERTER_PIN_UART2 PC13
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
#define USE_BARO
diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h
index b346aefdac..867dc38519 100644
--- a/src/main/target/BLUEJAYF4/target.h
+++ b/src/main/target/BLUEJAYF4/target.h
@@ -47,22 +47,21 @@
// MPU6500 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC5
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC5
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
-#define MPU6500_CS_PIN PC4
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_GYRO
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h
index 3f380b38d9..9153e95ac9 100644
--- a/src/main/target/CC3D/target.h
+++ b/src/main/target/CC3D/target.h
@@ -31,7 +31,8 @@
#define BEEPER_OPT PA2
#define USE_EXTI
-#define MPU_INT_EXTI PA3
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA3
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
@@ -39,8 +40,8 @@
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define FLASH_CS_PIN PB12
#define FLASH_SPI_INSTANCE SPI2
@@ -50,11 +51,11 @@
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h
index 45a4e08b81..8ba04ea5e6 100644
--- a/src/main/target/CHEBUZZF3/target.h
+++ b/src/main/target/CHEBUZZF3/target.h
@@ -69,7 +69,7 @@
//#define L3GD20_CS_PIN PE3
//#define GYRO_L3GD20_ALIGN CW270_DEG
-#define GYRO_MPU6050_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_ACC
#define USE_ACC_MPU6050
@@ -81,7 +81,7 @@
//#define LSM303DLHC_I2C_INT1_PIN PE4
//#define LSM303DLHC_I2C_INT2_PIN PE5
-#define ACC_MPU6050_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_BARO
#define USE_BARO_MS5611
diff --git a/src/main/target/CHEBUZZF3/target.mk b/src/main/target/CHEBUZZF3/target.mk
index cdf3c6d26e..2ece8cd60a 100644
--- a/src/main/target/CHEBUZZF3/target.mk
+++ b/src/main/target/CHEBUZZF3/target.mk
@@ -6,12 +6,6 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu3050.c \
drivers/accgyro/accgyro_mpu6050.c \
- drivers/accgyro_legacy/accgyro_l3gd20.c \
- drivers/accgyro_legacy/accgyro_lsm303dlhc.c \
- drivers/accgyro_legacy/accgyro_adxl345.c \
- drivers/accgyro_legacy/accgyro_bma280.c \
- drivers/accgyro_legacy/accgyro_mma845x.c \
- drivers/accgyro_legacy/accgyro_l3g4200d.c \
drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_ak8975.c
diff --git a/src/main/target/CJMCU/config.c b/src/main/target/CJMCU/config.c
new file mode 100644
index 0000000000..13668a4b17
--- /dev/null
+++ b/src/main/target/CJMCU/config.c
@@ -0,0 +1,38 @@
+/*
+ * 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 "platform.h"
+
+#ifdef USE_TARGET_CONFIG
+
+#include "drivers/io_types.h"
+#include "hardware_revision.h"
+
+#include "pg/pg.h"
+#include "pg/gyrodev.h"
+
+void targetConfiguration(void)
+{
+ gyroDeviceConfigMutable(0)->extiTag = selectMPUIntExtiConfigByHardwareRevision();
+}
+#endif
diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h
index 8e25aa985f..6952ce9c12 100644
--- a/src/main/target/CJMCU/target.h
+++ b/src/main/target/CJMCU/target.h
@@ -22,6 +22,7 @@
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
#define USE_HARDWARE_REVISION_DETECTION
+#define USE_TARGET_CONFIG
#define TARGET_BUS_INIT
#define LED0_PIN PC14
diff --git a/src/main/target/CLRACINGF4/target.h b/src/main/target/CLRACINGF4/target.h
index dcc0435d5b..55897d35c0 100644
--- a/src/main/target/CLRACINGF4/target.h
+++ b/src/main/target/CLRACINGF4/target.h
@@ -38,32 +38,29 @@
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
+#define CAMERA_CONTROL_PIN PB9 // define dedicated camera_osd_control pin
+
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
-// MPU 6000
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
#define USE_ACC
-#define USE_ACC_SPI_MPU6000
#define USE_GYRO
+
+// MPU 6000
+#define USE_ACC_SPI_MPU6000
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW0_DEG
-#define ACC_MPU6000_ALIGN CW0_DEG
// ICM-20602
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
-#define GYRO_MPU6500_ALIGN CW0_DEG
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
-
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_1_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI3
diff --git a/src/main/target/CLRACINGF7/target.h b/src/main/target/CLRACINGF7/target.h
index 42f8eb31bd..2117aaf7b3 100644
--- a/src/main/target/CLRACINGF7/target.h
+++ b/src/main/target/CLRACINGF7/target.h
@@ -30,29 +30,27 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
-//MPU-6000
+
#define USE_ACC
-#define USE_ACC_SPI_MPU6000
#define USE_GYRO
+
+//MPU-6000
+#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 PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
// ICM-20602
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
-#define GYRO_MPU6500_ALIGN CW0_DEG
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define GYRO_1_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
+
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI3
diff --git a/src/main/target/COLIBRI/target.h b/src/main/target/COLIBRI/target.h
index ae40d63a81..e9b8e266e3 100644
--- a/src/main/target/COLIBRI/target.h
+++ b/src/main/target/COLIBRI/target.h
@@ -37,20 +37,21 @@
#define INVERTER_PIN_UART2 PB2 // PB2 used as inverter select GPIO
-#define MPU6000_CS_PIN PC4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG_FLIP
+#define ACC_1_ALIGN CW270_DEG_FLIP
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG_FLIP
+#define GYRO_1_ALIGN CW270_DEG_FLIP
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PC0
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC0
#define USE_MPU_DATA_READY_SIGNAL
#define USE_MAG
diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h
index cd4ddbce95..51bab63b57 100644
--- a/src/main/target/COLIBRI_RACE/target.h
+++ b/src/main/target/COLIBRI_RACE/target.h
@@ -40,7 +40,8 @@
// MPU6500 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PA5
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA5
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@@ -52,25 +53,18 @@
#define SPI1_MOSI_PIN PB5
#define SPI1_NSS_PIN PA4
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
-
-#define MPU6000_CS_PIN SPI1_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_BARO
#define USE_BARO_MS5611
diff --git a/src/main/target/CRAZYBEEF3FR/target.h b/src/main/target/CRAZYBEEF3FR/target.h
index 7c59e745f7..e3a95f0545 100644
--- a/src/main/target/CRAZYBEEF3FR/target.h
+++ b/src/main/target/CRAZYBEEF3FR/target.h
@@ -63,16 +63,17 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPC13
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU6000_SPI_INSTANCE SPI1
-#define MPU6000_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
#define USE_VCP
#define USE_UART3
diff --git a/src/main/target/CRAZYFLIE2/target.h b/src/main/target/CRAZYFLIE2/target.h
index c98588c1e7..8c8489b39d 100644
--- a/src/main/target/CRAZYFLIE2/target.h
+++ b/src/main/target/CRAZYFLIE2/target.h
@@ -82,17 +82,20 @@
#define USE_I2C_DEVICE_3
#define I2C_DEVICE (I2CDEV_3)
+// This board only uses I2C acc/gyro
+#undef USE_MULTI_GYRO
+
// MPU9250 has the AD0 pin held high so the
// address is 0x69 instead of the default 0x68
#define MPU_ADDRESS 0x69
#define USE_GYRO
#define USE_GYRO_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_MAG
#define USE_MPU9250_MAG // Enables bypass configuration on the MPU9250 I2C bus
@@ -100,7 +103,8 @@
#define MAG_AK8963_ALIGN CW270_DEG
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_SERIALRX_TARGET_CUSTOM
#define SERIALRX_UART SERIAL_PORT_USART6
diff --git a/src/main/target/DALRCF405/target.h b/src/main/target/DALRCF405/target.h
index fb7013bf8a..7d9eda6d6b 100644
--- a/src/main/target/DALRCF405/target.h
+++ b/src/main/target/DALRCF405/target.h
@@ -40,7 +40,8 @@
#define SPI1_MOSI_PIN PA7
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
@@ -55,14 +56,14 @@
#define USE_ACC_SPI_ICM20689
#define ACC_ICM20689_ALIGN CW90_DEG
//------MPU6000
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
//Baro & MAG-------------------------------
#define USE_I2C
diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h
index d2ce79589f..229bd8dc00 100644
--- a/src/main/target/DOGE/target.h
+++ b/src/main/target/DOGE/target.h
@@ -57,10 +57,8 @@
#define SPI2_NSS_PIN PB12
// tqfp48 pin 3
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
-#define MPU6000_CS_PIN SPI1_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
// tqfp48 pin 25
#define BMP280_CS_PIN SPI2_NSS_PIN
@@ -73,19 +71,14 @@
#define FLASH_SPI_INSTANCE SPI2
#define USE_GYRO
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
-
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_BARO
#define USE_BARO_BMP280
@@ -121,7 +114,8 @@
// mpu_int definition in sensors/initialisation.c
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
diff --git a/src/main/target/EACHIF3/target.h b/src/main/target/EACHIF3/target.h
index 4dbb690fca..a4a91c63b1 100644
--- a/src/main/target/EACHIF3/target.h
+++ b/src/main/target/EACHIF3/target.h
@@ -26,7 +26,8 @@
#define USE_EXTI
-#define MPU_INT_EXTI PA15
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA15
#define USE_MPU_DATA_READY_SIGNAL
@@ -35,20 +36,20 @@
#define USE_SPI_DEVICE_2
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_SPI_INSTANCE SPI1
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
-#define MPU6500_CS_PIN PA5
+#define GYRO_1_CS_PIN PA5
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
#define USE_RX_SPI
diff --git a/src/main/target/ELLE0/target.h b/src/main/target/ELLE0/target.h
index a1a6f909fe..d1066a8680 100644
--- a/src/main/target/ELLE0/target.h
+++ b/src/main/target/ELLE0/target.h
@@ -31,22 +31,23 @@
// MPU9250 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PB5
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PB5
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define MPU6500_CS_PIN PB12
-#define MPU6500_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
// Using MPU6050 for the moment.
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
//#define USE_BARO
//#define USE_BARO_MS5611
diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h
index d6c9764875..8d1f8b98a8 100644
--- a/src/main/target/F4BY/target.h
+++ b/src/main/target/F4BY/target.h
@@ -36,19 +36,20 @@
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PB0
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PB0
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/FF_FORTINIF4/target.h b/src/main/target/FF_FORTINIF4/target.h
index a1ad91e4ea..979addb01c 100644
--- a/src/main/target/FF_FORTINIF4/target.h
+++ b/src/main/target/FF_FORTINIF4/target.h
@@ -52,44 +52,32 @@
/*------------SENSORS--------------*/
// MPU interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_GYRO
-#define USE_ACC
-
-#if !defined(FF_FORTINIF4_REV03)
-#define MPU6000_CS_PIN SPI1_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI1
-
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
-
-#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-
-#define ICM20689_CS_PIN SPI1_NSS_PIN
-#define ICM20689_SPI_INSTANCE SPI1
-
+#define USE_GYRO_SPI_MPU6500
#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
-#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW180_DEG
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#if defined(FF_FORTINIF4_REV03)
+#define GYRO_1_CS_PIN PA4
+#else
+#define GYRO_1_CS_PIN PA8
#endif
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
-
-#define USE_GYRO_MPU6500
-#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG
-
-#define USE_ACC_MPU6500
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
+#define USE_ACC_SPI_ICM20689
+#define ACC_1_ALIGN CW180_DEG
+
/*---------------------------------*/
#if !defined(FF_FORTINIF4_REV03)
diff --git a/src/main/target/FF_PIKOBLX/target.h b/src/main/target/FF_PIKOBLX/target.h
index c370146840..20cd3b5119 100644
--- a/src/main/target/FF_PIKOBLX/target.h
+++ b/src/main/target/FF_PIKOBLX/target.h
@@ -45,20 +45,21 @@
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PA15
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA15
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
#define MPU6000_CS_GPIO GPIOB
-#define MPU6000_CS_PIN PB12
-#define MPU6000_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_VCP
#define USE_UART1
diff --git a/src/main/target/FF_PIKOF4/target.h b/src/main/target/FF_PIKOF4/target.h
index 16edb8ca13..cc6492ba0c 100644
--- a/src/main/target/FF_PIKOF4/target.h
+++ b/src/main/target/FF_PIKOF4/target.h
@@ -46,38 +46,29 @@
/*------------SENSORS--------------*/
// MPU interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#if defined(FF_PIKOF4OSD)
-#define MPU6000_CS_PIN PA15
-#define MPU6000_SPI_INSTANCE SPI3
-
-#define MPU6500_CS_PIN PA15
-#define MPU6500_SPI_INSTANCE SPI3
+#define GYRO_1_CS_PIN PA15
+#define GYRO_1_SPI_INSTANCE SPI3
#else
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#endif
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
-
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#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 ACC_1_ALIGN CW180_DEG
/*---------------------------------*/
#if defined(FF_PIKOF4OSD)
diff --git a/src/main/target/FISHDRONEF4/target.h b/src/main/target/FISHDRONEF4/target.h
index 6135985c8e..70dcf54f15 100644
--- a/src/main/target/FISHDRONEF4/target.h
+++ b/src/main/target/FISHDRONEF4/target.h
@@ -38,23 +38,24 @@
#define INVERTER_PIN_UART6 PC8
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
// *************** Gyro & ACC **********************
#define USE_SPI
#define USE_SPI_DEVICE_1
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
// *************** UART *****************************
#define USE_VCP
diff --git a/src/main/target/FOXEERF405/target.h b/src/main/target/FOXEERF405/target.h
index 8fa1caec5a..0052e9db5e 100644
--- a/src/main/target/FOXEERF405/target.h
+++ b/src/main/target/FOXEERF405/target.h
@@ -40,7 +40,8 @@
#define SPI1_MOSI_PIN PA7
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
@@ -55,14 +56,14 @@
#define USE_ACC_SPI_ICM20689
#define ACC_ICM20689_ALIGN CW90_DEG
//------MPU6000
-#define MPU6000_CS_PIN PB2
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PB2
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
//Baro & MAG-------------------------------
#define USE_I2C
diff --git a/src/main/target/FRSKYF3/target.h b/src/main/target/FRSKYF3/target.h
index 08057eedb3..7399db6ec6 100644
--- a/src/main/target/FRSKYF3/target.h
+++ b/src/main/target/FRSKYF3/target.h
@@ -53,29 +53,30 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPC13
#define USE_MPU_DATA_READY_SIGNAL
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU_INT, SDCardDetect
#define MPU_ADDRESS 0x69
#ifdef MYMPU6000
-#define MPU6000_SPI_INSTANCE SPI2
-#define MPU6000_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#else
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#endif
#define USE_VCP
diff --git a/src/main/target/FRSKYF4/target.h b/src/main/target/FRSKYF4/target.h
index 708f0732e8..1ea25c31c6 100644
--- a/src/main/target/FRSKYF4/target.h
+++ b/src/main/target/FRSKYF4/target.h
@@ -31,8 +31,8 @@
#define INVERTER_PIN_UART6 PC8
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6000
@@ -40,11 +40,12 @@
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
#define USE_BARO
diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h
index 3e2fbdeba0..b47db2d9fc 100644
--- a/src/main/target/FURYF3/target.h
+++ b/src/main/target/FURYF3/target.h
@@ -64,40 +64,28 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PA3
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA3
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define ICM20689_CS_PIN PA4
-#define ICM20689_SPI_INSTANCE SPI1
-
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO
-#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW180_DEG
-
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
-
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW90_DEG
+#define USE_GYRO_SPI_ICM20689
+// MPU6000 and ICM20689 are CW180 aligned.
+// MPU6500 is CW90 aligned, but can't handle this.
+// Must be configured after flashing.
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC
-#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW180_DEG
-
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW90_DEG
+#define USE_ACC_SPI_ICM20689
+#define ACC_1_ALIGN CW180_DEG
#define USE_SPI
#define USE_SPI_DEVICE_1
diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h
index 6a59a0a278..7a8b215e01 100644
--- a/src/main/target/FURYF4/target.h
+++ b/src/main/target/FURYF4/target.h
@@ -39,41 +39,24 @@
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
-#define ICM20689_CS_PIN PA4
-#define ICM20689_SPI_INSTANCE SPI1
-
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO
-#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW180_DEG
-
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
-#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG
+#define USE_GYRO_SPI_ICM20689
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC
-#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW180_DEG
-
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
+#define USE_ACC_SPI_ICM20689
+#define ACC_1_ALIGN CW180_DEG
#ifdef FURYF4OSD
#define USE_MAX7456
diff --git a/src/main/target/FURYF7/target.h b/src/main/target/FURYF7/target.h
index 572d489170..314dcfad96 100644
--- a/src/main/target/FURYF7/target.h
+++ b/src/main/target/FURYF7/target.h
@@ -32,19 +32,20 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
-#define ICM20689_CS_PIN PA4
-#define ICM20689_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO
#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC
#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
//#define USE_BARO
//#define USE_BARO_MS5611
diff --git a/src/main/target/IMPULSERCF3/target.h b/src/main/target/IMPULSERCF3/target.h
index fde4309fa4..e4bf0d25ed 100644
--- a/src/main/target/IMPULSERCF3/target.h
+++ b/src/main/target/IMPULSERCF3/target.h
@@ -50,17 +50,18 @@
#define BEEPER_PIN PC15
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#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 CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_FLASHFS
#define USE_FLASH_M25P16
@@ -93,8 +94,8 @@
#define FLASH_CS_PIN PB12
#define FLASH_SPI_INSTANCE SPI2
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI1
diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h
index 21c9a500e7..7e38242431 100644
--- a/src/main/target/IRCFUSIONF3/target.h
+++ b/src/main/target/IRCFUSIONF3/target.h
@@ -26,17 +26,18 @@
#define LED0_PIN PB3
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_BARO
#define USE_BARO_BMP085
diff --git a/src/main/target/ISHAPEDF3/target.h b/src/main/target/ISHAPEDF3/target.h
index ab379849b3..d159a560ad 100644
--- a/src/main/target/ISHAPEDF3/target.h
+++ b/src/main/target/ISHAPEDF3/target.h
@@ -31,7 +31,8 @@
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@@ -40,11 +41,9 @@
#define USE_GYRO
#define USE_GYRO_MPU6500
-//#define USE_GYRO_SPI_MPU6500
#define USE_ACC
#define USE_ACC_MPU6500
-//#define USE_ACC_SPI_MPU6500
#define USE_BARO
#define USE_BARO_BMP280
diff --git a/src/main/target/KAKUTEF4/target.h b/src/main/target/KAKUTEF4/target.h
index 59dabf4c86..5ba410f525 100644
--- a/src/main/target/KAKUTEF4/target.h
+++ b/src/main/target/KAKUTEF4/target.h
@@ -56,21 +56,22 @@
// ICM20689 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC5
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC5
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define ICM20689_CS_PIN PC4
-#define ICM20689_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#if defined(FLYWOOF405)
//------MPU6000
diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h
index 4c425980d6..156a81896d 100644
--- a/src/main/target/KAKUTEF7/target.h
+++ b/src/main/target/KAKUTEF7/target.h
@@ -31,26 +31,24 @@
#define BEEPER_PIN PD15
#define BEEPER_INVERTED
+//define camera control
+#define CAMERA_CONTROL_PIN PE13
+
#define USE_ACC
#define USE_GYRO
+#define USE_EXTI
// ICM-20689
#define USE_ACC_SPI_ICM20689
#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW270_DEG
-#define ACC_ICM20689_ALIGN CW270_DEG
-#define MPU_INT_EXTI PE1
-
-#define ICM20689_CS_PIN SPI4_NSS_PIN
-#define ICM20689_SPI_INSTANCE SPI4
-#define GYRO_1_CS_PIN ICM20689_CS_PIN
-#define GYRO_1_SPI_INSTANCE ICM20689_SPI_INSTANCE
-
-#define ACC_1_ALIGN ACC_ICM20689_ALIGN
-#define GYRO_1_ALIGN GYRO_ICM20689_ALIGN
+#define GYRO_1_CS_PIN SPI4_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI4
+#define GYRO_1_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PE1
#define USE_MPU_DATA_READY_SIGNAL
-#define USE_EXTI
#define USE_VCP
#define USE_USB_DETECT
@@ -173,4 +171,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 8
#define USED_TIMERS ( TIM_N(1) | TIM_N(5) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
-
diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h
index c043b4a755..39316ad431 100644
--- a/src/main/target/KISSFC/target.h
+++ b/src/main/target/KISSFC/target.h
@@ -36,19 +36,21 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PB2
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PB2
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
+
#ifdef KISSCC
#define USE_TARGET_CONFIG
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
#define TARGET_DEFAULT_MIXER MIXER_QUADX_1234
@@ -56,11 +58,11 @@
#else
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
#endif
#define USE_VCP
diff --git a/src/main/target/KISSFCV2F7/target.h b/src/main/target/KISSFCV2F7/target.h
index b50f8c03f8..bd5be3bfe8 100644
--- a/src/main/target/KISSFCV2F7/target.h
+++ b/src/main/target/KISSFCV2F7/target.h
@@ -34,16 +34,16 @@
#define BEEPER_PIN PC9
#define BEEPER_INVERTED
-#define MPU6000_CS_PIN PB12
-#define MPU6000_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
#define USE_SPI
diff --git a/src/main/target/KIWIF4/target.h b/src/main/target/KIWIF4/target.h
index 4a69c7d763..954c4b6bbe 100644
--- a/src/main/target/KIWIF4/target.h
+++ b/src/main/target/KIWIF4/target.h
@@ -49,21 +49,19 @@
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-
-#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
#if defined(KIWIF4) || defined(KIWIF4V2)
#define USE_MAX7456
diff --git a/src/main/target/KROOZX/target.h b/src/main/target/KROOZX/target.h
index 33018e08df..8c060753b3 100644
--- a/src/main/target/KROOZX/target.h
+++ b/src/main/target/KROOZX/target.h
@@ -39,21 +39,22 @@
#define INVERTER_PIN_UART1 PB13
#define INVERTER_PIN_UART6 PB12
-#define MPU6000_CS_PIN PB2
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PB2
+#define GYRO_1_SPI_INSTANCE SPI1
// MPU6000 interrupts
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PA4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA4
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/LUMBAF3/target.h b/src/main/target/LUMBAF3/target.h
index b618a2df07..72237ff93e 100644
--- a/src/main/target/LUMBAF3/target.h
+++ b/src/main/target/LUMBAF3/target.h
@@ -27,15 +27,16 @@
#define BEEPER_PIN PC15
#define USE_EXTI
-#define MPU_INT_EXTI PA3
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA3
#define USE_MPU_DATA_READY_SIGNAL
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define FLASH_CS_PIN PB12
#define FLASH_SPI_INSTANCE SPI2
@@ -45,11 +46,11 @@
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
#define USE_VCP
#define USE_UART1
diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h
index fba843d81c..95f23bb246 100644
--- a/src/main/target/LUX_RACE/target.h
+++ b/src/main/target/LUX_RACE/target.h
@@ -51,7 +51,8 @@
// MPU6500 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PA5
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA5
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@@ -92,31 +93,27 @@
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#endif
-#define MPU6000_CS_PIN SPI1_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI1
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO
#ifdef LUXV2_RACE
-#define USE_GYRO_MPU6000
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#else
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#endif
#define USE_ACC
#ifdef LUXV2_RACE
#define USE_ACC_MPU6000
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#else
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#endif
#define USE_VCP
diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h
index 8043d055d1..8e8a539d84 100644
--- a/src/main/target/MATEKF405/target.h
+++ b/src/main/target/MATEKF405/target.h
@@ -40,29 +40,28 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define MPU6000_CS_PIN PC2
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PC2
+#define GYRO_1_SPI_INSTANCE SPI1
-#define MPU6500_CS_PIN PC2
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PC2
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_EXTI
-#define MPU_INT_EXTI PC3
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC3
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
-
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW270_DEG
+//#define GYRO_1_ALIGN CW180_DEG // XXX MPU6500 align, must be configured after flashing
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
-
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW270_DEG
+//#define ACC_1_ALIGN CW180_DEG // XXX MPU6500 align, must be configured after flashing
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/MATEKF411/target.h b/src/main/target/MATEKF411/target.h
index 6c6581266d..bee368b113 100644
--- a/src/main/target/MATEKF411/target.h
+++ b/src/main/target/MATEKF411/target.h
@@ -38,27 +38,22 @@
#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 GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_EXTI
-#define MPU_INT_EXTI PA1
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA1
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define USE_GYRO_SPI_MPU6500
+#define GYRO_1_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 CW180_DEG
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
// *************** Baro **************************
#define USE_I2C
diff --git a/src/main/target/MATEKF411RX/target.h b/src/main/target/MATEKF411RX/target.h
index 7dde270664..bcbfdcd55c 100644
--- a/src/main/target/MATEKF411RX/target.h
+++ b/src/main/target/MATEKF411RX/target.h
@@ -37,19 +37,20 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_EXTI
-#define MPU_INT_EXTI PA1
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA1
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
// *************** SPI2 OSD *****************************
#define USE_SPI_DEVICE_2
diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h
index af2f59ccee..fd7fb112c5 100644
--- a/src/main/target/MATEKF722/target.h
+++ b/src/main/target/MATEKF722/target.h
@@ -41,29 +41,28 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define MPU6500_CS_PIN PC2
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PC2
+#define GYRO_1_SPI_INSTANCE SPI1
#define ICM20689_CS_PIN PC2
#define ICM20689_SPI_INSTANCE SPI1
#define USE_EXTI
-#define MPU_INT_EXTI PC3
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC3
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG
-
#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW180_DEG
+//#define GYRO_ICM20689_ALIGN CW90_DEG // XXX has to be post-flash configured
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
-
#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW180_DEG
+//#define ACC_ICM20689_ALIGN CW90_DEG // XXX has to be post-flash configured
// *************** Baro **************************
#define USE_I2C
diff --git a/src/main/target/MICROSCISKY/target.h b/src/main/target/MICROSCISKY/target.h
index a4f573e284..70f233f8b9 100644
--- a/src/main/target/MICROSCISKY/target.h
+++ b/src/main/target/MICROSCISKY/target.h
@@ -51,11 +51,11 @@
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_BARO
#define USE_BARO_MS5611
diff --git a/src/main/target/MIDELICF3/target.h b/src/main/target/MIDELICF3/target.h
index 094fb7524a..0c0f25ca73 100644
--- a/src/main/target/MIDELICF3/target.h
+++ b/src/main/target/MIDELICF3/target.h
@@ -38,14 +38,15 @@
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_EXTI
-#define MPU_INT_EXTI PA13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA13
#define USE_MPU_DATA_READY_SIGNAL
#define USE_VCP
diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h
index 034b571f92..3a2f32b4f9 100644
--- a/src/main/target/MOTOLAB/target.h
+++ b/src/main/target/MOTOLAB/target.h
@@ -33,7 +33,8 @@
// MPU6050 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PA15
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA15
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@@ -41,20 +42,16 @@
#define USE_ACC
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW180_DEG
-
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW180_DEG
-
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-#define MPU6000_CS_GPIO GPIOB
-#define MPU6000_CS_PIN PB12
-#define MPU6000_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
+
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_VCP
#define USE_UART1
diff --git a/src/main/target/MOTOLABF4/target.h b/src/main/target/MOTOLABF4/target.h
index d2a8004140..5a9b391feb 100644
--- a/src/main/target/MOTOLABF4/target.h
+++ b/src/main/target/MOTOLABF4/target.h
@@ -38,20 +38,21 @@
#define BEEPER_PIN PB4
#define BEEPER_INVERTED
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PC5
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC5
#define USE_MPU_DATA_READY_SIGNAL
//#define ENSURE_MPU_DATA_READY_IS_LOW
//#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
diff --git a/src/main/target/MULTIFLITEPICO/target.h b/src/main/target/MULTIFLITEPICO/target.h
index 418d567106..4ef533a892 100644
--- a/src/main/target/MULTIFLITEPICO/target.h
+++ b/src/main/target/MULTIFLITEPICO/target.h
@@ -31,17 +31,18 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
#define USE_BARO
#define USE_BARO_MS5611
diff --git a/src/main/target/NAZE/config.c b/src/main/target/NAZE/config.c
index 89266f32aa..479f4d4d7e 100644
--- a/src/main/target/NAZE/config.c
+++ b/src/main/target/NAZE/config.c
@@ -61,6 +61,8 @@ void targetConfiguration(void)
motorConfigMutable()->minthrottle = 1049;
+ gyroDeviceConfigMutable()->extiTag = selectMPUIntExtiConfigByHardwareRevision();
+
gyroConfigMutable()->gyro_hardware_lpf = GYRO_HARDWARE_LPF_1KHZ_SAMPLE;
gyroConfigMutable()->gyro_soft_lpf_hz = 100;
gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h
index d583e1d16f..6de8191c17 100644
--- a/src/main/target/NAZE/target.h
+++ b/src/main/target/NAZE/target.h
@@ -58,7 +58,8 @@
#define USE_EXTI
#define MAG_INT_EXTI PC14
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define MMA8451_INT_PIN PA5
#define USE_MPU_DATA_READY_SIGNAL
@@ -74,8 +75,8 @@
#define FLASH_CS_PIN NAZE_SPI_CS_PIN
#define FLASH_SPI_INSTANCE NAZE_SPI_INSTANCE
-#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
-#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
+#define GYRO_1_CS_PIN NAZE_SPI_CS_PIN
+#define GYRO_1_SPI_INSTANCE NAZE_SPI_INSTANCE
#define USE_FLASHFS
#define USE_FLASH_M25P16
@@ -86,9 +87,7 @@
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU3050_ALIGN CW0_DEG
-#define GYRO_MPU6050_ALIGN CW0_DEG
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_ACC
//#define USE_ACC_ADXL345
@@ -99,10 +98,9 @@
#define USE_ACC_SPI_MPU6500
//#define ACC_ADXL345_ALIGN CW270_DEG
-#define ACC_MPU6050_ALIGN CW0_DEG
//#define ACC_MMA8452_ALIGN CW90_DEG
//#define ACC_BMA280_ALIGN CW0_DEG
-#define ACC_MPU6500_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_BARO
#define USE_BARO_MS5611 // needed for Flip32 board
diff --git a/src/main/target/NAZE/target.mk b/src/main/target/NAZE/target.mk
index bbe55d1897..96cd0814a6 100644
--- a/src/main/target/NAZE/target.mk
+++ b/src/main/target/NAZE/target.mk
@@ -2,10 +2,6 @@ F1_TARGETS += $(TARGET)
FEATURES = ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro_legacy/accgyro_adxl345.c \
- drivers/accgyro_legacy/accgyro_bma280.c \
- drivers/accgyro_legacy/accgyro_l3g4200d.c \
- drivers/accgyro_legacy/accgyro_mma845x.c \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu3050.c \
drivers/accgyro/accgyro_mpu6050.c \
diff --git a/src/main/target/NERO/target.h b/src/main/target/NERO/target.h
index b2a531de06..2d72277ac6 100644
--- a/src/main/target/NERO/target.h
+++ b/src/main/target/NERO/target.h
@@ -37,22 +37,21 @@
// MPU6500 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PB2
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PB2
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
-#define MPU6500_CS_PIN PC4
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_GYRO
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_SDCARD
diff --git a/src/main/target/NOX/target.h b/src/main/target/NOX/target.h
index 45612a1324..f3885d3648 100644
--- a/src/main/target/NOX/target.h
+++ b/src/main/target/NOX/target.h
@@ -41,14 +41,12 @@
#define USE_GYRO_SPI_MPU6500
#define USE_GYRO_SPI_MPU6000
-#define MPU6500_CS_PIN PB12
-#define MPU6500_SPI_INSTANCE SPI2
-
-#define MPU6000_CS_PIN PB12
-#define MPU6000_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_EXTI
-#define MPU_INT_EXTI PA8
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA8
#define USE_MPU_DATA_READY_SIGNAL
#define USE_BARO
diff --git a/src/main/target/NUCLEOF446RE/target.h b/src/main/target/NUCLEOF446RE/target.h
index e55ee0763f..0b92c9e61a 100644
--- a/src/main/target/NUCLEOF446RE/target.h
+++ b/src/main/target/NUCLEOF446RE/target.h
@@ -51,11 +51,8 @@
#define USE_ACC_SPI_MPU6500
#define USE_ACC_SPI_MPU9250
-#define MPU9250_CS_PIN PB12
-#define MPU9250_SPI_INSTANCE SPI2
-
-#define MPU6500_CS_PIN PB12
-#define MPU6500_SPI_INSTANCE SPI2
+#define GYRO_1_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
#define USE_EXTI
diff --git a/src/main/target/NUCLEOF7/target.h b/src/main/target/NUCLEOF7/target.h
index a11dbc444a..9beb9a1c61 100644
--- a/src/main/target/NUCLEOF7/target.h
+++ b/src/main/target/NUCLEOF7/target.h
@@ -33,19 +33,23 @@
#define BEEPER_PIN PA0
#define BEEPER_INVERTED
+#undef USE_MULTI_GYRO // XXX Drop this if target has I2C configured
+
#define USE_ACC
#define USE_FAKE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_FAKE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
// MPU6050 interrupts
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PB15
+#define USE_EXTI
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PB15
#define USE_EXTI
#define USE_MAG
diff --git a/src/main/target/NUCLEOF722/target.h b/src/main/target/NUCLEOF722/target.h
index b917705097..2c12855172 100644
--- a/src/main/target/NUCLEOF722/target.h
+++ b/src/main/target/NUCLEOF722/target.h
@@ -33,19 +33,23 @@
//#define BEEPER_PIN PA0
//#define BEEPER_INVERTED
+#undef USE_MULTI_GYRO
+
#define USE_ACC
#define USE_FAKE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_FAKE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
// MPU6050 interrupts
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PB15
+#define USE_EXTI
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPB15
#define USE_EXTI
#define USE_MAG
diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h
index 80ed15b593..c73bf05687 100644
--- a/src/main/target/OMNIBUS/target.h
+++ b/src/main/target/OMNIBUS/target.h
@@ -56,19 +56,20 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU6000_SPI_INSTANCE SPI1
-#define MPU6000_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
#define BMP280_SPI_INSTANCE SPI1
#define BMP280_CS_PIN PA13
diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h
index f726e4fd89..7b497ad6e2 100644
--- a/src/main/target/OMNIBUSF4/target.h
+++ b/src/main/target/OMNIBUSF4/target.h
@@ -71,29 +71,33 @@
#define INVERTER_PIN_UART1 PC0 // DYS F4 Pro; Omnibus F4 AIO (1st gen) have a FIXED inverter on UART1
#endif
+#define USE_EXTI
+
+#define USE_MULTI_GYRO
+
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
// MPU6000 interrupts
-#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
#if defined(OMNIBUSF4SD)
-#define GYRO_MPU6000_ALIGN CW270_DEG
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#elif defined(XRACERF4) || defined(EXUAVF4PRO)
-#define GYRO_MPU6000_ALIGN CW90_DEG
-#define ACC_MPU6000_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
#else
-#define GYRO_MPU6000_ALIGN CW180_DEG
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
#endif
// Support for iFlight OMNIBUS F4 V3
@@ -102,12 +106,15 @@
#if defined (OMNIBUSF4SD) || defined(OMNIBUSF4BASE)
#define USE_ACC_SPI_MPU6500
#define USE_GYRO_SPI_MPU6500
-#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
#endif
+// Dummy defines
+#define GYRO_2_SPI_INSTANCE GYRO_1_SPI_INSTANCE
+#define GYRO_2_CS_PIN NONE
+#define GYRO_2_ALIGN ALIGN_DEFAULT
+#define GYRO_2_EXTI_PIN NONE
+#define ACC_2_ALIGN ALIGN_DEFAULT
+
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
diff --git a/src/main/target/OMNIBUSF4FW/target.h b/src/main/target/OMNIBUSF4FW/target.h
index 902fbcbcda..dfdd7633ae 100644
--- a/src/main/target/OMNIBUSF4FW/target.h
+++ b/src/main/target/OMNIBUSF4FW/target.h
@@ -68,7 +68,9 @@
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
+#define GYRO_2_EXTI_PIN NONE
#define USE_MPU_DATA_READY_SIGNAL
#define USE_MAG
diff --git a/src/main/target/OMNIBUSF7/target.h b/src/main/target/OMNIBUSF7/target.h
index 07ab4147e4..18a0471658 100644
--- a/src/main/target/OMNIBUSF7/target.h
+++ b/src/main/target/OMNIBUSF7/target.h
@@ -46,66 +46,48 @@
#define USE_GYRO
#define USE_DUAL_GYRO
// ICM-20608-G
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
//#define MPU_INT_EXTI PE8
// MPU6000
-#define USE_ACC_MPU6000
#define USE_ACC_SPI_MPU6000
-#define USE_GYRO_MPU6000
#define USE_GYRO_SPI_MPU6000
//#define MPU_INT_EXTI PD0
+// Provisioned, but not used
+#define GYRO_1_EXTI_PIN NONE
+#define GYRO_2_EXTI_PIN NONE
+
#if defined(OMNIBUSF7V2)
-#define MPU6000_CS_PIN SPI1_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI1
-#define MPU6500_CS_PIN SPI3_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI3
-#define GYRO_1_CS_PIN MPU6500_CS_PIN
-#define GYRO_2_CS_PIN MPU6000_CS_PIN
-#define GYRO_MPU6500_ALIGN CW90_DEG
-#define ACC_MPU6500_ALIGN CW90_DEG
-#define GYRO_MPU6000_ALIGN ALIGN_DEFAULT
-#define ACC_MPU6000_ALIGN ALIGN_DEFAULT
-#define ACC_1_ALIGN ACC_MPU6500_ALIGN
-#define ACC_2_ALIGN ACC_MPU6000_ALIGN
-#define GYRO_1_ALIGN GYRO_MPU6500_ALIGN
-#define GYRO_2_ALIGN GYRO_MPU6000_ALIGN
-#define GYRO_1_SPI_INSTANCE MPU6500_SPI_INSTANCE
-#define GYRO_2_SPI_INSTANCE MPU6000_SPI_INSTANCE
-#elif defined(FPVM_BETAFLIGHTF7)
-#define MPU6000_CS_PIN SPI1_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI1
-#define MPU6500_CS_PIN SPI3_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI3
-#define GYRO_1_CS_PIN MPU6000_CS_PIN
-#define GYRO_2_CS_PIN MPU6500_CS_PIN
-#define GYRO_MPU6500_ALIGN CW270_DEG
-#define ACC_MPU6500_ALIGN CW270_DEG
-#define GYRO_MPU6000_ALIGN CW90_DEG
-#define ACC_MPU6000_ALIGN CW90_DEG
-#define ACC_1_ALIGN ACC_MPU6000_ALIGN
-#define ACC_2_ALIGN ACC_MPU6500_ALIGN
-#define GYRO_1_ALIGN GYRO_MPU6000_ALIGN
-#define GYRO_2_ALIGN GYRO_MPU6500_ALIGN
-#define GYRO_1_SPI_INSTANCE MPU6000_SPI_INSTANCE
-#define GYRO_2_SPI_INSTANCE MPU6500_SPI_INSTANCE
-#else
-#define MPU6000_CS_PIN SPI3_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI3
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
-#define GYRO_1_CS_PIN MPU6000_CS_PIN
-#define GYRO_2_CS_PIN MPU6500_CS_PIN
-#define ACC_1_ALIGN ALIGN_DEFAULT
-#define ACC_2_ALIGN ALIGN_DEFAULT
-#define GYRO_1_ALIGN ALIGN_DEFAULT
+#define GYRO_1_SPI_INSTANCE SPI3
+#define GYRO_1_CS_PIN PA15
+#define GYRO_2_SPI_INSTANCE SPI1
+#define GYRO_2_CS_PIN PA4
+#define GYRO_1_ALIGN CW90_DEG
#define GYRO_2_ALIGN ALIGN_DEFAULT
-#define GYRO_1_SPI_INSTANCE MPU6000_SPI_INSTANCE
-#define GYRO_2_SPI_INSTANCE MPU6500_SPI_INSTANCE
+#define ACC_1_ALIGN CW90_DEG
+#define ACC_2_ALIGN ALIGN_DEFAULT
+
+#elif defined(FPVM_BETAFLIGHTF7)
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_2_SPI_INSTANCE SPI3
+#define GYRO_2_CS_PIN PA15
+#define GYRO_1_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
+#define GYRO_2_ALIGN CW270_DEG
+#define ACC_2_ALIGN CW270_DEG
+
+#else
+#define GYRO_1_SPI_INSTANCE SPI3
+#define GYRO_1_CS_PIN PA15
+#define GYRO_2_SPI_INSTANCE SPI1
+#define GYRO_2_CS_PIN PA4
+#define GYRO_1_ALIGN ALIGN_DEFAULT
+#define ACC_1_ALIGN ALIGN_DEFAULT
+#define GYRO_2_ALIGN ALIGN_DEFAULT
+#define ACC_2_ALIGN ALIGN_DEFAULT
#endif
// TODO: dual gyro support
diff --git a/src/main/target/OMNINXT/hardware_revision.c b/src/main/target/OMNINXT/hardware_revision.c
index ff4ff18ae1..860c98a0f4 100644
--- a/src/main/target/OMNINXT/hardware_revision.c
+++ b/src/main/target/OMNINXT/hardware_revision.c
@@ -296,6 +296,7 @@ void updateHardwareRevision(void)
// Empty
}
+// XXX Can be gone as sensors/gyro.c is not calling this anymore
ioTag_t selectMPUIntExtiConfigByHardwareRevision(void)
{
return IO_TAG_NONE;
diff --git a/src/main/target/OMNINXT/target.h b/src/main/target/OMNINXT/target.h
index 60f859de62..a6eedb1775 100644
--- a/src/main/target/OMNINXT/target.h
+++ b/src/main/target/OMNINXT/target.h
@@ -46,6 +46,10 @@
#define USE_ACC
#define USE_GYRO
+// MPU interrupts
+//#define USE_EXTI
+//#define USE_GYRO_EXTI
+//#define USE_MPU_DATA_READY_SIGNAL
// For debugging with NUC405RG
#define USE_FAKE_ACC
@@ -57,25 +61,20 @@
#define USE_ACC_SPI_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define USE_DUAL_GYRO
-
#define GYRO_1_SPI_INSTANCE SPI1
#define GYRO_1_CS_PIN PB12 // Onboard IMU
#define GYRO_1_ALIGN CW0_DEG
#define ACC_1_ALIGN CW0_DEG
+#define GYRO_1_EXTI_PIN NONE
#define GYRO_2_SPI_INSTANCE SPI1
#define GYRO_2_CS_PIN PA8 // External IMU
#define GYRO_2_ALIGN CW0_DEG
#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_EXTI_PIN NONE
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
-// MPU interrupts
-//#define USE_EXTI
-//#define MPU_INT_EXTI PC4
-//#define USE_MPU_DATA_READY_SIGNAL
-
#define USE_MAG
#define MAG_I2C_INSTANCE (I2CDEV_1)
#define USE_MAG_HMC5883
diff --git a/src/main/target/PYRODRONEF4/target.h b/src/main/target/PYRODRONEF4/target.h
index a0e4293bc1..f73e172191 100644
--- a/src/main/target/PYRODRONEF4/target.h
+++ b/src/main/target/PYRODRONEF4/target.h
@@ -30,7 +30,8 @@
#define INVERTER_PIN_UART1 PC3 // PC3 used as sBUS inverter select GPIO
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
// DEFINE SPI USAGE
@@ -38,14 +39,14 @@
#define USE_SPI_DEVICE_1
// MPU 6000
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU6000
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW0_DEG
-#define ACC_MPU6000_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
// DEFINE OSD
#define USE_SPI_DEVICE_2
diff --git a/src/main/target/RACEBASE/target.h b/src/main/target/RACEBASE/target.h
index 0116fdcf28..2bd37a377f 100644
--- a/src/main/target/RACEBASE/target.h
+++ b/src/main/target/RACEBASE/target.h
@@ -59,13 +59,14 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC5
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC5
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define MPU6000_CS_PIN PB5
-#define MPU6000_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB5
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
@@ -73,8 +74,8 @@
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
-#define GYRO_MPU6000_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
#define USE_UART1
#define USE_UART2
diff --git a/src/main/target/RCEXPLORERF3/target.h b/src/main/target/RCEXPLORERF3/target.h
index f2ff549e99..539d9acebf 100644
--- a/src/main/target/RCEXPLORERF3/target.h
+++ b/src/main/target/RCEXPLORERF3/target.h
@@ -46,19 +46,20 @@
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PA15
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPA15
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_ACC_SPI_MPU6000
-#define MPU6000_CS_PIN PB12
-#define MPU6000_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_ACC
-#define ACC_MPU6000_ALIGN CW180_DEG
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_BARO
#define USE_BARO_MS5611
diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h
index 1a4d07b958..5468e6cdf5 100644
--- a/src/main/target/REVO/target.h
+++ b/src/main/target/REVO/target.h
@@ -76,70 +76,68 @@
#define INVERTER_PIN_UART1 PC0
#endif
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
-
#define USE_GYRO
#define USE_ACC
#ifdef AIRBOTF4SD
-#undef MPU6000_CS_PIN
-#define MPU6000_CS_PIN PB13
-#define USE_GYRO_SPI_ICM20601
-#define ICM20601_CS_PIN PA4 // served through MPU6500 code
-#define ICM20601_SPI_INSTANCE SPI1
-#define USE_DUAL_GYRO
-#define GYRO_1_CS_PIN MPU6000_CS_PIN
-#define GYRO_2_CS_PIN ICM20601_CS_PIN
-#define GYRO_1_SPI_INSTANCE MPU6000_SPI_INSTANCE
-#define GYRO_2_SPI_INSTANCE ICM20601_SPI_INSTANCE
-#define ACC_1_ALIGN ALIGN_DEFAULT
-#define ACC_2_ALIGN ALIGN_DEFAULT
-#endif
-
-#if defined(SOULF4)
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_MPU6500
+#define USE_ACC_SPI_MPU6500
+
+#define GYRO_1_CS_PIN PB13
+#define GYRO_2_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_2_SPI_INSTANCE SPI1
+
+#define GYRO_1_ALIGN CW270_DEG
+#define GYRO_2_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
+#define ACC_2_ALIGN CW270_DEG
+
+#elif defined(SOULF4)
+
+#define USE_GYRO_SPI_MPU6000
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
+
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#elif defined(PODIUMF4)
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
+
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#else
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
-
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
-
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
-
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_1_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#endif
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
+#define GYRO_2_EXTI_PIN NONE
+
// Configure MAG and BARO unconditionally.
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/REVOLT/target.h b/src/main/target/REVOLT/target.h
index 129dc15889..9dc17d1db3 100644
--- a/src/main/target/REVOLT/target.h
+++ b/src/main/target/REVOLT/target.h
@@ -83,26 +83,21 @@
#define I2C1_SDA PB9
/*----------Gyro Config--------*/
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
-
#define USE_GYRO
#define USE_ACC
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW0_DEG
-
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+
+#define GYRO_1_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
/*----------Flash Config--------*/
diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h
index 9e034c91af..07030f3558 100644
--- a/src/main/target/REVONANO/target.h
+++ b/src/main/target/REVONANO/target.h
@@ -32,25 +32,24 @@
#define USE_BEEPER
#define BEEPER_PIN PC13
-#define MPU6500_CS_PIN PB12
-#define MPU6500_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_ACC
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_BARO
#define USE_BARO_MS5611
// MPU6500 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PA15
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA15
#define USE_MPU_DATA_READY_SIGNAL
#define USE_VCP
diff --git a/src/main/target/RG_SSD_F3/target.h b/src/main/target/RG_SSD_F3/target.h
index c58ab907ee..3163e2187f 100644
--- a/src/main/target/RG_SSD_F3/target.h
+++ b/src/main/target/RG_SSD_F3/target.h
@@ -34,8 +34,8 @@
#define BEEPER_PIN PA8
#define BEEPER_INVERTED
-#define MPU6000_CS_PIN PB2
-#define MPU6000_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB2
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_SPI
#define USE_SPI_DEVICE_1
@@ -54,15 +54,17 @@
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
+#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define USE_TARGET_CONFIG
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h
index 7f251a178d..4be149aa64 100644
--- a/src/main/target/SINGULARITY/target.h
+++ b/src/main/target/SINGULARITY/target.h
@@ -29,16 +29,17 @@
#define BEEPER_PIN PC15
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW0_DEG_FLIP
+#define GYRO_1_ALIGN CW0_DEG_FLIP
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW0_DEG_FLIP
+#define ACC_1_ALIGN CW0_DEG_FLIP
#define USE_FLASHFS
#define USE_FLASH_M25P16
diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h
index 0187d5e539..d6b85858d9 100644
--- a/src/main/target/SIRINFPV/target.h
+++ b/src/main/target/SIRINFPV/target.h
@@ -53,32 +53,31 @@
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PA8
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA8
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
// MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-#define GYRO_MPU6000_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
// MPU6500
-#define ACC_MPU6500_ALIGN CW90_DEG
-#define GYRO_MPU6500_ALIGN CW90_DEG
+//#define ACC_1_ALIGN CW90_DEG // XXX Must be post-flash configured
+//#define GYRO_1_ALIGN CW90_DEG // XXX Must be post-flash configured
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_VCP
#define USE_UART1
diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h
index eddbc4f519..fbc3fcc463 100644
--- a/src/main/target/SPARKY/target.h
+++ b/src/main/target/SPARKY/target.h
@@ -32,17 +32,18 @@
// MPU6050 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PA15
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PA15
#define USE_MPU_DATA_READY_SIGNAL
// MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component.
#define USE_GYRO
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_BARO
#define USE_BARO_MS5611
diff --git a/src/main/target/SPARKY2/target.h b/src/main/target/SPARKY2/target.h
index 2c073e0dfa..a8a598ba9e 100644
--- a/src/main/target/SPARKY2/target.h
+++ b/src/main/target/SPARKY2/target.h
@@ -38,21 +38,22 @@
// MPU9250 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC5
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC5
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define MPU9250_CS_PIN PC4
-#define MPU9250_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_MPU9250
-#define ACC_MPU9250_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_GYRO_SPI_MPU9250
-#define GYRO_MPU9250_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_MAG
//#define USE_MAG_HMC5883
diff --git a/src/main/target/SPEEDYBEEF4/target.h b/src/main/target/SPEEDYBEEF4/target.h
index 33c6193833..abf0ff9e95 100644
--- a/src/main/target/SPEEDYBEEF4/target.h
+++ b/src/main/target/SPEEDYBEEF4/target.h
@@ -40,11 +40,12 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define MPU6000_CS_PIN PB11
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PB11
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
diff --git a/src/main/target/SPEKTRUMF400/target.h b/src/main/target/SPEKTRUMF400/target.h
index c983c0bccd..f1c4af6c19 100644
--- a/src/main/target/SPEKTRUMF400/target.h
+++ b/src/main/target/SPEKTRUMF400/target.h
@@ -54,21 +54,19 @@
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
#define USE_GYRO_SPI_MPU9250
-#define GYRO_MPU9250_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6500
#define USE_ACC_SPI_MPU9250
-#define ACC_MPU9250_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
-#define MPU9250_CS_PIN PB12
-#define MPU9250_SPI_INSTANCE SPI2
-
-#define MPU6500_CS_PIN PB12
-#define MPU6500_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PB12
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h
index b3df5dabb5..7af7aac8d7 100644
--- a/src/main/target/SPRACINGF3/target.h
+++ b/src/main/target/SPRACINGF3/target.h
@@ -75,7 +75,8 @@
#endif
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@@ -88,19 +89,19 @@
#if defined(FLIP32F3OSD)
#define USE_GYRO_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#elif defined(ZCOREF3)
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
@@ -109,8 +110,8 @@
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
-#define MPU6500_CS_PIN PB9
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PB9
+#define GYRO_1_SPI_INSTANCE SPI1
#elif defined(IRCSYNERGYF3)
#define USE_GYRO_SPI_MPU6000
@@ -123,10 +124,10 @@
#define MPU6000_SPI_INSTANCE SPI2
#else
#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#endif
#if defined(FLIP32F3OSD)
diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h
index 3317f8cab7..5fda1f61df 100644
--- a/src/main/target/SPRACINGF3EVO/target.h
+++ b/src/main/target/SPRACINGF3EVO/target.h
@@ -81,7 +81,8 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@@ -94,8 +95,8 @@
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
-#define GYRO_MPU6500_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_BARO
#define USE_BARO_BMP280
@@ -171,8 +172,8 @@
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
-#define MPU6500_CS_PIN PB9
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PB9
+#define GYRO_1_SPI_INSTANCE SPI1
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h
index 7f402e276b..07434b5171 100644
--- a/src/main/target/SPRACINGF3MINI/target.h
+++ b/src/main/target/SPRACINGF3MINI/target.h
@@ -67,7 +67,8 @@
#define BEEPER_INVERTED
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@@ -77,20 +78,20 @@
#ifdef TINYBEEF3
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#else
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define USE_GYRO_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG
+#define GYRO_1_ALIGN CW180_DEG
#define USE_ACC_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
+#define ACC_1_ALIGN CW180_DEG
#define USE_BARO
#define USE_BARO_BMP280
@@ -163,8 +164,8 @@
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#else
#define USE_I2C
#define USE_I2C_DEVICE_1
diff --git a/src/main/target/SPRACINGF3NEO/target.h b/src/main/target/SPRACINGF3NEO/target.h
index cb736df928..68379e44ee 100644
--- a/src/main/target/SPRACINGF3NEO/target.h
+++ b/src/main/target/SPRACINGF3NEO/target.h
@@ -69,8 +69,8 @@
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_VCP
#define USE_UART1
@@ -155,8 +155,8 @@
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#define CURRENT_METER_SCALE_DEFAULT 300
diff --git a/src/main/target/SPRACINGF4EVO/target.h b/src/main/target/SPRACINGF4EVO/target.h
index da7b608f05..9c56a6b768 100644
--- a/src/main/target/SPRACINGF4EVO/target.h
+++ b/src/main/target/SPRACINGF4EVO/target.h
@@ -27,7 +27,7 @@
#define SPRACINGF4EVO_REV 2
#endif
#ifdef SPRACINGF4EVODG
-#define USE_DUAL_GYRO
+#define USE_MULTI_GYRO
#endif
#define USBD_PRODUCT_STRING "SP Racing F4 EVO"
@@ -42,7 +42,7 @@
#define USE_EXTI
#define GYRO_1_EXTI_PIN PC13
-#ifdef USE_DUAL_GYRO
+#ifdef USE_MULTI_GYRO
#define GYRO_2_EXTI_PIN PC5 // GYRO 2 / NC on prototype boards, but if it was it'd be here.
#endif
#define MPU_INT_EXTI
@@ -62,20 +62,14 @@
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#ifndef USE_DUAL_GYRO
-#define ACC_MPU6500_ALIGN CW0_DEG
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#ifndef USE_MULTI_GYRO
+#define ACC_1_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#else
-#define ACC_MPU6500_1_ALIGN CW0_DEG
-#define GYRO_MPU6500_1_ALIGN CW0_DEG
-
-#define ACC_MPU6500_2_ALIGN CW0_DEG
-#define GYRO_MPU6500_2_ALIGN CW0_DEG
-
-#define GYRO_1_ALIGN GYRO_MPU6500_1_ALIGN
-#define GYRO_2_ALIGN GYRO_MPU6500_2_ALIGN
-#define ACC_1_ALIGN ACC_MPU6500_1_ALIGN
-#define ACC_2_ALIGN ACC_MPU6500_2_ALIGN
+#define GYRO_1_ALIGN CW0_DEG
+#define GYRO_2_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
+#define ACC_2_ALIGN CW0_DEG
#endif
#define USE_BARO
@@ -167,9 +161,9 @@
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL 0
-#ifndef USE_DUAL_GYRO
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
+#ifndef USE_MULTI_GYRO
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#else
#define GYRO_1_CS_PIN SPI1_NSS_PIN
#define GYRO_1_SPI_INSTANCE SPI1
diff --git a/src/main/target/SPRACINGF4NEO/target.h b/src/main/target/SPRACINGF4NEO/target.h
index c97aa92d46..5a90344335 100644
--- a/src/main/target/SPRACINGF4NEO/target.h
+++ b/src/main/target/SPRACINGF4NEO/target.h
@@ -55,7 +55,8 @@
#endif
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@@ -69,8 +70,8 @@
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#define ACC_1_ALIGN CW0_DEG
+#define GYRO_1_ALIGN CW0_DEG
#define USE_BARO
#define USE_BARO_BMP280
@@ -175,8 +176,8 @@
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL 0
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN SPI1_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ADC
#define ADC_INSTANCE ADC1
diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h
index 323eab745f..28087c41a9 100644
--- a/src/main/target/STM32F3DISCOVERY/target.h
+++ b/src/main/target/STM32F3DISCOVERY/target.h
@@ -113,25 +113,21 @@
//#define USE_GYRO_L3G4200D
#define USE_GYRO_MPU3050
#define USE_GYRO_MPU6050
-#define USE_GYRO_SPI_MPU6000
-#define MPU6000_CS_PIN SPI2_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI2
-// Support the GY-91 MPU9250 dev board
#define USE_GYRO_MPU6500
+#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_SPI_MPU6500
-#define MPU6500_CS_PIN PC14
-#define MPU6500_SPI_INSTANCE SPI2
-#define GYRO_MPU6500_ALIGN CW270_DEG_FLIP
#define USE_GYRO_SPI_MPU9250
-#define MPU9250_CS_PIN SPI2_NSS_PIN
-#define MPU9250_SPI_INSTANCE SPI2
-// BMI160 gyro support
+#define GYRO_1_CS_PIN SPI2_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI2
+#define GYRO_1_ALIGN CW0_DEG
#define USE_ACCGYRO_BMI160
#ifdef USE_ACCGYRO_BMI160
#define BMI160_CS_PIN SPI2_NSS_PIN
#define BMI160_SPI_INSTANCE SPI2
#define BMI160_SPI_DIVISOR 16
-#define BMI160_INT_EXTI PC13
+#define USE_EXTI
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
#define USE_EXTI
#endif
@@ -149,7 +145,7 @@
#define USE_ACC_SPI_MPU6500
#define USE_ACC_MPU9250
#define USE_ACC_SPI_MPU9250
-#define ACC_MPU6500_ALIGN CW270_DEG_FLIP
+#define ACC_1_ALIGN CW270_DEG_FLIP
#define USE_BARO
#define USE_FAKE_BARO
diff --git a/src/main/target/STM32F3DISCOVERY/target.mk b/src/main/target/STM32F3DISCOVERY/target.mk
index a455a47c87..8886e68e18 100644
--- a/src/main/target/STM32F3DISCOVERY/target.mk
+++ b/src/main/target/STM32F3DISCOVERY/target.mk
@@ -11,14 +11,6 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu9250.c \
- drivers/accgyro_legacy/accgyro_adxl345.c \
- drivers/accgyro_legacy/accgyro_bma280.c \
- drivers/accgyro_legacy/accgyro_l3gd20.c \
- drivers/accgyro_legacy/accgyro_l3g4200d.c \
- drivers/accgyro_legacy/accgyro_lsm303dlhc.c \
- drivers/accgyro_legacy/accgyro_adxl345.c \
- drivers/accgyro_legacy/accgyro_bma280.c \
- drivers/accgyro_legacy/accgyro_mma845x.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_fake.c \
diff --git a/src/main/target/STM32F4DISCOVERY/target.h b/src/main/target/STM32F4DISCOVERY/target.h
index 269a7bb391..40e7c5b339 100644
--- a/src/main/target/STM32F4DISCOVERY/target.h
+++ b/src/main/target/STM32F4DISCOVERY/target.h
@@ -32,27 +32,26 @@
// MPU6500 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
-#define MPU6500_CS_PIN PC4
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
// ACC section -- start
#define USE_ACC
#define USE_FAKE_ACC
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG_FLIP
+#define ACC_1_ALIGN CW180_DEG_FLIP
// ACC section -- end
// GYRO section -- start
#define USE_GYRO
#define USE_FAKE_GYRO
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG_FLIP
+#define GYRO_1_ALIGN CW180_DEG_FLIP
// GYRO section -- end
#define USE_VCP
diff --git a/src/main/target/STM32F7X2/config/NERO.config b/src/main/target/STM32F7X2/config/NERO.config
index 0284786218..094a7caa3b 100644
--- a/src/main/target/STM32F7X2/config/NERO.config
+++ b/src/main/target/STM32F7X2/config/NERO.config
@@ -34,6 +34,12 @@ resource SPI_MOSI 3 C12
resource SPI_PREINIT_IPU 1 C04 // MPU6500
resource SPI_PREINIT_IPU 2 A15 // SDCARD
+# Acc/gyro
+resource gyro_cs 1 C4
+set gyro_1_bustype = SPI
+set gyro_1_spibus = 1
+#set gyro_1_hardware = MPU6500 # Not working (yet)
+
# Timers
# First four timers
# timer is zero origin
diff --git a/src/main/target/STM32F7X2/target.h b/src/main/target/STM32F7X2/target.h
index 51c74e26c8..9958bf942e 100644
--- a/src/main/target/STM32F7X2/target.h
+++ b/src/main/target/STM32F7X2/target.h
@@ -36,7 +36,8 @@
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
-#define MPU_INT_EXTI PB15 // XXX Should be gone
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPB15 // XXX Should be gone
#define USE_ACC
#define USE_GYRO
@@ -45,12 +46,19 @@
#define USE_GYRO_SPI_MPU6500
// Other USE_ACCs and USE_GYROs should follow
-// Should be gone
-#define MPU6500_CS_PIN PC4 // XXX Should be gone
-#define MPU6500_SPI_INSTANCE SPI1 // XXX Should be gone
-#define ACC_MPU6500_ALIGN CW0_DEG
-#define GYRO_MPU6500_ALIGN CW0_DEG
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN NONE
+#define GYRO_1_ALIGN ALIGN_DEFAULT
+#define ACC_1_ALIGN ALIGN_DEFAULT
+#define GYRO_1_EXTI_PIN NONE
+#define GYRO_2_SPI_INSTANCE SPI1
+#define GYRO_2_CS_PIN NONE
+#define GYRO_2_ALIGN ALIGN_DEFAULT
+#define ACC_2_ALIGN ALIGN_DEFAULT
+#define GYRO_2_EXTI_PIN NONE
+
+#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
#define USE_MAG
#define USE_MAG_HMC5883
diff --git a/src/main/target/TINYFISH/target.h b/src/main/target/TINYFISH/target.h
index a28b8edd81..9655d131da 100644
--- a/src/main/target/TINYFISH/target.h
+++ b/src/main/target/TINYFISH/target.h
@@ -34,19 +34,20 @@
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPC13
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU6000_SPI_INSTANCE SPI1
-#define MPU6000_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG_FLIP
+#define GYRO_1_ALIGN CW180_DEG_FLIP
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG_FLIP
+#define ACC_1_ALIGN CW180_DEG_FLIP
#if USB_VCP_ENABLED
diff --git a/src/main/target/VRRACE/target.h b/src/main/target/VRRACE/target.h
index 338d7bedd7..13643d4cb8 100644
--- a/src/main/target/VRRACE/target.h
+++ b/src/main/target/VRRACE/target.h
@@ -32,20 +32,21 @@
#define INVERTER_PIN_UART6 PD7
-#define MPU6500_CS_PIN PE10
-#define MPU6500_SPI_INSTANCE SPI2
+#define GYRO_1_CS_PIN PE10
+#define GYRO_1_SPI_INSTANCE SPI2
#define USE_ACC
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
// MPU6500 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PD10
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PINPD10
#define USE_MPU_DATA_READY_SIGNAL
/*
diff --git a/src/main/target/WORMFC/target.h b/src/main/target/WORMFC/target.h
index 9646f06156..d82cd8de12 100644
--- a/src/main/target/WORMFC/target.h
+++ b/src/main/target/WORMFC/target.h
@@ -36,25 +36,24 @@
// MPU6500 interrupt
#define USE_EXTI
-#define MPU_INT_EXTI PC4
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL
//#define DEBUG_MPU_DATA_READY_INTERRUPT
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
// ACC section -- start
#define USE_ACC
-#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG_FLIP
+#define ACC_1_ALIGN CW180_DEG_FLIP
// ACC section -- end
// GYRO section -- start
#define USE_GYRO
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG_FLIP
+#define GYRO_1_ALIGN CW180_DEG_FLIP
// GYRO section -- end
//BARO
diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h
index 767c5ce4a1..e026e390d3 100644
--- a/src/main/target/X_RACERSPI/target.h
+++ b/src/main/target/X_RACERSPI/target.h
@@ -32,21 +32,22 @@
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
-#define MPU6000_CS_PIN PA15
-#define MPU6000_SPI_INSTANCE SPI1
+#define GYRO_1_CS_PIN PA15
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_GYRO
#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
// MPU6000 interrupts
#define USE_EXTI
-#define MPU_INT_EXTI PC13
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC13
#define USE_MPU_DATA_READY_SIGNAL
diff --git a/src/main/target/YUPIF4/target.h b/src/main/target/YUPIF4/target.h
index 7aefe39dbe..6ca501481c 100644
--- a/src/main/target/YUPIF4/target.h
+++ b/src/main/target/YUPIF4/target.h
@@ -38,34 +38,21 @@
// Gyro interrupt
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
-#define MPU_INT_EXTI PC4
-
-//ICM 20689
-#define ICM20689_CS_PIN PA4
-#define ICM20689_SPI_INSTANCE SPI1
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
#define USE_ACC
#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW90_DEG
+#define USE_ACC_SPI_MPU6500
+#define ACC_1_ALIGN CW90_DEG
#define USE_GYRO
#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW90_DEG
-
-// MPU 6500
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
-
-#define USE_ACC
-#define USE_ACC_MPU6500
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW90_DEG
-
-#define USE_GYRO
-#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW90_DEG
+#define GYRO_1_ALIGN CW90_DEG
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_VCP
diff --git a/src/main/target/YUPIF7/target.h b/src/main/target/YUPIF7/target.h
index ba90a91cf6..58b54e25f5 100644
--- a/src/main/target/YUPIF7/target.h
+++ b/src/main/target/YUPIF7/target.h
@@ -39,22 +39,25 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define ICM20689_CS_PIN PA4
-#define ICM20689_SPI_INSTANCE SPI1
-
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PC4
-#define USE_GYRO
-#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW90_DEG
+// ICM 20689
+#define GYRO_1_CS_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
#define USE_ACC
#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW90_DEG
+#define ACC_1_ALIGN CW90_DEG
-// *************** UART ****************************
+#define USE_GYRO
+#define USE_GYRO_SPI_ICM20689
+#define GYRO_1_ALIGN CW90_DEG
+
+// Serial ports
#define USE_VCP
#define USE_USB_DETECT
#define USB_DETECT_PIN PA8
diff --git a/src/main/target/common_defaults_post.h b/src/main/target/common_defaults_post.h
index ce187dc5a7..c9328ade9c 100644
--- a/src/main/target/common_defaults_post.h
+++ b/src/main/target/common_defaults_post.h
@@ -224,3 +224,30 @@
#ifndef BINDPLUG_PIN
#define BINDPLUG_PIN NONE
#endif
+
+// F4 and F7 single gyro boards
+#if defined(USE_MULTI_GYRO) && !defined(GYRO_2_SPI_INSTANCE)
+#define GYRO_2_SPI_INSTANCE GYRO_1_SPI_INSTANCE
+#define GYRO_2_CS_PIN NONE
+#define GYRO_2_ALIGN ALIGN_DEFAULT
+#define GYRO_2_EXTI_PIN NONE
+#define ACC_2_ALIGN ALIGN_DEFAULT
+#endif
+
+#if !defined(GYRO_1_EXTI_PIN)
+#define GYRO_1_EXTI_PIN NONE
+#endif
+
+#if !defined(GYRO_1_ALIGN)
+#define GYRO_1_ALIGN ALIGN_DEFAULT
+#endif
+
+#if !defined(ACC_1_ALIGN)
+#define ACC_1_ALIGN ALIGN_DEFAULT
+#endif
+
+#if defined(MPU_ADDRESS)
+#define GYRO_I2C_ADDRESS MPU_ADDRESS
+#else
+#define GYRO_I2C_ADDRESS 0 // AUTO
+#endif
diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h
index a48f60f11f..50299d6039 100644
--- a/src/main/target/common_post.h
+++ b/src/main/target/common_post.h
@@ -167,3 +167,12 @@
#if defined(USE_GPS_RESCUE)
#define USE_GPS
#endif
+
+// Generate USE_SPI_GYRO or USE_I2C_GYRO
+#if defined(USE_GYRO_L3G4200D) || defined(USE_GYRO_L3GD20) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6000) || defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU6500)
+#define USE_I2C_GYRO
+#endif
+
+#if defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250)
+#define USE_SPI_GYRO
+#endif
diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h
index e1733608de..b9e910fd8d 100644
--- a/src/main/target/common_pre.h
+++ b/src/main/target/common_pre.h
@@ -210,6 +210,7 @@
#define USE_GYRO_DLPF_EXPERIMENTAL
#define USE_OSD
#define USE_OSD_OVER_MSP_DISPLAYPORT
+#define USE_MULTI_GYRO
#define USE_OSD_ADJUSTMENTS
#define USE_SENSOR_NAMES
#define USE_SERIALRX_JETIEXBUS
diff --git a/src/test/Makefile b/src/test/Makefile
index 565b05887b..105aa20455 100644
--- a/src/test/Makefile
+++ b/src/test/Makefile
@@ -218,7 +218,8 @@ sensor_gyro_unittest_SRC := \
$(USER_DIR)/common/maths.c \
$(USER_DIR)/drivers/accgyro/accgyro_fake.c \
$(USER_DIR)/drivers/accgyro/gyro_sync.c \
- $(USER_DIR)/pg/pg.c
+ $(USER_DIR)/pg/pg.c \
+ $(USER_DIR)/pg/gyrodev.c
telemetry_crsf_unittest_SRC := \
$(USER_DIR)/rx/crsf.c \