mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
Implement queuing of SPI request segments
Use union in busSegment_t as per ledvinap feedback
This commit is contained in:
parent
ea53e32db4
commit
4aab87539f
11 changed files with 190 additions and 185 deletions
|
@ -220,11 +220,11 @@ bool mpuAccReadSPI(accDev_t *acc)
|
|||
acc->gyro->dev.txBuf[0] = MPU_RA_ACCEL_XOUT_H | 0x80;
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{NULL, NULL, 7, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 7, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
segments[0].txData = acc->gyro->dev.txBuf;
|
||||
segments[0].rxData = &acc->gyro->dev.rxBuf[1];
|
||||
segments[0].u.buffers.txData = acc->gyro->dev.txBuf;
|
||||
segments[0].u.buffers.rxData = &acc->gyro->dev.rxBuf[1];
|
||||
|
||||
spiSequence(&acc->gyro->dev, &segments[0]);
|
||||
|
||||
|
@ -275,8 +275,8 @@ bool mpuGyroReadSPI(gyroDev_t *gyro)
|
|||
gyro->dev.txBuf[0] = gyro->accDataReg | 0x80;
|
||||
gyro->segments[0].len = gyro->gyroDataReg - gyro->accDataReg + 7;
|
||||
gyro->segments[0].callback = mpuIntcallback;
|
||||
gyro->segments[0].txData = gyro->dev.txBuf;
|
||||
gyro->segments[0].rxData = &gyro->dev.rxBuf[1];
|
||||
gyro->segments[0].u.buffers.txData = gyro->dev.txBuf;
|
||||
gyro->segments[0].u.buffers.rxData = &gyro->dev.rxBuf[1];
|
||||
gyro->segments[0].negateCS = true;
|
||||
gyro->gyroModeSPI = GYRO_EXTI_INT_DMA;
|
||||
} else {
|
||||
|
@ -297,11 +297,11 @@ bool mpuGyroReadSPI(gyroDev_t *gyro)
|
|||
gyro->dev.txBuf[0] = MPU_RA_GYRO_XOUT_H | 0x80;
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{NULL, NULL, 7, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 7, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
segments[0].txData = gyro->dev.txBuf;
|
||||
segments[0].rxData = &gyro->dev.rxBuf[1];
|
||||
segments[0].u.buffers.txData = gyro->dev.txBuf;
|
||||
segments[0].u.buffers.rxData = &gyro->dev.rxBuf[1];
|
||||
|
||||
spiSequence(&gyro->dev, &segments[0]);
|
||||
|
||||
|
|
|
@ -319,11 +319,11 @@ static bool bmi270AccRead(accDev_t *acc)
|
|||
acc->gyro->dev.txBuf[0] = BMI270_REG_ACC_DATA_X_LSB | 0x80;
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{NULL, NULL, 8, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 8, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
segments[0].txData = acc->gyro->dev.txBuf;
|
||||
segments[0].rxData = acc->gyro->dev.rxBuf;
|
||||
segments[0].u.buffers.txData = acc->gyro->dev.txBuf;
|
||||
segments[0].u.buffers.rxData = acc->gyro->dev.rxBuf;
|
||||
|
||||
spiSequence(&acc->gyro->dev, &segments[0]);
|
||||
|
||||
|
@ -375,8 +375,8 @@ static bool bmi270GyroReadRegister(gyroDev_t *gyro)
|
|||
gyro->dev.txBuf[0] = BMI270_REG_ACC_DATA_X_LSB | 0x80;
|
||||
gyro->segments[0].len = 14;
|
||||
gyro->segments[0].callback = bmi270Intcallback;
|
||||
gyro->segments[0].txData = gyro->dev.txBuf;
|
||||
gyro->segments[0].rxData = gyro->dev.rxBuf;
|
||||
gyro->segments[0].u.buffers.txData = gyro->dev.txBuf;
|
||||
gyro->segments[0].u.buffers.rxData = gyro->dev.rxBuf;
|
||||
gyro->segments[0].negateCS = true;
|
||||
gyro->gyroModeSPI = GYRO_EXTI_INT_DMA;
|
||||
} else {
|
||||
|
@ -397,11 +397,11 @@ static bool bmi270GyroReadRegister(gyroDev_t *gyro)
|
|||
gyro->dev.txBuf[0] = BMI270_REG_GYR_DATA_X_LSB | 0x80;
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{NULL, NULL, 8, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 8, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
segments[0].txData = gyro->dev.txBuf;
|
||||
segments[0].rxData = gyro->dev.rxBuf;
|
||||
segments[0].u.buffers.txData = gyro->dev.txBuf;
|
||||
segments[0].u.buffers.rxData = gyro->dev.rxBuf;
|
||||
|
||||
spiSequence(&gyro->dev, &segments[0]);
|
||||
|
||||
|
|
|
@ -77,23 +77,6 @@ typedef struct busDevice_s {
|
|||
bool initSegment;
|
||||
} busDevice_t;
|
||||
|
||||
/* Each SPI access may comprise multiple parts, for example, wait/write enable/write/data each of which
|
||||
* is defined by a segment, with optional callback after each is completed
|
||||
*/
|
||||
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;
|
||||
/* 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;
|
||||
int len;
|
||||
bool negateCS; // Should CS be negated at the end of this segment
|
||||
busStatus_e (*callback)(uint32_t arg);
|
||||
} busSegment_t;
|
||||
|
||||
// External device has an associated bus and bus dependent address
|
||||
typedef struct extDevice_s {
|
||||
busDevice_t *bus;
|
||||
|
@ -128,6 +111,28 @@ typedef struct extDevice_s {
|
|||
uint32_t callbackArg;
|
||||
} extDevice_t;
|
||||
|
||||
/* Each SPI access may comprise multiple parts, for example, wait/write enable/write/data each of which
|
||||
* is defined by a segment, with optional callback after each is completed
|
||||
*/
|
||||
typedef struct busSegment_s {
|
||||
union {
|
||||
struct {
|
||||
// Transmit buffer
|
||||
uint8_t *txData;
|
||||
// Receive buffer, or in the case of the final segment to
|
||||
uint8_t *rxData;
|
||||
} buffers;
|
||||
struct {
|
||||
// Link to the device associated with the next transfer
|
||||
const extDevice_t *dev;
|
||||
// Segments to process in the next transfer.
|
||||
struct busSegment_s *segments;
|
||||
} link;
|
||||
} u;
|
||||
int len;
|
||||
bool negateCS; // Should CS be negated at the end of this segment
|
||||
busStatus_e (*callback)(uint32_t arg);
|
||||
} busSegment_t;
|
||||
|
||||
#ifdef TARGET_BUS_INIT
|
||||
void targetBusInit(void);
|
||||
|
|
|
@ -171,8 +171,8 @@ void spiReadWriteBuf(const extDevice_t *dev, uint8_t *txData, uint8_t *rxData, i
|
|||
{
|
||||
// This routine blocks so no need to use static data
|
||||
busSegment_t segments[] = {
|
||||
{txData, rxData, len, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {txData, rxData}, len, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -200,8 +200,8 @@ uint8_t spiReadWrite(const extDevice_t *dev, uint8_t data)
|
|||
|
||||
// This routine blocks so no need to use static data
|
||||
busSegment_t segments[] = {
|
||||
{&data, &retval, sizeof(data), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {&data, &retval}, sizeof(data), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -218,9 +218,9 @@ uint8_t spiReadWriteReg(const extDevice_t *dev, uint8_t reg, uint8_t data)
|
|||
|
||||
// This routine blocks so no need to use static data
|
||||
busSegment_t segments[] = {
|
||||
{®, NULL, sizeof(reg), false, NULL},
|
||||
{&data, &retval, sizeof(data), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {®, NULL}, sizeof(reg), false, NULL},
|
||||
{.u.buffers = {&data, &retval}, sizeof(data), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -235,8 +235,8 @@ void spiWrite(const extDevice_t *dev, uint8_t data)
|
|||
{
|
||||
// This routine blocks so no need to use static data
|
||||
busSegment_t segments[] = {
|
||||
{&data, NULL, sizeof(data), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {&data, NULL}, sizeof(data), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -249,9 +249,9 @@ void spiWriteReg(const extDevice_t *dev, uint8_t reg, uint8_t data)
|
|||
{
|
||||
// This routine blocks so no need to use static data
|
||||
busSegment_t segments[] = {
|
||||
{®, NULL, sizeof(reg), false, NULL},
|
||||
{&data, NULL, sizeof(data), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {®, NULL}, sizeof(reg), false, NULL},
|
||||
{.u.buffers = {&data, NULL}, sizeof(data), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -277,9 +277,9 @@ void spiReadRegBuf(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t l
|
|||
{
|
||||
// This routine blocks so no need to use static data
|
||||
busSegment_t segments[] = {
|
||||
{®, NULL, sizeof(reg), false, NULL},
|
||||
{NULL, data, length, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {®, NULL}, sizeof(reg), false, NULL},
|
||||
{.u.buffers = {NULL, data}, length, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -311,9 +311,9 @@ void spiWriteRegBuf(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint32_t
|
|||
{
|
||||
// This routine blocks so no need to use static data
|
||||
busSegment_t segments[] = {
|
||||
{®, NULL, sizeof(reg), false, NULL},
|
||||
{data, NULL, length, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {®, NULL}, sizeof(reg), false, NULL},
|
||||
{.u.buffers = {data, NULL}, length, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -327,9 +327,9 @@ uint8_t spiReadReg(const extDevice_t *dev, uint8_t reg)
|
|||
uint8_t data;
|
||||
// This routine blocks so no need to use static data
|
||||
busSegment_t segments[] = {
|
||||
{®, NULL, sizeof(reg), false, NULL},
|
||||
{NULL, &data, sizeof(data), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {®, NULL}, sizeof(reg), false, NULL},
|
||||
{.u.buffers = {NULL, &data}, sizeof(data), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -408,12 +408,12 @@ static void spiIrqHandler(const extDevice_t *dev)
|
|||
|
||||
if (nextSegment->len == 0) {
|
||||
// If a following transaction has been linked, start it
|
||||
if (nextSegment->txData) {
|
||||
const extDevice_t *nextDev = (const extDevice_t *)nextSegment->txData;
|
||||
busSegment_t *nextSegments = (busSegment_t *)nextSegment->rxData;
|
||||
if (nextSegment->u.link.dev) {
|
||||
const extDevice_t *nextDev = nextSegment->u.link.dev;
|
||||
busSegment_t *nextSegments = nextSegment->u.link.segments;
|
||||
// The end of the segment list has been reached
|
||||
bus->curSegment = nextSegments;
|
||||
nextSegment->txData = NULL;
|
||||
nextSegment->u.link.dev = NULL;
|
||||
spiSequenceStart(nextDev);
|
||||
} else {
|
||||
// The end of the segment list has been reached, so mark transactions as complete
|
||||
|
@ -456,15 +456,15 @@ static void spiRxIrqHandler(dmaChannelDescriptor_t* descriptor)
|
|||
|
||||
#ifdef __DCACHE_PRESENT
|
||||
#ifdef STM32H7
|
||||
if (bus->curSegment->rxData &&
|
||||
((bus->curSegment->rxData < &_dmaram_start__) || (bus->curSegment->rxData >= &_dmaram_end__))) {
|
||||
if (bus->curSegment->u.buffers.rxData &&
|
||||
((bus->curSegment->u.buffers.rxData < &_dmaram_start__) || (bus->curSegment->u.buffers.rxData >= &_dmaram_end__))) {
|
||||
#else
|
||||
if (bus->curSegment->rxData) {
|
||||
if (bus->curSegment->u.buffers.rxData) {
|
||||
#endif
|
||||
// Invalidate the D cache covering the area into which data has been read
|
||||
SCB_InvalidateDCache_by_Addr(
|
||||
(uint32_t *)((uint32_t)bus->curSegment->rxData & ~CACHE_LINE_MASK),
|
||||
(((uint32_t)bus->curSegment->rxData & CACHE_LINE_MASK) +
|
||||
(uint32_t *)((uint32_t)bus->curSegment->u.buffers.rxData & ~CACHE_LINE_MASK),
|
||||
(((uint32_t)bus->curSegment->u.buffers.rxData & CACHE_LINE_MASK) +
|
||||
bus->curSegment->len - 1 + CACHE_LINE_SIZE) & ~CACHE_LINE_MASK);
|
||||
}
|
||||
#endif // __DCACHE_PRESENT
|
||||
|
@ -731,18 +731,18 @@ void spiSequence(const extDevice_t *dev, busSegment_t *segments)
|
|||
return;
|
||||
}
|
||||
|
||||
if (endCmpSegment->txData == NULL) {
|
||||
if (endCmpSegment->u.link.dev == NULL) {
|
||||
// End of the segment list queue reached
|
||||
break;
|
||||
} else {
|
||||
// Follow the link to the next queued segment list
|
||||
endCmpSegment = (busSegment_t *)endCmpSegment->rxData;
|
||||
endCmpSegment = endCmpSegment->u.link.segments;
|
||||
}
|
||||
}
|
||||
|
||||
// Record the dev and segments parameters in the terminating segment entry
|
||||
endCmpSegment->txData = (uint8_t *)dev;
|
||||
endCmpSegment->rxData = (uint8_t *)segments;
|
||||
endCmpSegment->u.link.dev = dev;
|
||||
endCmpSegment->u.link.segments = segments;
|
||||
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -309,7 +309,7 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
|
|||
|
||||
int len = segment->len;
|
||||
|
||||
uint8_t *txData = segment->txData;
|
||||
uint8_t *txData = segment->u.buffers.txData;
|
||||
LL_DMA_InitTypeDef *initTx = bus->initTx;
|
||||
|
||||
if (txData) {
|
||||
|
@ -337,7 +337,7 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
|
|||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
if (dev->bus->dmaRx) {
|
||||
#endif
|
||||
uint8_t *rxData = segment->rxData;
|
||||
uint8_t *rxData = segment->u.buffers.rxData;
|
||||
LL_DMA_InitTypeDef *initRx = bus->initRx;
|
||||
|
||||
if (rxData) {
|
||||
|
@ -592,45 +592,45 @@ void spiSequenceStart(const extDevice_t *dev)
|
|||
// Check that any reads are cache aligned and of multiple cache lines in length
|
||||
for (busSegment_t *checkSegment = bus->curSegment; checkSegment->len; checkSegment++) {
|
||||
// Check there is no receive data as only transmit DMA is available
|
||||
if ((checkSegment->rxData) && (bus->dmaRx == (dmaChannelDescriptor_t *)NULL)) {
|
||||
if ((checkSegment->u.buffers.rxData) && (bus->dmaRx == (dmaChannelDescriptor_t *)NULL)) {
|
||||
dmaSafe = false;
|
||||
break;
|
||||
}
|
||||
#ifdef STM32H7
|
||||
// Check if RX data can be DMAed
|
||||
if ((checkSegment->rxData) &&
|
||||
if ((checkSegment->u.buffers.rxData) &&
|
||||
// DTCM can't be accessed by DMA1/2 on the H7
|
||||
(IS_DTCM(checkSegment->rxData) ||
|
||||
(IS_DTCM(checkSegment->u.buffers.rxData) ||
|
||||
// Memory declared as DMA_RAM will have an address between &_dmaram_start__ and &_dmaram_end__
|
||||
(((checkSegment->rxData < &_dmaram_start__) || (checkSegment->rxData >= &_dmaram_end__)) &&
|
||||
(((uint32_t)checkSegment->rxData & (CACHE_LINE_SIZE - 1)) || (checkSegment->len & (CACHE_LINE_SIZE - 1)))))) {
|
||||
(((checkSegment->u.buffers.rxData < &_dmaram_start__) || (checkSegment->u.buffers.rxData >= &_dmaram_end__)) &&
|
||||
(((uint32_t)checkSegment->u.buffers.rxData & (CACHE_LINE_SIZE - 1)) || (checkSegment->len & (CACHE_LINE_SIZE - 1)))))) {
|
||||
dmaSafe = false;
|
||||
break;
|
||||
}
|
||||
// Check if TX data can be DMAed
|
||||
else if ((checkSegment->txData) && IS_DTCM(checkSegment->txData)) {
|
||||
else if ((checkSegment->u.buffers.txData) && IS_DTCM(checkSegment->u.buffers.txData)) {
|
||||
dmaSafe = false;
|
||||
break;
|
||||
}
|
||||
#elif defined(STM32F7)
|
||||
if ((checkSegment->rxData) &&
|
||||
if ((checkSegment->u.buffers.rxData) &&
|
||||
// DTCM is accessible and uncached on the F7
|
||||
(!IS_DTCM(checkSegment->rxData) &&
|
||||
(((uint32_t)checkSegment->rxData & (CACHE_LINE_SIZE - 1)) || (checkSegment->len & (CACHE_LINE_SIZE - 1))))) {
|
||||
(!IS_DTCM(checkSegment->u.buffers.rxData) &&
|
||||
(((uint32_t)checkSegment->u.buffers.rxData & (CACHE_LINE_SIZE - 1)) || (checkSegment->len & (CACHE_LINE_SIZE - 1))))) {
|
||||
dmaSafe = false;
|
||||
break;
|
||||
}
|
||||
#elif defined(STM32G4)
|
||||
// Check if RX data can be DMAed
|
||||
if ((checkSegment->rxData) &&
|
||||
if ((checkSegment->u.buffers.rxData) &&
|
||||
// CCM can't be accessed by DMA1/2 on the G4
|
||||
IS_CCM(checkSegment->rxData)) {
|
||||
IS_CCM(checkSegment->u.buffers.rxData)) {
|
||||
dmaSafe = false;
|
||||
break;
|
||||
}
|
||||
if ((checkSegment->txData) &&
|
||||
if ((checkSegment->u.buffers.txData) &&
|
||||
// CCM can't be accessed by DMA1/2 on the G4
|
||||
IS_CCM(checkSegment->txData)) {
|
||||
IS_CCM(checkSegment->u.buffers.txData)) {
|
||||
dmaSafe = false;
|
||||
break;
|
||||
}
|
||||
|
@ -655,8 +655,8 @@ void spiSequenceStart(const extDevice_t *dev)
|
|||
|
||||
spiInternalReadWriteBufPolled(
|
||||
bus->busType_u.spi.instance,
|
||||
bus->curSegment->txData,
|
||||
bus->curSegment->rxData,
|
||||
bus->curSegment->u.buffers.txData,
|
||||
bus->curSegment->u.buffers.rxData,
|
||||
bus->curSegment->len);
|
||||
|
||||
if (bus->curSegment->negateCS) {
|
||||
|
@ -685,12 +685,12 @@ void spiSequenceStart(const extDevice_t *dev)
|
|||
}
|
||||
|
||||
// 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;
|
||||
if (bus->curSegment->u.link.dev) {
|
||||
const extDevice_t *nextDev = bus->curSegment->u.link.dev;
|
||||
busSegment_t *nextSegments = bus->curSegment->u.link.segments;
|
||||
busSegment_t *endSegment = bus->curSegment;
|
||||
bus->curSegment = nextSegments;
|
||||
endSegment->txData = NULL;
|
||||
endSegment->u.link.dev = NULL;
|
||||
spiSequenceStart(nextDev);
|
||||
} else {
|
||||
// The end of the segment list has been reached, so mark transactions as complete
|
||||
|
|
|
@ -179,7 +179,7 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
|
|||
|
||||
int len = segment->len;
|
||||
|
||||
uint8_t *txData = segment->txData;
|
||||
uint8_t *txData = segment->u.buffers.txData;
|
||||
DMA_InitTypeDef *initTx = bus->initTx;
|
||||
|
||||
if (txData) {
|
||||
|
@ -193,7 +193,7 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
|
|||
initTx->DMA_BufferSize = len;
|
||||
|
||||
if (dev->bus->dmaRx) {
|
||||
uint8_t *rxData = segment->rxData;
|
||||
uint8_t *rxData = segment->u.buffers.rxData;
|
||||
DMA_InitTypeDef *initRx = bus->initRx;
|
||||
|
||||
if (rxData) {
|
||||
|
@ -357,8 +357,8 @@ void spiSequenceStart(const extDevice_t *dev)
|
|||
// Check that any there are no attempts to DMA to/from CCD SRAM
|
||||
for (busSegment_t *checkSegment = bus->curSegment; checkSegment->len; checkSegment++) {
|
||||
// Check there is no receive data as only transmit DMA is available
|
||||
if (((checkSegment->rxData) && (IS_CCM(checkSegment->rxData) || (bus->dmaRx == (dmaChannelDescriptor_t *)NULL))) ||
|
||||
((checkSegment->txData) && IS_CCM(checkSegment->txData))) {
|
||||
if (((checkSegment->u.buffers.rxData) && (IS_CCM(checkSegment->u.buffers.rxData) || (bus->dmaRx == (dmaChannelDescriptor_t *)NULL))) ||
|
||||
((checkSegment->u.buffers.txData) && IS_CCM(checkSegment->u.buffers.txData))) {
|
||||
dmaSafe = false;
|
||||
break;
|
||||
}
|
||||
|
@ -381,8 +381,8 @@ void spiSequenceStart(const extDevice_t *dev)
|
|||
|
||||
spiInternalReadWriteBufPolled(
|
||||
bus->busType_u.spi.instance,
|
||||
bus->curSegment->txData,
|
||||
bus->curSegment->rxData,
|
||||
bus->curSegment->u.buffers.txData,
|
||||
bus->curSegment->u.buffers.rxData,
|
||||
bus->curSegment->len);
|
||||
|
||||
if (bus->curSegment->negateCS) {
|
||||
|
@ -411,12 +411,12 @@ void spiSequenceStart(const extDevice_t *dev)
|
|||
}
|
||||
|
||||
// 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;
|
||||
if (bus->curSegment->u.link.dev) {
|
||||
const extDevice_t *nextDev = bus->curSegment->u.link.dev;
|
||||
busSegment_t *nextSegments = bus->curSegment->u.link.segments;
|
||||
busSegment_t *endSegment = bus->curSegment;
|
||||
bus->curSegment = nextSegments;
|
||||
endSegment->txData = NULL;
|
||||
endSegment->u.link.dev = NULL;
|
||||
spiSequenceStart(nextDev);
|
||||
} else {
|
||||
// The end of the segment list has been reached, so mark transactions as complete
|
||||
|
|
|
@ -257,7 +257,7 @@ busStatus_e m25p16_callbackReady(uint32_t arg)
|
|||
flashDevice_t *fdevice = (flashDevice_t *)arg;
|
||||
extDevice_t *dev = fdevice->io.handle.dev;
|
||||
|
||||
uint8_t readyPoll = dev->bus->curSegment->rxData[1];
|
||||
uint8_t readyPoll = dev->bus->curSegment->u.buffers.rxData[1];
|
||||
|
||||
if (readyPoll & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) {
|
||||
return BUS_BUSY;
|
||||
|
@ -281,10 +281,10 @@ static void m25p16_eraseSector(flashDevice_t *fdevice, uint32_t address)
|
|||
STATIC_DMA_DATA_AUTO uint8_t writeEnable[] = { M25P16_INSTRUCTION_WRITE_ENABLE };
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{readStatus, readyStatus, sizeof(readStatus), true, m25p16_callbackReady},
|
||||
{writeEnable, NULL, sizeof(writeEnable), true, m25p16_callbackWriteEnable},
|
||||
{sectorErase, NULL, fdevice->isLargeFlash ? 5 : 4, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, m25p16_callbackReady},
|
||||
{.u.buffers = {writeEnable, NULL}, sizeof(writeEnable), true, m25p16_callbackWriteEnable},
|
||||
{.u.buffers = {sectorErase, NULL}, fdevice->isLargeFlash ? 5 : 4, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
// Ensure any prior DMA has completed before continuing
|
||||
|
@ -306,10 +306,10 @@ static void m25p16_eraseCompletely(flashDevice_t *fdevice)
|
|||
STATIC_DMA_DATA_AUTO uint8_t bulkErase[] = { M25P16_INSTRUCTION_BULK_ERASE };
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{readStatus, readyStatus, sizeof(readStatus), true, m25p16_callbackReady},
|
||||
{writeEnable, NULL, sizeof(writeEnable), true, m25p16_callbackWriteEnable},
|
||||
{bulkErase, NULL, sizeof(bulkErase), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, m25p16_callbackReady},
|
||||
{.u.buffers = {writeEnable, NULL}, sizeof(writeEnable), true, m25p16_callbackWriteEnable},
|
||||
{.u.buffers = {bulkErase, NULL}, sizeof(bulkErase), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(fdevice->io.handle.dev, segments);
|
||||
|
@ -334,12 +334,12 @@ static uint32_t m25p16_pageProgramContinue(flashDevice_t *fdevice, uint8_t const
|
|||
STATIC_DMA_DATA_AUTO uint8_t pageProgram[5] = { M25P16_INSTRUCTION_PAGE_PROGRAM };
|
||||
|
||||
static busSegment_t segments[] = {
|
||||
{readStatus, readyStatus, sizeof(readStatus), true, m25p16_callbackReady},
|
||||
{writeEnable, NULL, sizeof(writeEnable), true, m25p16_callbackWriteEnable},
|
||||
{pageProgram, NULL, 0, false, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, m25p16_callbackReady},
|
||||
{.u.buffers = {writeEnable, NULL}, sizeof(writeEnable), true, m25p16_callbackWriteEnable},
|
||||
{.u.buffers = {pageProgram, NULL}, 0, false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
// Ensure any prior DMA has completed before continuing
|
||||
|
@ -350,7 +350,7 @@ static uint32_t m25p16_pageProgramContinue(flashDevice_t *fdevice, uint8_t const
|
|||
m25p16_setCommandAddress(&pageProgram[1], fdevice->currentWriteAddress, fdevice->isLargeFlash);
|
||||
|
||||
// Patch the data segments
|
||||
segments[DATA1].txData = (uint8_t *)buffers[0];
|
||||
segments[DATA1].u.buffers.txData = (uint8_t *)buffers[0];
|
||||
segments[DATA1].len = bufferSizes[0];
|
||||
fdevice->callbackArg = bufferSizes[0];
|
||||
|
||||
|
@ -358,12 +358,12 @@ static uint32_t m25p16_pageProgramContinue(flashDevice_t *fdevice, uint8_t const
|
|||
segments[DATA1].negateCS = true;
|
||||
segments[DATA1].callback = m25p16_callbackWriteComplete;
|
||||
// Mark segment following data as being of zero length
|
||||
segments[DATA2].txData = (uint8_t *)NULL;
|
||||
segments[DATA2].u.buffers.txData = (uint8_t *)NULL;
|
||||
segments[DATA2].len = 0;
|
||||
} else if (bufferCount == 2) {
|
||||
segments[DATA1].negateCS = false;
|
||||
segments[DATA1].callback = NULL;
|
||||
segments[DATA2].txData = (uint8_t *)buffers[1];
|
||||
segments[DATA2].u.buffers.txData = (uint8_t *)buffers[1];
|
||||
segments[DATA2].len = bufferSizes[1];
|
||||
fdevice->callbackArg += bufferSizes[1];
|
||||
segments[DATA2].negateCS = true;
|
||||
|
@ -427,10 +427,10 @@ static int m25p16_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *b
|
|||
spiWait(fdevice->io.handle.dev);
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{readStatus, readyStatus, sizeof(readStatus), true, m25p16_callbackReady},
|
||||
{readBytes, NULL, fdevice->isLargeFlash ? 5 : 4, false, NULL},
|
||||
{NULL, buffer, length, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, m25p16_callbackReady},
|
||||
{.u.buffers = {readBytes, NULL}, fdevice->isLargeFlash ? 5 : 4, false, NULL},
|
||||
{.u.buffers = {NULL, buffer}, length, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
// Patch the readBytes command
|
||||
|
|
|
@ -73,8 +73,8 @@ static void w25m_dieSelect(const extDevice_t *dev, int die)
|
|||
uint8_t command[2] = { W25M_INSTRUCTION_SOFTWARE_DIE_SELECT, die };
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{command, NULL, sizeof(command), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {command, NULL}, sizeof(command), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
// Ensure any prior DMA has completed before continuing
|
||||
|
|
|
@ -150,8 +150,8 @@ static void w25n01g_performOneByteCommand(flashDeviceIO_t *io, uint8_t command)
|
|||
extDevice_t *dev = io->handle.dev;
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{&command, NULL, sizeof(command), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {&command, NULL}, sizeof(command), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -175,8 +175,8 @@ static void w25n01g_performCommandWithPageAddress(flashDeviceIO_t *io, uint8_t c
|
|||
uint8_t cmd[] = { command, 0, (pageAddress >> 8) & 0xff, (pageAddress >> 0) & 0xff};
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{cmd, NULL, sizeof(cmd), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {cmd, NULL}, sizeof(cmd), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -202,8 +202,8 @@ static uint8_t w25n01g_readRegister(flashDeviceIO_t *io, uint8_t reg)
|
|||
uint8_t in[3];
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{cmd, in, sizeof(cmd), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {cmd, in}, sizeof(cmd), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
// Ensure any prior DMA has completed before continuing
|
||||
|
@ -237,8 +237,8 @@ static void w25n01g_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data
|
|||
uint8_t cmd[3] = { W25N01G_INSTRUCTION_WRITE_STATUS_REG, reg, data };
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{cmd, NULL, sizeof(cmd), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {cmd, NULL}, sizeof(cmd), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
// Ensure any prior DMA has completed before continuing
|
||||
|
@ -408,9 +408,9 @@ static void w25n01g_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddre
|
|||
uint8_t cmd[] = { W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff };
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{cmd, NULL, sizeof(cmd), false, NULL},
|
||||
{(uint8_t *)data, NULL, length, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {cmd, NULL}, sizeof(cmd), false, NULL},
|
||||
{.u.buffers = {(uint8_t *)data, NULL}, length, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -439,9 +439,9 @@ static void w25n01g_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t colum
|
|||
extDevice_t *dev = fdevice->io.handle.dev;
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{cmd, NULL, sizeof(cmd), false, NULL},
|
||||
{(uint8_t *)data, NULL, length, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {cmd, NULL}, sizeof(cmd), false, NULL},
|
||||
{.u.buffers = {(uint8_t *)data, NULL}, length, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -682,9 +682,9 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
|
|||
cmd[3] = 0;
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{cmd, NULL, sizeof(cmd), false, NULL},
|
||||
{NULL, buffer, length, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {cmd, NULL}, sizeof(cmd), false, NULL},
|
||||
{.u.buffers = {NULL, buffer}, length, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -747,9 +747,9 @@ int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t
|
|||
cmd[3] = 0;
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{cmd, NULL, sizeof(cmd), false, NULL},
|
||||
{NULL, buffer, length, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {cmd, NULL}, sizeof(cmd), false, NULL},
|
||||
{.u.buffers = {NULL, buffer}, length, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
// Ensure any prior DMA has completed before continuing
|
||||
|
@ -811,7 +811,7 @@ busStatus_e w25n01g_readBBLUTCallback(uint32_t arg)
|
|||
{
|
||||
cb_context_t *cb_context = (cb_context_t *)arg;
|
||||
flashDevice_t *fdevice = cb_context->fdevice;
|
||||
uint8_t *rxData = fdevice->io.handle.dev->bus->curSegment->rxData;
|
||||
uint8_t *rxData = fdevice->io.handle.dev->bus->curSegment->u.buffers.rxData;
|
||||
|
||||
|
||||
cb_context->bblut->pba = (rxData[0] << 16)|rxData[1];
|
||||
|
@ -847,9 +847,9 @@ void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
|
|||
cb_context.lutindex = 0;
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{cmd, NULL, sizeof(cmd), false, NULL},
|
||||
{NULL, in, sizeof(in), true, w25n01g_readBBLUTCallback},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {cmd, NULL}, sizeof(cmd), false, NULL},
|
||||
{.u.buffers = {NULL, in}, sizeof(in), true, w25n01g_readBBLUTCallback},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
@ -887,8 +887,8 @@ void w25n01g_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba)
|
|||
uint8_t cmd[5] = { W25N01G_INSTRUCTION_BB_MANAGEMENT, lba >> 8, lba, pba >> 8, pba };
|
||||
|
||||
busSegment_t segments[] = {
|
||||
{cmd, NULL, sizeof(cmd), true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {cmd, NULL}, sizeof(cmd), true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
// Ensure any prior DMA has completed before continuing
|
||||
|
|
|
@ -615,8 +615,8 @@ bool max7456DrawScreen(void)
|
|||
static uint16_t pos = 0;
|
||||
// This routine doesn't block so need to use static data
|
||||
static busSegment_t segments[] = {
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{NULL, NULL, 0, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, true, NULL},
|
||||
};
|
||||
|
||||
if (!fontIsLoading) {
|
||||
|
@ -697,7 +697,7 @@ bool max7456DrawScreen(void)
|
|||
}
|
||||
|
||||
if (spiBufIndex) {
|
||||
segments[0].txData = spiBuf;
|
||||
segments[0].u.buffers.txData = spiBuf;
|
||||
segments[0].len = spiBufIndex;
|
||||
|
||||
spiSequence(dev, &segments[0]);
|
||||
|
|
|
@ -121,14 +121,14 @@ busStatus_e sdcard_callbackIdle(uint32_t arg)
|
|||
sdcard_t *sdcard = (sdcard_t *)arg;
|
||||
extDevice_t *dev = &sdcard->dev;
|
||||
|
||||
uint8_t idleByte = dev->bus->curSegment->rxData[0];
|
||||
uint8_t idleByte = dev->bus->curSegment->u.buffers.rxData[0];
|
||||
|
||||
if (idleByte == 0xff) {
|
||||
return BUS_READY;
|
||||
}
|
||||
|
||||
if (--sdcard->idleCount == 0) {
|
||||
dev->bus->curSegment->rxData[0] = 0x00;
|
||||
dev->bus->curSegment->u.buffers.rxData[0] = 0x00;
|
||||
return BUS_ABORT;
|
||||
}
|
||||
|
||||
|
@ -143,7 +143,7 @@ busStatus_e sdcard_callbackNotIdle(uint32_t arg)
|
|||
sdcard_t *sdcard = (sdcard_t *)arg;
|
||||
extDevice_t *dev = &sdcard->dev;
|
||||
|
||||
uint8_t idleByte = dev->bus->curSegment->rxData[0];
|
||||
uint8_t idleByte = dev->bus->curSegment->u.buffers.rxData[0];
|
||||
|
||||
if (idleByte != 0xff) {
|
||||
return BUS_READY;
|
||||
|
@ -168,8 +168,8 @@ static bool sdcard_waitForIdle(int maxBytesToWait)
|
|||
|
||||
// Note that this does not release the CS at the end of the transaction
|
||||
busSegment_t segments[] = {
|
||||
{NULL, &idleByte, sizeof(idleByte), false, sdcard_callbackIdle},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {NULL, &idleByte}, sizeof(idleByte), false, sdcard_callbackIdle},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
sdcard.idleCount = maxBytesToWait;
|
||||
|
@ -193,8 +193,8 @@ static uint8_t sdcard_waitForNonIdleByte(int maxDelay)
|
|||
|
||||
// Note that this does not release the CS at the end of the transaction
|
||||
busSegment_t segments[] = {
|
||||
{NULL, &idleByte, sizeof(idleByte), false, sdcard_callbackNotIdle},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {NULL, &idleByte}, sizeof(idleByte), false, sdcard_callbackNotIdle},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
sdcard.idleCount = maxDelay;
|
||||
|
@ -232,9 +232,9 @@ static uint8_t sdcard_sendCommand(uint8_t commandCode, uint32_t commandArgument)
|
|||
|
||||
// Note that this does not release the CS at the end of the transaction
|
||||
busSegment_t segments[] = {
|
||||
{command, NULL, sizeof(command), false, NULL},
|
||||
{NULL, &idleByte, sizeof(idleByte), false, sdcard_callbackNotIdle},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {command, NULL}, sizeof(command), false, NULL},
|
||||
{.u.buffers = {NULL, &idleByte}, sizeof(idleByte), false, sdcard_callbackNotIdle},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
if (!sdcard_waitForIdle(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY) && commandCode != SDCARD_COMMAND_GO_IDLE_STATE)
|
||||
|
@ -279,8 +279,8 @@ static bool sdcard_validateInterfaceCondition(void)
|
|||
} else if (status == SDCARD_R1_STATUS_BIT_IDLE) {
|
||||
// Note that this does not release the CS at the end of the transaction
|
||||
busSegment_t segments[] = {
|
||||
{NULL, ifCondReply, sizeof(ifCondReply), false, NULL},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {NULL, ifCondReply}, sizeof(ifCondReply), false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
spiSequence(&sdcard.dev, &segments[0]);
|
||||
|
@ -312,8 +312,8 @@ static bool sdcard_readOCRRegister(uint32_t *result)
|
|||
|
||||
// Note that this does not release the CS at the end of the transaction
|
||||
busSegment_t segments[] = {
|
||||
{NULL, response, sizeof(response), false, NULL},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {NULL, response}, sizeof(response), false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
spiSequence(&sdcard.dev, &segments[0]);
|
||||
|
@ -359,10 +359,10 @@ static sdcardReceiveBlockStatus_e sdcard_receiveDataBlock(uint8_t *buffer, int c
|
|||
|
||||
// Note that this does not release the CS at the end of the transaction
|
||||
busSegment_t segments[] = {
|
||||
{NULL, buffer, count, false, NULL},
|
||||
{.u.buffers = {NULL, buffer}, count, false, NULL},
|
||||
// Discard trailing CRC, we don't care
|
||||
{NULL, NULL, 2, false, NULL},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 2, false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
spiSequence(&sdcard.dev, &segments[0]);
|
||||
|
@ -379,9 +379,9 @@ static bool sdcard_sendDataBlockFinish(void)
|
|||
uint8_t dataResponseToken;
|
||||
// Note that this does not release the CS at the end of the transaction
|
||||
busSegment_t segments[] = {
|
||||
{(uint8_t *)&dummyCRC, NULL, sizeof(dummyCRC), false, NULL},
|
||||
{NULL, &dataResponseToken, sizeof(dataResponseToken), false, NULL},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {(uint8_t *)&dummyCRC, NULL}, sizeof(dummyCRC), false, NULL},
|
||||
{.u.buffers = {NULL, &dataResponseToken}, sizeof(dataResponseToken), false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
spiSequence(&sdcard.dev, &segments[0]);
|
||||
|
@ -416,13 +416,13 @@ static void sdcard_sendDataBlockBegin(uint8_t *buffer, bool multiBlockWrite)
|
|||
// Note that this does not release the CS at the end of the transaction
|
||||
static busSegment_t segments[] = {
|
||||
// Write a single 0xff
|
||||
{NULL, NULL, 1, false, NULL},
|
||||
{&token, NULL, sizeof(token), false, NULL},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 1, false, NULL},
|
||||
{.u.buffers = {&token, NULL}, sizeof(token), false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
segments[2].txData = buffer;
|
||||
segments[2].u.buffers.txData = buffer;
|
||||
segments[2].len = spiUseDMA(&sdcard.dev) ? SDCARD_BLOCK_SIZE : SDCARD_NON_DMA_CHUNK_SIZE;
|
||||
|
||||
spiSequence(&sdcard.dev, &segments[0]);
|
||||
|
@ -562,8 +562,8 @@ static void sdcardSpi_init(const sdcardConfig_t *config, const spiPinConfig_t *s
|
|||
// Note that this does not release the CS at the end of the transaction
|
||||
busSegment_t segments[] = {
|
||||
// Write a single 0xff
|
||||
{NULL, NULL, SDCARD_INIT_NUM_DUMMY_BYTES, false, NULL},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, SDCARD_INIT_NUM_DUMMY_BYTES, false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
spiSequence(&sdcard.dev, &segments[0]);
|
||||
|
@ -613,9 +613,9 @@ static sdcardOperationStatus_e sdcard_endWriteBlocks(void)
|
|||
// Note that this does not release the CS at the end of the transaction
|
||||
busSegment_t segments[] = {
|
||||
// 8 dummy clocks to guarantee N_WR clocks between the last card response and this token
|
||||
{NULL, NULL, 1, false, NULL},
|
||||
{&token, NULL, sizeof(token), false, NULL},
|
||||
{NULL, NULL, 0, false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 1, false, NULL},
|
||||
{.u.buffers = {&token, NULL}, sizeof(token), false, NULL},
|
||||
{.u.buffers = {NULL, NULL}, 0, false, NULL},
|
||||
};
|
||||
|
||||
spiSequence(&sdcard.dev, &segments[0]);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue