hack for cc3d interrupt

This commit is contained in:
henn1001 2015-10-07 21:17:12 +02:00
parent 3f10c0c184
commit dbcfa5dc43
3 changed files with 43 additions and 1 deletions

View File

@ -218,6 +218,33 @@ void MPU_DATA_READY_EXTI_Handler(void)
#endif #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) void configureMPUDataReadyInterruptHandling(void)
{ {
#ifdef USE_MPU_DATA_READY_SIGNAL #ifdef USE_MPU_DATA_READY_SIGNAL
@ -247,7 +274,9 @@ void configureMPUDataReadyInterruptHandling(void)
} }
#endif #endif
#ifndef CC3D
registerExti15_10_CallbackHandler(MPU_DATA_READY_EXTI_Handler); registerExti15_10_CallbackHandler(MPU_DATA_READY_EXTI_Handler);
#endif
EXTI_ClearITPendingBit(mpuIntExtiConfig->exti_line); EXTI_ClearITPendingBit(mpuIntExtiConfig->exti_line);

View File

@ -126,6 +126,8 @@ void mpu6000SpiGyroInit(uint16_t lpf)
mpu6000AccAndGyroInit(); mpu6000AccAndGyroInit();
mpuIntExtiInit();
spiResetErrorCounter(MPU6000_SPI_INSTANCE); spiResetErrorCounter(MPU6000_SPI_INSTANCE);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER); spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
@ -145,6 +147,7 @@ void mpu6000SpiGyroInit(uint16_t lpf)
void mpu6000SpiAccInit(void) void mpu6000SpiAccInit(void)
{ {
mpuIntExtiInit();
acc_1G = 512 * 8; acc_1G = 512 * 8;
} }
@ -234,6 +237,13 @@ static void mpu6000AccAndGyroInit(void) {
delayMicroseconds(1); delayMicroseconds(1);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock 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; mpuSpi6000InitDone = true;
} }

View File

@ -44,6 +44,9 @@
#define MPU6000_WHO_AM_I_CONST (0x68) #define MPU6000_WHO_AM_I_CONST (0x68)
// RF = Register Flag
#define MPU_RF_DATA_RDY_EN (1 << 0)
bool mpu6000SpiDetect(void); bool mpu6000SpiDetect(void);
bool mpu6000SpiAccDetect(acc_t *acc); bool mpu6000SpiAccDetect(acc_t *acc);