Skip to content

Commit

Permalink
Remove cs lock device (betaflight#12999)
Browse files Browse the repository at this point in the history
Remove csLockDevice as SD card cannot share an SPI bus
  • Loading branch information
SteveCEvans authored and davidbitton committed Feb 5, 2024
1 parent 2f0164c commit b682259
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 43 deletions.
1 change: 0 additions & 1 deletion src/main/drivers/bus.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,6 @@ typedef struct busDevice_s {
#endif
#endif // UNIT_TEST
volatile struct busSegment_s* volatile curSegment;
volatile struct extDevice_s *csLockDevice;
bool initSegment;
} busDevice_t;

Expand Down
21 changes: 7 additions & 14 deletions src/main/drivers/bus_spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -160,10 +160,6 @@ bool spiInit(SPIDevice device)
// Return true if DMA engine is busy
bool spiIsBusy(const extDevice_t *dev)
{
if (dev->bus->csLockDevice && (dev->bus->csLockDevice != dev)) {
// If CS is still asserted, but not by the current device, the bus is busy
return true;
}
return (dev->bus->curSegment != (busSegment_t *)BUS_SPI_FREE);
}

Expand All @@ -174,6 +170,13 @@ void spiWait(const extDevice_t *dev)
while (spiIsBusy(dev));
}

// Negate CS if held asserted after a transfer
void spiRelease(const extDevice_t *dev)
{
// Negate Chip Select
IOHi(dev->busType_u.spi.csnPin);
}

// Wait for bus to become free, then read/write block of data
void spiReadWriteBuf(const extDevice_t *dev, uint8_t *txData, uint8_t *rxData, int len)
{
Expand Down Expand Up @@ -440,11 +443,6 @@ FAST_IRQ_HANDLER static void spiIrqHandler(const extDevice_t *dev)
spiSequenceStart(nextDev);
} else {
// The end of the segment list has been reached, so mark transactions as complete
if (bus->curSegment->negateCS) {
bus->csLockDevice = (extDevice_t *)NULL;
} else {
bus->csLockDevice = (extDevice_t *)dev;
}
bus->curSegment = (busSegment_t *)BUS_SPI_FREE;
}
} else {
Expand Down Expand Up @@ -763,11 +761,6 @@ void spiSequence(const extDevice_t *dev, busSegment_t *segments)
// Safe to discard the volatile qualifier as we're in an atomic block
busSegment_t *endCmpSegment = (busSegment_t *)bus->curSegment;

/* It is possible that the endCmpSegment may be NULL as the bus is held busy by csLockDevice.
* If this is the case this transfer will be silently dropped. Therefore holding CS low after a transfer,
* as is done with the SD card, MUST not be done on a bus where interrupts may trigger a transfer
* on an idle bus, such as would be the case with a gyro. This would be result in skipped gyro transfers.
*/
if (endCmpSegment) {
while (true) {
// Find the last segment of the current transfer
Expand Down
2 changes: 2 additions & 0 deletions src/main/drivers/bus_spi.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,8 @@ void spiDmaEnable(const extDevice_t *dev, bool enable);
void spiSequence(const extDevice_t *dev, busSegment_t *segments);
// Wait for DMA completion
void spiWait(const extDevice_t *dev);
// Negate CS if held asserted after a transfer
void spiRelease(const extDevice_t *dev);
// Return true if DMA engine is busy
bool spiIsBusy(const extDevice_t *dev);

Expand Down
31 changes: 3 additions & 28 deletions src/main/drivers/sdcard_spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -71,11 +71,6 @@ static bool sdcardSpi_isFunctional(void)
return sdcard.state != SDCARD_STATE_NOT_PRESENT;
}

static void sdcard_select(void)
{
IOLo(sdcard.dev.busType_u.spi.csnPin);
}

static void sdcard_deselect(void)
{
// As per the SD-card spec, give the card 8 dummy clocks so it can finish its operation
Expand All @@ -84,7 +79,9 @@ static void sdcard_deselect(void)
spiWait(&sdcard.dev);

delayMicroseconds(10);
IOHi(sdcard.dev.busType_u.spi.csnPin);

// Negate CS
spiRelease(&sdcard.dev);
}

/**
Expand Down Expand Up @@ -214,8 +211,6 @@ static uint8_t sdcard_waitForNonIdleByte(int maxDelay)
* with the given argument, waits up to SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY bytes for a reply, and returns the
* first non-0xFF byte of the reply.
*
* You must select the card first with sdcard_select() and deselect it afterwards with sdcard_deselect().
*
* Upon failure, 0xFF is returned.
*/
static uint8_t sdcard_sendCommand(uint8_t commandCode, uint32_t commandArgument)
Expand Down Expand Up @@ -270,8 +265,6 @@ static bool sdcard_validateInterfaceCondition(void)

sdcard.version = 0;

sdcard_select();

uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_SEND_IF_COND, (SDCARD_VOLTAGE_ACCEPTED_2_7_to_3_6 << 8) | SDCARD_IF_COND_CHECK_PATTERN);

// Don't deselect the card right away, because we'll want to read the rest of its reply if it's a V2 card
Expand Down Expand Up @@ -308,8 +301,6 @@ static bool sdcard_validateInterfaceCondition(void)

static bool sdcard_readOCRRegister(uint32_t *result)
{
sdcard_select();

uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_READ_OCR, 0);

uint8_t response[4];
Expand Down Expand Up @@ -467,8 +458,6 @@ static bool sdcard_fetchCSD(void)
uint32_t readBlockLen, blockCount, blockCountMult;
uint64_t capacityBytes;

sdcard_select();

/* The CSD command's data block should always arrive within 8 idle clock cycles (SD card spec). This is because
* the information about card latency is stored in the CSD register itself, so we can't use that yet!
*/
Expand Down Expand Up @@ -511,8 +500,6 @@ static bool sdcard_fetchCSD(void)
*/
static bool sdcard_checkInitDone(void)
{
sdcard_select();

uint8_t status = sdcard_sendAppCommand(SDCARD_ACOMMAND_SEND_OP_COND, sdcard.version == 2 ? 1 << 30 /* We support high capacity cards */ : 0);

sdcard_deselect();
Expand Down Expand Up @@ -586,8 +573,6 @@ static void sdcardSpi_init(const sdcardConfig_t *config, const spiPinConfig_t *s

static bool sdcard_setBlockLength(uint32_t blockLen)
{
sdcard_select();

uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_SET_BLOCKLEN, blockLen);

sdcard_deselect();
Expand Down Expand Up @@ -666,8 +651,6 @@ static bool sdcardSpi_poll(void)
doMore:
switch (sdcard.state) {
case SDCARD_STATE_RESET:
sdcard_select();

initStatus = sdcard_sendCommand(SDCARD_COMMAND_GO_IDLE_STATE, 0);

sdcard_deselect();
Expand Down Expand Up @@ -704,8 +687,6 @@ static bool sdcardSpi_poll(void)

// Now fetch the CSD and CID registers
if (sdcard_fetchCSD()) {
sdcard_select();

uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_SEND_CID, 0);

if (status == 0) {
Expand Down Expand Up @@ -942,8 +923,6 @@ static sdcardOperationStatus_e sdcardSpi_writeBlock(uint32_t blockIndex, uint8_t
break;
case SDCARD_STATE_READY:
// We're not continuing a multi-block write so we need to send a single-block write command
sdcard_select();

// Standard size cards use byte addressing, high capacity cards use block addressing
status = sdcard_sendCommand(SDCARD_COMMAND_WRITE_BLOCK, sdcard.highCapacity ? blockIndex : blockIndex * SDCARD_BLOCK_SIZE);

Expand Down Expand Up @@ -999,8 +978,6 @@ static sdcardOperationStatus_e sdcardSpi_beginWriteBlocks(uint32_t blockIndex, u
}
}

sdcard_select();

if (
sdcard_sendAppCommand(SDCARD_ACOMMAND_SET_WR_BLOCK_ERASE_COUNT, blockCount) == 0
&& sdcard_sendCommand(SDCARD_COMMAND_WRITE_MULTIPLE_BLOCK, sdcard.highCapacity ? blockIndex : blockIndex * SDCARD_BLOCK_SIZE) == 0
Expand Down Expand Up @@ -1048,8 +1025,6 @@ static bool sdcardSpi_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_ope
sdcard.pendingOperation.profileStartTime = micros();
#endif

sdcard_select();

// Standard size cards use byte addressing, high capacity cards use block addressing
uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_READ_SINGLE_BLOCK, sdcard.highCapacity ? blockIndex : blockIndex * SDCARD_BLOCK_SIZE);

Expand Down

0 comments on commit b682259

Please sign in to comment.