diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 3c3af17f7..8f2f49eef 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -218,6 +218,33 @@ void MPU_DATA_READY_EXTI_Handler(void) #endif } + //// Hack for cc3d +void EXTI3_IRQHandler(void) +{ + if (EXTI_GetITStatus(mpuIntExtiConfig->exti_line) == RESET) { + return; + } + + EXTI_ClearITPendingBit(mpuIntExtiConfig->exti_line); + + mpuDataReady = true; + +#ifdef DEBUG_MPU_DATA_READY_INTERRUPT + // Measure the delta in micro seconds between calls to the interrupt handler + static uint32_t lastCalledAt = 0; + static int32_t callDelta = 0; + + uint32_t now = micros(); + callDelta = now - lastCalledAt; + + //UNUSED(callDelta); + debug[0] = callDelta; + + lastCalledAt = now; +#endif +} + //// Hack for cc3d + void configureMPUDataReadyInterruptHandling(void) { #ifdef USE_MPU_DATA_READY_SIGNAL @@ -247,7 +274,9 @@ void configureMPUDataReadyInterruptHandling(void) } #endif +#ifndef CC3D registerExti15_10_CallbackHandler(MPU_DATA_READY_EXTI_Handler); +#endif EXTI_ClearITPendingBit(mpuIntExtiConfig->exti_line); diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index 31985246d..c02c77fcb 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -126,6 +126,8 @@ void mpu6000SpiGyroInit(uint16_t lpf) mpu6000AccAndGyroInit(); + mpuIntExtiInit(); + spiResetErrorCounter(MPU6000_SPI_INSTANCE); spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER); @@ -145,6 +147,7 @@ void mpu6000SpiGyroInit(uint16_t lpf) void mpu6000SpiAccInit(void) { + mpuIntExtiInit(); acc_1G = 512 * 8; } @@ -234,6 +237,13 @@ static void mpu6000AccAndGyroInit(void) { delayMicroseconds(1); spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock + delayMicroseconds(1); + + #ifdef USE_MPU_DATA_READY_SIGNAL + // Set MPU Data Ready Signal + mpu6000WriteRegister(MPU6000_INT_ENABLE , MPU_RF_DATA_RDY_EN); + delayMicroseconds(1); + #endif mpuSpi6000InitDone = true; } diff --git a/src/main/drivers/accgyro_spi_mpu6000.h b/src/main/drivers/accgyro_spi_mpu6000.h index 539c7b878..c1c361524 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.h +++ b/src/main/drivers/accgyro_spi_mpu6000.h @@ -44,10 +44,13 @@ #define MPU6000_WHO_AM_I_CONST (0x68) +// RF = Register Flag +#define MPU_RF_DATA_RDY_EN (1 << 0) + bool mpu6000SpiDetect(void); bool mpu6000SpiAccDetect(acc_t *acc); bool mpu6000SpiGyroDetect(gyro_t *gyro); bool mpu6000WriteRegister(uint8_t reg, uint8_t data); -bool mpu6000ReadRegister(uint8_t reg, uint8_t length, uint8_t *data); \ No newline at end of file +bool mpu6000ReadRegister(uint8_t reg, uint8_t length, uint8_t *data);