Skip to content

Commit

Permalink
Merge pull request betaflight#11585 from SteveCEvans/exti_use
Browse files Browse the repository at this point in the history
Remove USE_EXTI, USE_GYRO_EXTI and USE_MPU_DATA_READY_SIGNAL defines
  • Loading branch information
blckmn committed Jun 28, 2022
2 parents 71fea67 + 4f9f26e commit 671f8ab
Show file tree
Hide file tree
Showing 121 changed files with 143 additions and 483 deletions.
4 changes: 0 additions & 4 deletions src/main/cli/cli.c
Expand Up @@ -4804,14 +4804,12 @@ static void cliStatus(const char *cmdName, char *cmdline)
}
}
#ifdef USE_SPI
#ifdef USE_GYRO_EXTI
if (gyroActiveDev()->gyroModeSPI != GYRO_EXTI_NO_INT) {
cliPrintf(" locked");
}
if (gyroActiveDev()->gyroModeSPI == GYRO_EXTI_INT_DMA) {
cliPrintf(" dma");
}
#endif
if (spiGetExtDeviceCount(&gyroActiveDev()->dev) > 1) {
cliPrintf(" shared");
}
Expand Down Expand Up @@ -5201,9 +5199,7 @@ const cliResourceValue_t resourceTable[] = {
DEFS( OWNER_RX_SPI_EXPRESSLRS_BUSY, PG_RX_EXPRESSLRS_SPI_CONFIG, rxExpressLrsSpiConfig_t, busyIoTag ),
#endif
#endif
#ifdef USE_GYRO_EXTI
DEFW( OWNER_GYRO_EXTI, PG_GYRO_DEVICE_CONFIG, gyroDeviceConfig_t, extiTag, MAX_GYRODEV_COUNT ),
#endif
DEFW( OWNER_GYRO_CS, PG_GYRO_DEVICE_CONFIG, gyroDeviceConfig_t, csnTag, MAX_GYRODEV_COUNT ),
#ifdef USE_USB_DETECT
DEFS( OWNER_USB_DETECT, PG_USB_CONFIG, usbDev_t, detectPin ),
Expand Down
2 changes: 0 additions & 2 deletions src/main/drivers/accgyro/accgyro.h
Expand Up @@ -109,14 +109,12 @@ typedef struct gyroDev_s {
sensor_align_e gyroAlign;
gyroRateKHz_e gyroRateKHz;
gyroModeSPI_e gyroModeSPI;
#ifdef USE_GYRO_EXTI
uint32_t detectedEXTI;
uint32_t gyroLastEXTI;
uint32_t gyroSyncEXTI;
int32_t gyroShortPeriod;
int32_t gyroDmaMaxDuration;
busSegment_t segments[2];
#endif
volatile bool dataReady;
bool gyro_high_fsr;
uint8_t hardware_lpf;
Expand Down
12 changes: 2 additions & 10 deletions src/main/drivers/accgyro/accgyro_mpu.c
Expand Up @@ -115,7 +115,6 @@ static void mpu6050FindRevision(gyroDev_t *gyro)
/*
* Gyro interrupt service routine
*/
#ifdef USE_GYRO_EXTI
#ifdef USE_SPI_GYRO
// Called in ISR context
// Gyro read has just completed
Expand Down Expand Up @@ -181,7 +180,6 @@ static void mpuIntExtiInit(gyroDev_t *gyro)
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(mpuIntIO);
}
#endif // USE_GYRO_EXTI

bool mpuAccRead(accDev_t *acc)
{
Expand Down Expand Up @@ -270,7 +268,7 @@ bool mpuGyroReadSPI(gyroDev_t *gyro)
{
// Initialise the tx buffer to all 0xff
memset(gyro->dev.txBuf, 0xff, 16);
#ifdef USE_GYRO_EXTI

// Check that minimum number of interrupts have been detected

// We need some offset from the gyro interrupts to ensure sampling after the interrupt
Expand All @@ -289,9 +287,7 @@ bool mpuGyroReadSPI(gyroDev_t *gyro)
// Interrupts are present, but no DMA
gyro->gyroModeSPI = GYRO_EXTI_INT;
}
} else
#endif
{
} else {
gyro->gyroModeSPI = GYRO_EXTI_NO_INT;
}
break;
Expand Down Expand Up @@ -489,11 +485,7 @@ void mpuGyroInit(gyroDev_t *gyro)
{
gyro->accDataReg = MPU_RA_ACCEL_XOUT_H;
gyro->gyroDataReg = MPU_RA_GYRO_XOUT_H;
#ifdef USE_GYRO_EXTI
mpuIntExtiInit(gyro);
#else
UNUSED(gyro);
#endif
}

uint8_t mpuGyroDLPF(gyroDev_t *gyro)
Expand Down
4 changes: 1 addition & 3 deletions src/main/drivers/accgyro/accgyro_mpu6050.c
Expand Up @@ -96,9 +96,7 @@ static void mpu6050GyroInit(gyroDev_t *gyro)
busWriteRegister(dev, MPU_RA_INT_PIN_CFG,
0 << 7 | 0 << 6 | 0 << 5 | 0 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_PIN_CFG -- INT_LEVEL_HIGH, INT_OPEN_DIS, LATCH_INT_DIS, INT_RD_CLEAR_DIS, FSYNC_INT_LEVEL_HIGH, FSYNC_INT_DIS, I2C_BYPASS_EN, CLOCK_DIS

#ifdef USE_MPU_DATA_READY_SIGNAL
busWriteRegister(dev, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
#endif
busWriteRegister(&gyro->dev, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
}

bool mpu6050GyroDetect(gyroDev_t *gyro)
Expand Down
4 changes: 1 addition & 3 deletions src/main/drivers/accgyro/accgyro_mpu6500.c
Expand Up @@ -91,9 +91,7 @@ void mpu6500GyroInit(gyroDev_t *gyro)
#endif
delay(15);

#ifdef USE_MPU_DATA_READY_SIGNAL
busWriteRegister(dev, MPU_RA_INT_ENABLE, MPU6500_BIT_RAW_RDY_EN); // RAW_RDY_EN interrupt enable
#endif
busWriteRegister(&gyro->dev, MPU_RA_INT_ENABLE, MPU6500_BIT_RAW_RDY_EN); // RAW_RDY_EN interrupt enable
delay(15);
}

Expand Down
61 changes: 26 additions & 35 deletions src/main/drivers/accgyro/accgyro_spi_bmi160.c
Expand Up @@ -120,8 +120,6 @@ uint8_t bmi160Detect(const extDevice_t *dev)

BMI160Detected = true;

spiSetClkDivisor(dev, spiCalculateDivider(BMI160_MAX_SPI_CLK_HZ));

return BMI_160_SPI;
}

Expand Down Expand Up @@ -260,7 +258,6 @@ static int32_t BMI160_do_foc(const extDevice_t *dev)

extiCallbackRec_t bmi160IntCallbackRec;

#ifdef USE_GYRO_EXTI
// Called in ISR context
// Gyro read has just completed
busStatus_e bmi160Intcallback(uint32_t arg)
Expand All @@ -280,14 +277,16 @@ busStatus_e bmi160Intcallback(uint32_t arg)
void bmi160ExtiHandler(extiCallbackRec_t *cb)
{
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
extDevice_t *dev = &gyro->dev;

// Ideally we'd use a timer to capture such information, but unfortunately the port used for EXTI interrupt does
// not have an associated timer
uint32_t nowCycles = getCycleCounter();
gyro->gyroSyncEXTI = gyro->gyroLastEXTI + gyro->gyroDmaMaxDuration;
gyro->gyroLastEXTI = nowCycles;

if (gyro->gyroModeSPI == GYRO_EXTI_INT_DMA) {
spiSequence(&gyro->dev, gyro->segments);
spiSequence(dev, gyro->segments);
}

gyro->detectedEXTI++;
Expand All @@ -307,35 +306,29 @@ static void bmi160IntExtiInit(gyroDev_t *gyro)
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(mpuIntIO);
}
#else
void bmi160ExtiHandler(extiCallbackRec_t *cb)
{
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
gyro->dataReady = true;
}
#endif

static bool bmi160AccRead(accDev_t *acc)
{
extDevice_t *dev = &acc->gyro->dev;
switch (acc->gyro->gyroModeSPI) {
case GYRO_EXTI_INT:
case GYRO_EXTI_NO_INT:
{
acc->gyro->dev.txBuf[0] = BMI160_REG_ACC_DATA_X_LSB | 0x80;
dev->txBuf[0] = BMI160_REG_ACC_DATA_X_LSB | 0x80;

busSegment_t segments[] = {
{.u.buffers = {NULL, NULL}, 7, true, NULL},
{.u.link = {NULL, NULL}, 0, true, NULL},
};
segments[0].u.buffers.txData = &acc->gyro->dev.txBuf[1];
segments[0].u.buffers.rxData = &acc->gyro->dev.rxBuf[1];
segments[0].u.buffers.txData = &dev->txBuf[1];
segments[0].u.buffers.rxData = &dev->rxBuf[1];

spiSequence(&acc->gyro->dev, &segments[0]);

// Wait for completion
spiWait(&acc->gyro->dev);

uint16_t *accData = (uint16_t *)acc->gyro->dev.rxBuf;
uint16_t *accData = (uint16_t *)dev->rxBuf;
acc->ADCRaw[X] = accData[1];
acc->ADCRaw[Y] = accData[2];
acc->ADCRaw[Z] = accData[3];
Expand All @@ -348,7 +341,7 @@ static bool bmi160AccRead(accDev_t *acc)
// up an old value.

// This data was read from the gyro, which is the same SPI device as the acc
uint16_t *accData = (uint16_t *)acc->gyro->dev.rxBuf;
uint16_t *accData = (uint16_t *)dev->rxBuf;
acc->ADCRaw[X] = accData[4];
acc->ADCRaw[Y] = accData[5];
acc->ADCRaw[Z] = accData[6];
Expand All @@ -366,35 +359,33 @@ static bool bmi160AccRead(accDev_t *acc)

static bool bmi160GyroRead(gyroDev_t *gyro)
{
uint16_t *gyroData = (uint16_t *)gyro->dev.rxBuf;
extDevice_t *dev = &gyro->dev;
uint16_t *gyroData = (uint16_t *)dev->rxBuf;
switch (gyro->gyroModeSPI) {
case GYRO_EXTI_INIT:
{
// Initialise the tx buffer to all 0x00
memset(gyro->dev.txBuf, 0x00, 14);
#ifdef USE_GYRO_EXTI
memset(dev->txBuf, 0x00, 14);
// Check that minimum number of interrupts have been detected

// We need some offset from the gyro interrupts to ensure sampling after the interrupt
gyro->gyroDmaMaxDuration = 5;
// Using DMA for gyro access upsets the scheduler on the F4
if (gyro->detectedEXTI > GYRO_EXTI_DETECT_THRESHOLD) {
if (spiUseDMA(&gyro->dev)) {
gyro->dev.callbackArg = (uint32_t)gyro;
gyro->dev.txBuf[1] = BMI160_REG_GYR_DATA_X_LSB | 0x80;
if (spiUseDMA(dev)) {
dev->callbackArg = (uint32_t)gyro;
dev->txBuf[1] = BMI160_REG_GYR_DATA_X_LSB | 0x80;
gyro->segments[0].len = 14;
gyro->segments[0].callback = bmi160Intcallback;
gyro->segments[0].u.buffers.txData = &gyro->dev.txBuf[1];
gyro->segments[0].u.buffers.rxData = &gyro->dev.rxBuf[1];
gyro->segments[0].u.buffers.txData = dev.txBuf[1];
gyro->segments[0].u.buffers.rxData = dev.rxBuf[1];
gyro->segments[0].negateCS = true;
gyro->gyroModeSPI = GYRO_EXTI_INT_DMA;
} else {
// Interrupts are present, but no DMA
gyro->gyroModeSPI = GYRO_EXTI_INT;
}
} else
#endif
{
} else {
gyro->gyroModeSPI = GYRO_EXTI_NO_INT;
}
break;
Expand All @@ -403,19 +394,19 @@ static bool bmi160GyroRead(gyroDev_t *gyro)
case GYRO_EXTI_INT:
case GYRO_EXTI_NO_INT:
{
gyro->dev.txBuf[1] = BMI160_REG_GYR_DATA_X_LSB | 0x80;
dev->txBuf[1] = BMI160_REG_GYR_DATA_X_LSB | 0x80;

busSegment_t segments[] = {
{.u.buffers = {NULL, NULL}, 7, true, NULL},
{.u.link = {NULL, NULL}, 0, true, NULL},
};
segments[0].u.buffers.txData = &gyro->dev.txBuf[1];
segments[0].u.buffers.rxData = &gyro->dev.rxBuf[1];
segments[0].u.buffers.txData = dev.txBuf[1];
segments[0].u.buffers.rxData = dev.rxBuf[1];

spiSequence(&gyro->dev, &segments[0]);
spiSequence(dev, &segments[0]);

// Wait for completion
spiWait(&gyro->dev);
spiWait(dev);

// Fall through
FALLTHROUGH;
Expand All @@ -441,10 +432,10 @@ static bool bmi160GyroRead(gyroDev_t *gyro)

void bmi160SpiGyroInit(gyroDev_t *gyro)
{
BMI160_Init(&gyro->dev);
#if defined(USE_GYRO_EXTI)
extDevice_t *dev = &gyro->dev;

BMI160_Init(dev);
bmi160IntExtiInit(gyro);
#endif

spiSetClkDivisor(dev, spiCalculateDivider(BMI160_MAX_SPI_CLK_HZ));
}
Expand Down

0 comments on commit 671f8ab

Please sign in to comment.