1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 12:55:19 +03:00

Merge pull request #10997 from SteveCEvans/dual_gyro

This commit is contained in:
Michael Keller 2021-10-06 08:16:26 +13:00 committed by GitHub
commit 0b5a428ba1
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
10 changed files with 114 additions and 45 deletions

View file

@ -112,6 +112,7 @@ typedef struct gyroDev_s {
uint32_t gyroSyncEXTI; uint32_t gyroSyncEXTI;
int32_t gyroShortPeriod; int32_t gyroShortPeriod;
int32_t gyroDmaMaxDuration; int32_t gyroDmaMaxDuration;
busSegment_t segments[2];
#endif #endif
volatile bool dataReady; volatile bool dataReady;
bool gyro_high_fsr; bool gyro_high_fsr;

View file

@ -129,11 +129,6 @@ busStatus_e mpuIntcallback(uint32_t arg)
static void mpuIntExtiHandler(extiCallbackRec_t *cb) static void mpuIntExtiHandler(extiCallbackRec_t *cb)
{ {
// Non-blocking, so this needs to be static
static busSegment_t segments[] = {
{NULL, NULL, 15, true, mpuIntcallback},
{NULL, NULL, 0, true, NULL},
};
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti); gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
// Ideally we'd use a time to capture such information, but unfortunately the port used for EXTI interrupt does // Ideally we'd use a time to capture such information, but unfortunately the port used for EXTI interrupt does
@ -147,12 +142,7 @@ static void mpuIntExtiHandler(extiCallbackRec_t *cb)
gyro->gyroLastEXTI = nowCycles; gyro->gyroLastEXTI = nowCycles;
if (gyro->gyroModeSPI == GYRO_EXTI_INT_DMA) { if (gyro->gyroModeSPI == GYRO_EXTI_INT_DMA) {
segments[0].txData = gyro->dev.txBuf;; spiSequence(&gyro->dev, gyro->segments);
segments[0].rxData = &gyro->dev.rxBuf[1];
if (!spiIsBusy(&gyro->dev)) {
spiSequence(&gyro->dev, &segments[0]);
}
} }
gyro->detectedEXTI++; gyro->detectedEXTI++;
@ -287,9 +277,14 @@ bool mpuGyroReadSPI(gyroDev_t *gyro)
if (spiUseDMA(&gyro->dev)) { if (spiUseDMA(&gyro->dev)) {
// Indicate that the bus on which this device resides may initiate DMA transfers from interrupt context // Indicate that the bus on which this device resides may initiate DMA transfers from interrupt context
spiSetAtomicWait(&gyro->dev); spiSetAtomicWait(&gyro->dev);
gyro->gyroModeSPI = GYRO_EXTI_INT_DMA;
gyro->dev.callbackArg = (uint32_t)gyro; gyro->dev.callbackArg = (uint32_t)gyro;
gyro->dev.txBuf[0] = MPU_RA_ACCEL_XOUT_H | 0x80; gyro->dev.txBuf[0] = MPU_RA_ACCEL_XOUT_H | 0x80;
gyro->segments[0].len = 15;
gyro->segments[0].callback = mpuIntcallback;
gyro->segments[0].txData = gyro->dev.txBuf;
gyro->segments[0].rxData = &gyro->dev.rxBuf[1];
gyro->segments[0].negateCS = true;
gyro->gyroModeSPI = GYRO_EXTI_INT_DMA;
} else { } else {
// Interrupts are present, but no DMA // Interrupts are present, but no DMA
gyro->gyroModeSPI = GYRO_EXTI_INT; gyro->gyroModeSPI = GYRO_EXTI_INT;

View file

@ -82,7 +82,13 @@ typedef struct busDevice_s {
* is defined by a segment, with optional callback after each is completed * is defined by a segment, with optional callback after each is completed
*/ */
typedef struct busSegment_s { typedef struct busSegment_s {
/* Note that txData may point to the transmit buffer, or in the case of the final segment to
* a const extDevice_t * structure to link to the next transfer.
*/
uint8_t *txData; uint8_t *txData;
/* Note that rxData may point to the receive buffer, or in the case of the final segment to
* a busSegment_t * structure to link to the next transfer.
*/
uint8_t *rxData; uint8_t *rxData;
int len; int len;
bool negateCS; // Should CS be negated at the end of this segment bool negateCS; // Should CS be negated at the end of this segment

View file

@ -137,7 +137,7 @@ bool spiInit(SPIDevice device)
// Return true if DMA engine is busy // Return true if DMA engine is busy
bool spiIsBusy(const extDevice_t *dev) bool spiIsBusy(const extDevice_t *dev)
{ {
return (dev->bus->curSegment != (busSegment_t *)NULL); return (dev->bus->curSegment != (busSegment_t *)BUS_SPI_FREE);
} }
// Indicate that the bus on which this device resides may initiate DMA transfers from interrupt context // Indicate that the bus on which this device resides may initiate DMA transfers from interrupt context
@ -156,15 +156,15 @@ void spiWaitClaim(const extDevice_t *dev)
if (dev->bus->useAtomicWait) { if (dev->bus->useAtomicWait) {
// Prevent race condition where the bus appears free, but a gyro interrupt starts a transfer // Prevent race condition where the bus appears free, but a gyro interrupt starts a transfer
do { do {
ATOMIC_BLOCK(NVIC_PRIO_MPU_INT_EXTI) { ATOMIC_BLOCK(NVIC_PRIO_MAX) {
if (dev->bus->curSegment == (busSegment_t *)NULL) { if (dev->bus->curSegment == (busSegment_t *)BUS_SPI_FREE) {
dev->bus->curSegment = (busSegment_t *)0x04; dev->bus->curSegment = (busSegment_t *)BUS_SPI_LOCKED;
} }
} }
} while (dev->bus->curSegment != (busSegment_t *)0x04); } while (dev->bus->curSegment != (busSegment_t *)BUS_SPI_LOCKED);
} else { } else {
// Wait for completion // Wait for completion
while (dev->bus->curSegment != (busSegment_t *)NULL); while (dev->bus->curSegment != (busSegment_t *)BUS_SPI_FREE);
} }
} }
@ -172,7 +172,7 @@ void spiWaitClaim(const extDevice_t *dev)
void spiWait(const extDevice_t *dev) void spiWait(const extDevice_t *dev)
{ {
// Wait for completion // Wait for completion
while (dev->bus->curSegment != (busSegment_t *)NULL); while (dev->bus->curSegment != (busSegment_t *)BUS_SPI_FREE);
} }
// Wait for bus to become free, then read/write block of data // Wait for bus to become free, then read/write block of data
@ -407,6 +407,7 @@ static void spiRxIrqHandler(dmaChannelDescriptor_t* descriptor)
} }
busDevice_t *bus = dev->bus; busDevice_t *bus = dev->bus;
busSegment_t *nextSegment;
if (bus->curSegment->negateCS) { if (bus->curSegment->negateCS) {
// Negate Chip Select // Negate Chip Select
@ -451,12 +452,23 @@ static void spiRxIrqHandler(dmaChannelDescriptor_t* descriptor)
} }
// Advance through the segment list // Advance through the segment list
bus->curSegment++; nextSegment = bus->curSegment + 1;
if (bus->curSegment->len == 0) { if (nextSegment->len == 0) {
// The end of the segment list has been reached, so mark transactions as complete // If a following transaction has been linked, start it
bus->curSegment = (busSegment_t *)NULL; if (nextSegment->txData) {
const extDevice_t *nextDev = (const extDevice_t *)nextSegment->txData;
busSegment_t *nextSegments = (busSegment_t *)nextSegment->rxData;
nextSegment->txData = NULL;
// The end of the segment list has been reached
spiSequenceStart(nextDev, nextSegments);
} else {
// The end of the segment list has been reached, so mark transactions as complete
bus->curSegment = (busSegment_t *)NULL;
}
} else { } else {
bus->curSegment = nextSegment;
// After the completion of the first segment setup the init structure for the subsequent segment // After the completion of the first segment setup the init structure for the subsequent segment
if (bus->initSegment) { if (bus->initSegment) {
spiInternalInitStream(dev, false); spiInternalInitStream(dev, false);
@ -479,6 +491,7 @@ bool spiSetBusInstance(extDevice_t *dev, uint32_t device)
} }
dev->bus = &spiBusDevice[SPI_CFG_TO_DEV(device)]; dev->bus = &spiBusDevice[SPI_CFG_TO_DEV(device)];
dev->useDMA = true;
if (dev->bus->busType == BUS_TYPE_SPI) { if (dev->bus->busType == BUS_TYPE_SPI) {
// This bus has already been initialised // This bus has already been initialised
@ -495,7 +508,6 @@ bool spiSetBusInstance(extDevice_t *dev, uint32_t device)
} }
bus->busType = BUS_TYPE_SPI; bus->busType = BUS_TYPE_SPI;
dev->useDMA = true;
bus->useDMA = false; bus->useDMA = false;
bus->useAtomicWait = false; bus->useAtomicWait = false;
bus->deviceCount = 1; bus->deviceCount = 1;
@ -637,4 +649,33 @@ uint8_t spiGetExtDeviceCount(const extDevice_t *dev)
{ {
return dev->bus->deviceCount; return dev->bus->deviceCount;
} }
// DMA transfer setup and start
void spiSequence(const extDevice_t *dev, busSegment_t *segments)
{
busDevice_t *bus = dev->bus;
ATOMIC_BLOCK(NVIC_PRIO_MAX) {
if ((bus->curSegment != (busSegment_t *)BUS_SPI_LOCKED) && spiIsBusy(dev)) {
/* Defer this transfer to be triggered upon completion of the current transfer. Blocking calls
* and those from non-interrupt context will have already called spiWaitClaim() so this will
* only happen for non-blocking calls called from an ISR.
*/
busSegment_t *endSegment = bus->curSegment;
if (endSegment) {
// Find the last segment of the current transfer
for (; endSegment->len; endSegment++);
// Record the dev and segments parameters in the terminating segment entry
endSegment->txData = (uint8_t *)dev;
endSegment->rxData = (uint8_t *)segments;
return;
}
}
}
spiSequenceStart(dev, segments);
}
#endif #endif

View file

@ -32,6 +32,9 @@
#error Unknown MCU family #error Unknown MCU family
#endif #endif
#define BUS_SPI_FREE 0x0
#define BUS_SPI_LOCKED 0x4
typedef struct spiPinDef_s { typedef struct spiPinDef_s {
ioTag_t pin; ioTag_t pin;
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) #if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
@ -87,4 +90,5 @@ void spiInternalStartDMA(const extDevice_t *dev);
void spiInternalStopDMA (const extDevice_t *dev); void spiInternalStopDMA (const extDevice_t *dev);
void spiInternalResetStream(dmaChannelDescriptor_t *descriptor); void spiInternalResetStream(dmaChannelDescriptor_t *descriptor);
void spiInternalResetDescriptors(busDevice_t *bus); void spiInternalResetDescriptors(busDevice_t *bus);
void spiSequenceStart(const extDevice_t *dev, busSegment_t *segments);

View file

@ -34,7 +34,6 @@
#include "drivers/bus_spi_impl.h" #include "drivers/bus_spi_impl.h"
#include "drivers/dma.h" #include "drivers/dma.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/nvic.h"
#include "drivers/rcc.h" #include "drivers/rcc.h"
#ifndef SPI2_SCK_PIN #ifndef SPI2_SCK_PIN
@ -471,7 +470,7 @@ void spiInternalStopDMA (const extDevice_t *dev)
} }
// DMA transfer setup and start // DMA transfer setup and start
void spiSequence(const extDevice_t *dev, busSegment_t *segments) void spiSequenceStart(const extDevice_t *dev, busSegment_t *segments)
{ {
busDevice_t *bus = dev->bus; busDevice_t *bus = dev->bus;
SPI_TypeDef *instance = bus->busType_u.spi.instance; SPI_TypeDef *instance = bus->busType_u.spi.instance;
@ -612,7 +611,16 @@ void spiSequence(const extDevice_t *dev, busSegment_t *segments)
bus->curSegment++; bus->curSegment++;
} }
bus->curSegment = (busSegment_t *)NULL; // If a following transaction has been linked, start it
if (bus->curSegment->txData) {
const extDevice_t *nextDev = (const extDevice_t *)bus->curSegment->txData;
busSegment_t *nextSegments = (busSegment_t *)bus->curSegment->rxData;
bus->curSegment->txData = NULL;
spiSequenceStart(nextDev, nextSegments);
} else {
// The end of the segment list has been reached, so mark transactions as complete
bus->curSegment = (busSegment_t *)NULL;
}
} }
} }
#endif #endif

View file

@ -270,7 +270,7 @@ void spiInternalStopDMA (const extDevice_t *dev)
} }
// DMA transfer setup and start // DMA transfer setup and start
void spiSequence(const extDevice_t *dev, busSegment_t *segments) void spiSequenceStart(const extDevice_t *dev, busSegment_t *segments)
{ {
busDevice_t *bus = dev->bus; busDevice_t *bus = dev->bus;
SPI_TypeDef *instance = bus->busType_u.spi.instance; SPI_TypeDef *instance = bus->busType_u.spi.instance;
@ -360,7 +360,16 @@ void spiSequence(const extDevice_t *dev, busSegment_t *segments)
bus->curSegment++; bus->curSegment++;
} }
bus->curSegment = (busSegment_t *)NULL; // If a following transaction has been linked, start it
if (bus->curSegment->txData) {
const extDevice_t *nextDev = (const extDevice_t *)bus->curSegment->txData;
busSegment_t *nextSegments = (busSegment_t *)bus->curSegment->rxData;
bus->curSegment->txData = NULL;
spiSequenceStart(nextDev, nextSegments);
} else {
// The end of the segment list has been reached, so mark transactions as complete
bus->curSegment = (busSegment_t *)NULL;
}
} }
} }
#endif #endif

View file

@ -392,6 +392,9 @@ void ak8963BusInit(const extDevice_t *dev)
case BUS_TYPE_MPU_SLAVE: case BUS_TYPE_MPU_SLAVE:
rescheduleTask(TASK_COMPASS, TASK_PERIOD_HZ(40)); rescheduleTask(TASK_COMPASS, TASK_PERIOD_HZ(40));
// Disable DMA on gyro as this upsets slave access timing
spiDmaEnable(dev->bus->busType_u.mpuSlave.master, false);
// initialize I2C master via SPI bus // initialize I2C master via SPI bus
ak8963SpiWriteRegisterDelay(dev->bus->busType_u.mpuSlave.master, MPU_RA_INT_PIN_CFG, MPU6500_BIT_INT_ANYRD_2CLEAR | MPU6500_BIT_BYPASS_EN); ak8963SpiWriteRegisterDelay(dev->bus->busType_u.mpuSlave.master, MPU_RA_INT_PIN_CFG, MPU6500_BIT_INT_ANYRD_2CLEAR | MPU6500_BIT_BYPASS_EN);
ak8963SpiWriteRegisterDelay(dev->bus->busType_u.mpuSlave.master, MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz ak8963SpiWriteRegisterDelay(dev->bus->busType_u.mpuSlave.master, MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz

View file

@ -234,39 +234,40 @@ void EXTIEnable(IO_t io, bool enable)
#define EXTI_EVENT_MASK 0xFFFF // first 16 bits only, see also definition of extiChannelRecs. #define EXTI_EVENT_MASK 0xFFFF // first 16 bits only, see also definition of extiChannelRecs.
void EXTI_IRQHandler(void) void EXTI_IRQHandler(uint32_t mask)
{ {
uint32_t exti_active = (EXTI_REG_IMR & EXTI_REG_PR) & EXTI_EVENT_MASK; uint32_t exti_active = (EXTI_REG_IMR & EXTI_REG_PR) & mask;
EXTI_REG_PR = exti_active; // clear pending mask (by writing 1)
while (exti_active) { while (exti_active) {
unsigned idx = 31 - __builtin_clz(exti_active); unsigned idx = 31 - __builtin_clz(exti_active);
uint32_t mask = 1 << idx; uint32_t mask = 1 << idx;
extiChannelRecs[idx].handler->fn(extiChannelRecs[idx].handler); extiChannelRecs[idx].handler->fn(extiChannelRecs[idx].handler);
EXTI_REG_PR = mask; // clear pending mask (by writing 1)
exti_active &= ~mask; exti_active &= ~mask;
} }
} }
#define _EXTI_IRQ_HANDLER(name) \ #define _EXTI_IRQ_HANDLER(name, mask) \
void name(void) { \ void name(void) { \
EXTI_IRQHandler(); \ EXTI_IRQHandler(mask & EXTI_EVENT_MASK); \
} \ } \
struct dummy \ struct dummy \
/**/ /**/
_EXTI_IRQ_HANDLER(EXTI0_IRQHandler); _EXTI_IRQ_HANDLER(EXTI0_IRQHandler, 0x0001);
_EXTI_IRQ_HANDLER(EXTI1_IRQHandler); _EXTI_IRQ_HANDLER(EXTI1_IRQHandler, 0x0002);
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) #if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
_EXTI_IRQ_HANDLER(EXTI2_IRQHandler); _EXTI_IRQ_HANDLER(EXTI2_IRQHandler, 0x0004);
#elif defined(STM32F3) #elif defined(STM32F3)
_EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler); _EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler, 0x0004);
#else #else
# warning "Unknown CPU" # warning "Unknown CPU"
#endif #endif
_EXTI_IRQ_HANDLER(EXTI3_IRQHandler); _EXTI_IRQ_HANDLER(EXTI3_IRQHandler, 0x0008);
_EXTI_IRQ_HANDLER(EXTI4_IRQHandler); _EXTI_IRQ_HANDLER(EXTI4_IRQHandler, 0x0010);
_EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler); _EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler, 0x03e0);
_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); _EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler, 0xfc00);
#endif #endif

View file

@ -361,6 +361,7 @@ static uint32_t m25p16_pageProgramContinue(flashDevice_t *fdevice, uint8_t const
segments[DATA1].negateCS = true; segments[DATA1].negateCS = true;
segments[DATA1].callback = m25p16_callbackWriteComplete; segments[DATA1].callback = m25p16_callbackWriteComplete;
// Mark segment following data as being of zero length // Mark segment following data as being of zero length
segments[DATA2].txData = (uint8_t *)NULL;
segments[DATA2].len = 0; segments[DATA2].len = 0;
} else if (bufferCount == 2) { } else if (bufferCount == 2) {
segments[DATA1].negateCS = false; segments[DATA1].negateCS = false;