Skip to content

Commit

Permalink
AT32 SD card support (#14070)
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveCEvans authored Dec 7, 2024
1 parent 896c8ee commit b5ab83b
Show file tree
Hide file tree
Showing 5 changed files with 90 additions and 46 deletions.
17 changes: 10 additions & 7 deletions src/main/drivers/bus_spi.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,20 +31,23 @@
#if defined(STM32F4)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN)
#define SPI_IO_AF_SDI_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
#define SPI_IO_AF_SDI_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define SPI_IO_CS_HIGH_CFG IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
#elif defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
#define SPI_IO_AF_SCK_CFG_HIGH IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
#define SPI_IO_AF_SCK_CFG_LOW IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLDOWN)
#define SPI_IO_AF_SDI_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
#define SPI_IO_AF_SDI_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
#define SPI_IO_CS_HIGH_CFG IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
#elif defined(AT32F4)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE)
#define SPI_IO_AF_SCK_CFG_HIGH IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP)
#define SPI_IO_AF_SCK_CFG_LOW IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_DOWN)
#define SPI_IO_AF_SDI_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE)
#define SPI_IO_AF_SCK_CFG_HIGH IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP)
#define SPI_IO_AF_SCK_CFG_LOW IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_DOWN)
#define SPI_IO_AF_SDI_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE)
#define SPI_IO_CS_HIGH_CFG IO_CONFIG(GPIO_MODE_INPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP)
#endif

// De facto standard mode
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/sdcard_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ typedef struct sdcard_t {

#ifdef USE_SDCARD_SPI
extDevice_t dev;
uint8_t idleCount;
int8_t idleCount;
#endif

#ifdef USE_SDCARD_SDIO
Expand Down
94 changes: 65 additions & 29 deletions src/main/drivers/sdcard_spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -111,19 +111,21 @@ static void sdcard_reset(void)
}

// Called in ISR context
// Wait until idle indicated by a read value of 0xff
// Wait until idle indicated by a read value of SDCARD_IDLE_TOKEN
busStatus_e sdcard_callbackIdle(uint32_t arg)
{
sdcard_t *sdcard = (sdcard_t *)arg;
extDevice_t *dev = &sdcard->dev;

uint8_t idleByte = dev->bus->curSegment->u.buffers.rxData[0];

if (idleByte == 0xff) {
if (idleByte == SDCARD_IDLE_TOKEN) {
// Default for next call to sdcard_callbackNotIdle()
sdcard->idleCount = SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY;
return BUS_READY;
}

if (--sdcard->idleCount == 0) {
if (--sdcard->idleCount <= 0) {
dev->bus->curSegment->u.buffers.rxData[0] = 0x00;
return BUS_ABORT;
}
Expand All @@ -132,19 +134,19 @@ busStatus_e sdcard_callbackIdle(uint32_t arg)
}

// Called in ISR context
// Wait until idle is no longer indicated by a read value of 0xff
// Wait until idle is no longer indicated by a read value of SDCARD_IDLE_TOKEN
busStatus_e sdcard_callbackNotIdle(uint32_t arg)
{
sdcard_t *sdcard = (sdcard_t *)arg;
extDevice_t *dev = &sdcard->dev;

uint8_t idleByte = dev->bus->curSegment->u.buffers.rxData[0];

if (idleByte != 0xff) {
if (idleByte != SDCARD_IDLE_TOKEN) {
return BUS_READY;
}

if (sdcard->idleCount-- == 0) {
if (sdcard->idleCount-- <= 0) {
return BUS_ABORT;
}

Expand Down Expand Up @@ -174,11 +176,11 @@ static bool sdcard_waitForIdle(int maxBytesToWait)
// Block pending completion of SPI access
spiWait(&sdcard.dev);

return (idleByte == 0xff);
return (idleByte == SDCARD_IDLE_TOKEN);
}

/**
* Wait for up to maxDelay 0xFF idle bytes to arrive from the card, returning the first non-idle byte found.
* Wait for up to maxDelay SDCARD_IDLE_TOKEN idle bytes to arrive from the card, returning the first non-idle byte found.
*
* Returns 0xFF on failure.
*/
Expand Down Expand Up @@ -208,9 +210,9 @@ 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.
*
* Upon failure, 0xFF is returned.
* Upon failure, -1 is returned.
*/
static uint8_t sdcard_sendCommand(uint8_t commandCode, uint32_t commandArgument)
static int sdcard_sendCommand(uint8_t commandCode, uint32_t commandArgument)
{
uint8_t command[6] = {
0x40 | commandCode,
Expand All @@ -223,26 +225,29 @@ static uint8_t sdcard_sendCommand(uint8_t commandCode, uint32_t commandArgument)
};

uint8_t idleByte;
uint8_t cmdResponse;

// Note that this does not release the CS at the end of the transaction
busSegment_t segments[] = {
{.u.buffers = {NULL, &idleByte}, sizeof(idleByte), false, sdcard_callbackIdle},
{.u.buffers = {command, NULL}, sizeof(command), false, NULL},
{.u.buffers = {NULL, &idleByte}, sizeof(idleByte), false, sdcard_callbackNotIdle},
{.u.buffers = {NULL, &cmdResponse}, sizeof(cmdResponse), false, sdcard_callbackNotIdle},
{.u.link = {NULL, NULL}, 0, true, NULL},

};

if (!sdcard_waitForIdle(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY) && commandCode != SDCARD_COMMAND_GO_IDLE_STATE)
return 0xFF;

sdcard.idleCount = SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY;

spiSequence(&sdcard.dev, &segments[0]);

// Block pending completion of SPI access
spiWait(&sdcard.dev);

return idleByte;
if ((idleByte != SDCARD_IDLE_TOKEN) && commandCode != SDCARD_COMMAND_GO_IDLE_STATE) {
return -1;
}

return cmdResponse;
}

static uint8_t sdcard_sendAppCommand(uint8_t commandCode, uint32_t commandArgument)
Expand Down Expand Up @@ -333,25 +338,44 @@ typedef enum {
SDCARD_RECEIVE_ERROR
} sdcardReceiveBlockStatus_e;

/// Called in ISR context
// Wait until the arrival of the SDCARD_SINGLE_BLOCK_READ_START_TOKEN token
busStatus_e sdcard_callbackNotIdleDataBlock(uint32_t arg)
{
sdcard_t *sdcard = (sdcard_t *)arg;
extDevice_t *dev = &sdcard->dev;

uint8_t idleByte = dev->bus->curSegment->u.buffers.rxData[0];

if (idleByte == SDCARD_SINGLE_BLOCK_READ_START_TOKEN) {
return BUS_READY;
}

if (idleByte != SDCARD_IDLE_TOKEN) {
return BUS_ABORT;
}

if (sdcard->idleCount-- <= 0) {
return BUS_ABORT;
}

return BUS_BUSY;
}

/**
* Attempt to receive a data block from the SD card.
*
* Return true on success, otherwise the card has not responded yet and you should retry later.
*/
static sdcardReceiveBlockStatus_e sdcard_receiveDataBlock(uint8_t *buffer, int count)
{
uint8_t dataToken = sdcard_waitForNonIdleByte(8);

if (dataToken == 0xFF) {
return SDCARD_RECEIVE_BLOCK_IN_PROGRESS;
}
uint8_t dataToken;

if (dataToken != SDCARD_SINGLE_BLOCK_READ_START_TOKEN) {
return SDCARD_RECEIVE_ERROR;
}
sdcard.idleCount = 8;

// Note that this does not release the CS at the end of the transaction
busSegment_t segments[] = {
{.u.buffers = {NULL, &dataToken}, sizeof(dataToken), false, sdcard_callbackNotIdleDataBlock},
{.u.buffers = {NULL, buffer}, count, false, NULL},
// Discard trailing CRC, we don't care
{.u.buffers = {NULL, NULL}, 2, false, NULL},
Expand All @@ -364,7 +388,14 @@ static sdcardReceiveBlockStatus_e sdcard_receiveDataBlock(uint8_t *buffer, int c
// Block pending completion of SPI access
spiWait(&sdcard.dev);

return SDCARD_RECEIVE_SUCCESS;
switch (dataToken) {
case SDCARD_IDLE_TOKEN:
return SDCARD_RECEIVE_BLOCK_IN_PROGRESS;
case SDCARD_SINGLE_BLOCK_READ_START_TOKEN:
return SDCARD_RECEIVE_SUCCESS;
default:
return SDCARD_RECEIVE_ERROR;
}
}

static bool sdcard_sendDataBlockFinish(void)
Expand Down Expand Up @@ -529,7 +560,7 @@ static void sdcardSpi_init(const sdcardConfig_t *config, const spiPinConfig_t *s
if (config->chipSelectTag) {
chipSelectIO = IOGetByTag(config->chipSelectTag);
IOInit(chipSelectIO, OWNER_SDCARD_CS, 0);
IOConfigGPIO(chipSelectIO, SPI_IO_CS_CFG);
IOConfigGPIO(chipSelectIO, SPI_IO_CS_HIGH_CFG);
} else {
chipSelectIO = IO_NONE;
}
Expand All @@ -551,10 +582,10 @@ static void sdcardSpi_init(const sdcardConfig_t *config, const spiPinConfig_t *s
// Transmit at least 74 dummy clock cycles with CS high so the SD card can start up
IOHi(sdcard.dev.busType_u.spi.csnPin);

// Note that this does not release the CS at the end of the transaction
// Note that CS is not asserted for this transaction
busSegment_t segments[] = {
// Write a single 0xff
{.u.buffers = {NULL, NULL}, SDCARD_INIT_NUM_DUMMY_BYTES, false, NULL},
{.u.buffers = {NULL, NULL}, SDCARD_INIT_NUM_DUMMY_BYTES, true, NULL},
{.u.link = {NULL, NULL}, 0, true, NULL},
};

Expand All @@ -563,6 +594,11 @@ static void sdcardSpi_init(const sdcardConfig_t *config, const spiPinConfig_t *s
// Block pending completion of SPI access
spiWait(&sdcard.dev);

// Enable the CS line
if (chipSelectIO != IO_NONE) {
IOConfigGPIO(chipSelectIO, SPI_IO_CS_CFG);
}

sdcard.operationStartTime = millis();
sdcard.state = SDCARD_STATE_RESET;
sdcard.failureCount = 0;
Expand Down Expand Up @@ -614,8 +650,8 @@ static sdcardOperationStatus_e sdcard_endWriteBlocks(void)
// Block pending completion of SPI access
spiWait(&sdcard.dev);

// Card may choose to raise a busy (non-0xFF) signal after at most N_BR (1 byte) delay
if (sdcard_waitForNonIdleByte(1) == 0xFF) {
// Card may choose to raise a busy (non-SDCARD_IDLE_TOKEN) signal after at most N_BR (1 byte) delay
if (sdcard_waitForNonIdleByte(1) == SDCARD_IDLE_TOKEN) {
sdcard.state = SDCARD_STATE_READY;
return SDCARD_OPERATION_SUCCESS;
} else {
Expand Down
15 changes: 8 additions & 7 deletions src/main/drivers/sdcard_standard.h
Original file line number Diff line number Diff line change
Expand Up @@ -196,6 +196,7 @@ typedef struct sdcardCSD_t {
#define SDCARD_CSD_V2_TRAILER_OFFSET 127
#define SDCARD_CSD_V2_TRAILER_LEN 1

#define SDCARD_IDLE_TOKEN 0xFF
#define SDCARD_SINGLE_BLOCK_READ_START_TOKEN 0xFE
#define SDCARD_SINGLE_BLOCK_WRITE_START_TOKEN 0xFE
#define SDCARD_MULTIPLE_BLOCK_WRITE_START_TOKEN 0xFC
Expand All @@ -204,13 +205,13 @@ typedef struct sdcardCSD_t {
#define SDCARD_BLOCK_SIZE 512

// Idle bit is set to 1 only when idle during initialization phase:
#define SDCARD_R1_STATUS_BIT_IDLE 1
#define SDCARD_R1_STATUS_BIT_ERASE_RESET 2
#define SDCARD_R1_STATUS_BIT_ILLEGAL_COMMAND 4
#define SDCARD_R1_STATUS_BIT_COM_CRC_ERROR 8
#define SDCARD_R1_STATUS_BIT_ERASE_SEQUENCE_ERROR 16
#define SDCARD_R1_STATUS_BIT_ADDRESS_ERROR 32
#define SDCARD_R1_STATUS_BIT_PARAMETER_ERROR 64
#define SDCARD_R1_STATUS_BIT_IDLE 0x01
#define SDCARD_R1_STATUS_BIT_ERASE_RESET 0x02
#define SDCARD_R1_STATUS_BIT_ILLEGAL_COMMAND 0x04
#define SDCARD_R1_STATUS_BIT_COM_CRC_ERROR 0x08
#define SDCARD_R1_STATUS_BIT_ERASE_SEQUENCE_ERROR 0x10
#define SDCARD_R1_STATUS_BIT_ADDRESS_ERROR 0x20
#define SDCARD_R1_STATUS_BIT_PARAMETER_ERROR 0x40

#define SDCARD_CSD_STRUCTURE_VERSION_1 0
#define SDCARD_CSD_STRUCTURE_VERSION_2 1
Expand Down
8 changes: 6 additions & 2 deletions src/platform/AT32/bus_spi_at32bsp.c
Original file line number Diff line number Diff line change
Expand Up @@ -208,6 +208,10 @@ void spiInternalStartDMA(const extDevice_t *dev)
dmaChannelDescriptor_t *dmaTx = dev->bus->dmaTx;
dmaChannelDescriptor_t *dmaRx = dev->bus->dmaRx;
DMA_ARCH_TYPE *streamRegsTx = (DMA_ARCH_TYPE *)dmaTx->ref;

// Wait for any ongoing transmission to complete
while (spi_i2s_flag_get(dev->bus->busType_u.spi.instance, SPI_I2S_BF_FLAG) == SET);

if (dmaRx) {
DMA_ARCH_TYPE *streamRegsRx = (DMA_ARCH_TYPE *)dmaRx->ref;

Expand All @@ -229,10 +233,10 @@ void spiInternalStartDMA(const extDevice_t *dev)
xDMA_Init(streamRegsRx, dev->bus->initRx);

// Enable streams
xDMA_Cmd(streamRegsTx, TRUE);
xDMA_Cmd(streamRegsRx, TRUE);
xDMA_Cmd(streamRegsTx, TRUE);

/* Enable the receiver before the transmitter to ensure that not bits are missed on reception. An interrupt between
/* Enable the receiver before the transmitter to ensure that no bits are missed on reception. An interrupt between
* the transmitter and receiver being enabled can otherwise cause a hang.
*/
spi_i2s_dma_receiver_enable(dev->bus->busType_u.spi.instance, TRUE);
Expand Down

0 comments on commit b5ab83b

Please sign in to comment.