diff --git a/src/main/drivers/accgyro.h b/src/main/drivers/accgyro.h index 9dbd6f6dd2..c9d23dac3e 100644 --- a/src/main/drivers/accgyro.h +++ b/src/main/drivers/accgyro.h @@ -18,6 +18,7 @@ #pragma once #include "common/axis.h" +#include "drivers/exti.h" #include "drivers/sensor.h" #ifndef MPU_I2C_INSTANCE @@ -35,9 +36,10 @@ typedef struct gyroDev_s { sensorGyroInitFuncPtr init; // initialize function - sensorGyroReadFuncPtr read; // read 3 axis data function + sensorGyroReadFuncPtr read; // read 3 axis data function sensorReadFuncPtr temperature; // read temperature if available sensorGyroInterruptStatusFuncPtr intStatus; + extiCallbackRec_t exti; float scale; // scalefactor volatile bool dataReady; uint16_t lpf; @@ -46,7 +48,7 @@ typedef struct gyroDev_s { } gyroDev_t; typedef struct accDev_s { - sensorAccInitFuncPtr init; // initialize function + sensorAccInitFuncPtr init; // initialize function sensorReadFuncPtr read; // read 3 axis data function uint16_t acc_1G; char revisionCode; // a revision code for the sensor, if known diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 7c87b8fddd..77ac0b8c2c 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -221,21 +221,13 @@ static void mpu6050FindRevision(void) } } -typedef struct mpuIntRec_s { - extiCallbackRec_t exti; - gyroDev_t *gyro; -} mpuIntRec_t; - -mpuIntRec_t mpuIntRec; - /* * Gyro interrupt service routine */ #if defined(MPU_INT_EXTI) static void mpuIntExtiHandler(extiCallbackRec_t *cb) { - mpuIntRec_t *rec = container_of(cb, mpuIntRec_t, exti); - gyroDev_t *gyro = rec->gyro; + gyroDev_t *gyro = container_of(cb, gyroDev_t, exti); gyro->dataReady = true; #ifdef DEBUG_MPU_DATA_READY_INTERRUPT @@ -250,7 +242,6 @@ static void mpuIntExtiHandler(extiCallbackRec_t *cb) static void mpuIntExtiInit(gyroDev_t *gyro) { - mpuIntRec.gyro = gyro; #if defined(MPU_INT_EXTI) static bool mpuExtiInitDone = false; @@ -269,19 +260,21 @@ static void mpuIntExtiInit(gyroDev_t *gyro) #if defined (STM32F7) IOInit(mpuIntIO, OWNER_MPU_EXTI, 0); - EXTIHandlerInit(&mpuIntRec.exti, mpuIntExtiHandler); - EXTIConfig(mpuIntIO, &mpuIntRec.exti, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ? + 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); IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? - EXTIHandlerInit(&mpuIntRec.exti, mpuIntExtiHandler); - EXTIConfig(mpuIntIO, &mpuIntRec.exti, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); + EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler); + EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); EXTIEnable(mpuIntIO, true); #endif mpuExtiInitDone = true; +#else + UNUSED(gyro); #endif } diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 691597a5b6..cd033cdcf3 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -39,12 +39,13 @@ #include "drivers/accgyro_mpu6500.h" #include "drivers/accgyro_l3gd20.h" #include "drivers/accgyro_lsm303dlhc.h" -#include "drivers/bus_spi.h" #include "drivers/accgyro_spi_icm20689.h" #include "drivers/accgyro_spi_mpu6000.h" #include "drivers/accgyro_spi_mpu6500.h" #include "drivers/accgyro_spi_mpu9250.h" +#include "drivers/bus_spi.h" #include "drivers/gyro_sync.h" +#include "drivers/io.h" #include "drivers/system.h" #include "fc/runtime_config.h" @@ -56,6 +57,10 @@ #include "sensors/boardalignment.h" #include "sensors/gyro.h" +#ifdef USE_HARDWARE_REVISION_DETECTION +#include "hardware_revision.h" +#endif + gyro_t gyro; // gyro access functions static int32_t gyroADC[XYZ_AXIS_COUNT]; @@ -71,8 +76,25 @@ static void *notchFilter1[3]; static filterApplyFnPtr notchFilter2ApplyFn; static void *notchFilter2[3]; +static const extiConfig_t *selectMPUIntExtiConfig(void) +{ +#if defined(MPU_INT_EXTI) + static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) }; + return &mpuIntExtiConfig; +#elif defined(USE_HARDWARE_REVISION_DETECTION) + return selectMPUIntExtiConfigByHardwareRevision(); +#else + return NULL; +#endif +} + bool gyroDetect(gyroDev_t *dev) { +#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_ICM20689) + const extiConfig_t *extiConfig = selectMPUIntExtiConfig(); + mpuDetect(extiConfig); +#endif + gyroSensor_e gyroHardware = GYRO_DEFAULT; dev->gyroAlign = ALIGN_DEFAULT; diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 341ca113eb..4075e2bdd0 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -20,14 +20,12 @@ #include "platform.h" -#include "build/build_config.h" - #include "common/axis.h" +#include "common/utils.h" #include "config/feature.h" #include "drivers/accgyro_mpu.h" -#include "drivers/io.h" #include "drivers/system.h" #include "drivers/exti.h" #include "drivers/sensor.h" @@ -55,18 +53,6 @@ uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE }; -const extiConfig_t *selectMPUIntExtiConfig(void) -{ -#if defined(MPU_INT_EXTI) - static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) }; - return &mpuIntExtiConfig; -#elif defined(USE_HARDWARE_REVISION_DETECTION) - return selectMPUIntExtiConfigByHardwareRevision(); -#else - return NULL; -#endif -} - #ifdef SONAR static bool sonarDetect(void) { @@ -86,15 +72,6 @@ bool sensorsAutodetect(const gyroConfig_t *gyroConfig, const barometerConfig_t *barometerConfig, const sonarConfig_t *sonarConfig) { - -#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_ICM20689) - - const extiConfig_t *extiConfig = selectMPUIntExtiConfig(); - - mpuDetectionResult_t *mpuDetectionResult = mpuDetect(extiConfig); - UNUSED(mpuDetectionResult); -#endif - memset(&gyro, 0, sizeof(gyro)); if (!gyroDetect(&gyro.dev)) { return false;