Merge branch 'fix/spi_master_cmd_addr_lsbfirst_v3.0' into 'release/v3.0'

spi_master: fix the command and address field when LSB_FIRST enabled (Backport v3.0)

See merge request idf/esp-idf!3444
This commit is contained in:
Angus Gratton 2018-10-11 06:28:38 +08:00
commit d02d2d5170
4 changed files with 219 additions and 137 deletions

View file

@ -329,6 +329,7 @@ void spicommon_cs_initialize(spi_host_device_t host, int cs_io_num, int cs_num,
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[cs_io_num], 1);
} else {
//Use GPIO matrix
gpio_set_direction(cs_io_num, GPIO_MODE_INPUT_OUTPUT);
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[cs_io_num], PIN_FUNC_GPIO);
gpio_matrix_out(cs_io_num, io_signal[host].spics_out[cs_num], false, false);
if (cs_num == 0) gpio_matrix_in(cs_io_num, io_signal[host].spics_in, false);

View file

@ -21,13 +21,13 @@ is a combination of SPI port and CS pin, plus some information about the specifi
The essence of the interface to a device is a set of queues; one per device. The idea is that to send something to a SPI
device, you allocate a transaction descriptor. It contains some information about the transfer like the lenghth, address,
command etc, plus pointers to transmit and receive buffer. The address of this block gets pushed into the transmit queue.
The SPI driver does its magic, and sends and retrieves the data eventually. The data gets written to the receive buffers,
command etc, plus pointers to transmit and receive buffer. The address of this block gets pushed into the transmit queue.
The SPI driver does its magic, and sends and retrieves the data eventually. The data gets written to the receive buffers,
if needed the transaction descriptor is modified to indicate returned parameters and the entire thing goes into the return
queue, where whatever software initiated the transaction can retrieve it.
The entire thing is run from the SPI interrupt handler. If SPI is done transmitting/receiving but nothing is in the queue,
it will not clear the SPI interrupt but just disable it. This way, when a new thing is sent, pushing the packet into the send
The entire thing is run from the SPI interrupt handler. If SPI is done transmitting/receiving but nothing is in the queue,
it will not clear the SPI interrupt but just disable it. This way, when a new thing is sent, pushing the packet into the send
queue and re-enabling the interrupt will trigger the interrupt again, which can then take care of the sending.
*/
@ -67,8 +67,8 @@ typedef struct spi_device_t spi_device_t;
/// struct to hold private transaction data (like tx and rx buffer for DMA).
typedef struct {
spi_transaction_t *trans;
typedef struct {
spi_transaction_t *trans;
uint32_t *buffer_to_send; //equals to tx_data, if SPI_TRANS_USE_RXDATA is applied; otherwise if original buffer wasn't in DMA-capable memory, this gets the address of a temporary buffer that is;
//otherwise sets to the original buffer or NULL if no buffer is assigned.
uint32_t *buffer_to_rcv; // similar to buffer_to_send
@ -140,10 +140,10 @@ esp_err_t spi_bus_initialize(spi_host_device_t host, const spi_bus_config_t *bus
goto nomem;
}
#endif //CONFIG_PM_ENABLE
spicommon_bus_initialize_io(host, bus_config, dma_chan, SPICOMMON_BUSFLAG_MASTER|SPICOMMON_BUSFLAG_QUAD, &native);
spihost[host]->no_gpio_matrix=native;
spihost[host]->dma_chan=dma_chan;
if (dma_chan == 0) {
spihost[host]->max_transfer_sz = 32;
@ -180,7 +180,7 @@ esp_err_t spi_bus_initialize(spi_host_device_t host, const spi_bus_config_t *bus
spihost[host]->hw->slave.wr_sta_inten=0;
//Force a transaction done interrupt. This interrupt won't fire yet because we initialized the SPI interrupt as
//disabled. This way, we can just enable the SPI interrupt and the interrupt handler will kick in, handling
//disabled. This way, we can just enable the SPI interrupt and the interrupt handler will kick in, handling
//any transactions that are queued.
spihost[host]->hw->slave.trans_inten=1;
spihost[host]->hw->slave.trans_done=1;
@ -271,7 +271,6 @@ esp_err_t spi_bus_add_device(spi_host_device_t host, spi_device_interface_config
//Set CS pin, CS options
if (dev_config->spics_io_num >= 0) {
gpio_set_direction(dev_config->spics_io_num, GPIO_MODE_OUTPUT);
spicommon_cs_initialize(host, dev_config->spics_io_num, freecs, spihost[host]->no_gpio_matrix == false);
}
if (dev_config->flags&SPI_DEVICE_CLK_AS_CS) {
@ -397,7 +396,7 @@ static void IRAM_ATTR spi_intr(void *arg)
/*------------ deal with the in-flight transaction -----------------*/
if (host->cur_cs != NO_CS) {
spi_transaction_t *cur_trans = host->cur_trans_buf.trans;
//Okay, transaction is done.
//Okay, transaction is done.
if (host->cur_trans_buf.buffer_to_rcv && host->dma_chan == 0 ) {
//Need to copy from SPI regs to result buffer.
for (int x=0; x < cur_trans->rxlength; x+=32) {
@ -411,7 +410,7 @@ static void IRAM_ATTR spi_intr(void *arg)
//Call post-transaction callback, if any
if (host->device[host->cur_cs]->cfg.post_cb) host->device[host->cur_cs]->cfg.post_cb(cur_trans);
//Return transaction descriptor.
xQueueSendFromISR(host->device[host->cur_cs]->ret_queue, &host->cur_trans_buf, &do_yield);
xQueueSendFromISR(host->device[host->cur_cs]->ret_queue, &host->cur_trans_buf, &do_yield);
prevCs=host->cur_cs;
host->cur_cs = NO_CS;
}
@ -443,7 +442,7 @@ static void IRAM_ATTR spi_intr(void *arg)
host->cur_cs=i;
//We should be done with the transmission.
assert(host->hw->cmd.usr == 0);
//Reconfigure according to device settings, but only if we change CSses.
if (i!=prevCs) {
//Assumes a hardcoded 80MHz Fapb for now. ToDo: figure out something better once we have
@ -453,7 +452,7 @@ static void IRAM_ATTR spi_intr(void *arg)
//Configure bit order
host->hw->ctrl.rd_bit_order=(dev->cfg.flags & SPI_DEVICE_RXBIT_LSBFIRST)?1:0;
host->hw->ctrl.wr_bit_order=(dev->cfg.flags & SPI_DEVICE_TXBIT_LSBFIRST)?1:0;
//Configure polarity
//SPI iface needs to be configured for a delay in some cases.
int nodelay=0;
@ -548,7 +547,7 @@ static void IRAM_ATTR spi_intr(void *arg)
host->hw->dma_in_link.start=1;
}
} else {
//DMA temporary workaround: let RX DMA work somehow to avoid the issue in ESP32 v0/v1 silicon
//DMA temporary workaround: let RX DMA work somehow to avoid the issue in ESP32 v0/v1 silicon
if (host->dma_chan != 0 ) {
host->hw->dma_in_link.addr=0;
host->hw->dma_in_link.start=1;
@ -601,17 +600,38 @@ static void IRAM_ATTR spi_intr(void *arg)
host->hw->user.usr_addr=addrlen?1:0;
host->hw->user.usr_command=cmdlen?1:0;
// output command will be sent from bit 7 to 0 of command_value, and then bit 15 to 8 of the same register field.
if ((dev->cfg.flags & SPI_DEVICE_TXBIT_LSBFIRST)==0) {
/* Output command will be sent from bit 7 to 0 of command_value, and
* then bit 15 to 8 of the same register field. Shift and swap to send
* more straightly.
*/
uint16_t command = trans->cmd << (16-cmdlen); //shift to MSB
host->hw->user2.usr_command_value = (command>>8)|(command<<8); //swap the first and second byte
// shift the address to MSB of addr (and maybe slv_wr_status) register.
// output address will be sent from MSB to LSB of addr register, then comes the MSB to LSB of slv_wr_status register.
if (addrlen>32) {
host->hw->addr = trans->addr >> (addrlen- 32);
// shift the address to MSB of addr (and maybe slv_wr_status) register.
// output address will be sent from MSB to LSB of addr register, then comes the MSB to LSB of slv_wr_status register.
if (addrlen > 32) {
host->hw->addr = trans->addr >> (addrlen - 32);
host->hw->slv_wr_status = trans->addr << (64 - addrlen);
} else {
host->hw->addr = trans->addr << (32 - addrlen);
}
} else {
/* The output command start from bit0 to bit 15, kept as is.
* The output address start from the LSB of the highest byte, i.e.
* addr[24] -> addr[31]
* ...
* addr[0] -> addr[7]
* slv_wr_status[24] -> slv_wr_status[31]
* ...
* slv_wr_status[0] -> slv_wr_status[7]
* So swap the byte order to let the LSB sent first.
*/
host->hw->user2.usr_command_value = trans->cmd;
uint64_t addr = __builtin_bswap64(trans->addr);
host->hw->addr = addr>>32;
host->hw->slv_wr_status = addr;
}
host->hw->user.usr_mosi=( (!(dev->cfg.flags & SPI_DEVICE_HALFDUPLEX) && trans_buf->buffer_to_rcv) || trans_buf->buffer_to_send)?1:0;
host->hw->user.usr_miso=(trans_buf->buffer_to_rcv)?1:0;
@ -630,13 +650,13 @@ esp_err_t spi_device_queue_trans(spi_device_handle_t handle, spi_transaction_t *
esp_err_t ret = ESP_OK;
BaseType_t r;
SPI_CHECK(handle!=NULL, "invalid dev handle", ESP_ERR_INVALID_ARG);
//check transmission length
//check transmission length
SPI_CHECK((trans_desc->flags & SPI_TRANS_USE_RXDATA)==0 ||trans_desc->rxlength <= 32, "rxdata transfer > 32 bits without configured DMA", ESP_ERR_INVALID_ARG);
SPI_CHECK((trans_desc->flags & SPI_TRANS_USE_TXDATA)==0 ||trans_desc->length <= 32, "txdata transfer > 32 bits without configured DMA", ESP_ERR_INVALID_ARG);
SPI_CHECK(trans_desc->length <= handle->host->max_transfer_sz*8, "txdata transfer > host maximum", ESP_ERR_INVALID_ARG);
SPI_CHECK(trans_desc->rxlength <= handle->host->max_transfer_sz*8, "rxdata transfer > host maximum", ESP_ERR_INVALID_ARG);
SPI_CHECK((handle->cfg.flags & SPI_DEVICE_HALFDUPLEX) || trans_desc->rxlength <= trans_desc->length, "rx length > tx length in full duplex mode", ESP_ERR_INVALID_ARG);
//check working mode
//check working mode
SPI_CHECK(!((trans_desc->flags & (SPI_TRANS_MODE_DIO|SPI_TRANS_MODE_QIO)) && (handle->cfg.flags & SPI_DEVICE_3WIRE)), "incompatible iface params", ESP_ERR_INVALID_ARG);
SPI_CHECK(!((trans_desc->flags & (SPI_TRANS_MODE_DIO|SPI_TRANS_MODE_QIO)) && (!(handle->cfg.flags & SPI_DEVICE_HALFDUPLEX))), "incompatible iface params", ESP_ERR_INVALID_ARG);
SPI_CHECK( !(handle->cfg.flags & SPI_DEVICE_HALFDUPLEX) || handle->host->dma_chan == 0 || !(trans_desc->flags & SPI_TRANS_USE_RXDATA || trans_desc->rx_buffer != NULL)
@ -655,7 +675,7 @@ esp_err_t spi_device_queue_trans(spi_device_handle_t handle, spi_transaction_t *
// rx memory assign
if ( trans_desc->flags & SPI_TRANS_USE_RXDATA ) {
trans_buf.buffer_to_rcv = (uint32_t*)&trans_desc->rx_data[0];
} else {
} else {
//if not use RXDATA neither rx_buffer, buffer_to_rcv assigned to NULL
trans_buf.buffer_to_rcv = trans_desc->rx_buffer;
}
@ -668,12 +688,12 @@ esp_err_t spi_device_queue_trans(spi_device_handle_t handle, spi_transaction_t *
goto clean_up;
}
}
const uint32_t *txdata;
// tx memory assign
if ( trans_desc->flags & SPI_TRANS_USE_TXDATA ) {
txdata = (uint32_t*)&trans_desc->tx_data[0];
} else {
} else {
//if not use TXDATA neither tx_buffer, tx data assigned to NULL
txdata = trans_desc->tx_buffer ;
}
@ -686,11 +706,11 @@ esp_err_t spi_device_queue_trans(spi_device_handle_t handle, spi_transaction_t *
goto clean_up;
}
memcpy( trans_buf.buffer_to_send, txdata, (trans_desc->length+7)/8 );
} else {
} else {
// else use the original buffer (forced-conversion) or assign to NULL
trans_buf.buffer_to_send = (uint32_t*)txdata;
}
#ifdef CONFIG_PM_ENABLE
esp_pm_lock_acquire(handle->host->pm_lock);
#endif
@ -710,10 +730,10 @@ clean_up:
// free malloc-ed buffer (if needed) before return.
if ( (void*)trans_buf.buffer_to_rcv != trans_desc->rx_buffer && (void*)trans_buf.buffer_to_rcv != &trans_desc->rx_data[0] ) {
free( trans_buf.buffer_to_rcv );
}
}
if ( (void*)trans_buf.buffer_to_send!= trans_desc->tx_buffer && (void*)trans_buf.buffer_to_send != &trans_desc->tx_data[0] ) {
free( trans_buf.buffer_to_send );
}
}
assert( ret != ESP_OK );
return ret;
}
@ -722,12 +742,12 @@ esp_err_t spi_device_get_trans_result(spi_device_handle_t handle, spi_transactio
{
BaseType_t r;
spi_trans_priv trans_buf;
SPI_CHECK(handle!=NULL, "invalid dev handle", ESP_ERR_INVALID_ARG);
r=xQueueReceive(handle->ret_queue, (void*)&trans_buf, ticks_to_wait);
if (!r) {
// The memory occupied by rx and tx DMA buffer destroyed only when receiving from the queue (transaction finished).
// If timeout, wait and retry.
// If timeout, wait and retry.
// Every on-flight transaction request occupies internal memory as DMA buffer if needed.
return ESP_ERR_TIMEOUT;
}
@ -736,12 +756,12 @@ esp_err_t spi_device_get_trans_result(spi_device_handle_t handle, spi_transactio
if ( (void*)trans_buf.buffer_to_send != &(*trans_desc)->tx_data[0] && trans_buf.buffer_to_send != (*trans_desc)->tx_buffer ) {
free( trans_buf.buffer_to_send );
}
}
//copy data from temporary DMA-capable buffer back to IRAM buffer and free the temporary one.
if ( (void*)trans_buf.buffer_to_rcv != &(*trans_desc)->rx_data[0] && trans_buf.buffer_to_rcv != (*trans_desc)->rx_buffer ) {
if ( (*trans_desc)->flags & SPI_TRANS_USE_RXDATA ) {
memcpy( (uint8_t*)&(*trans_desc)->rx_data[0], trans_buf.buffer_to_rcv, ((*trans_desc)->rxlength+7)/8 );
memcpy( (uint8_t*)&(*trans_desc)->rx_data[0], trans_buf.buffer_to_rcv, ((*trans_desc)->rxlength+7)/8 );
} else {
memcpy( (*trans_desc)->rx_buffer, trans_buf.buffer_to_rcv, ((*trans_desc)->rxlength+7)/8 );
}

View file

@ -96,7 +96,6 @@ esp_err_t spi_slave_initialize(spi_host_device_t host, const spi_bus_config_t *b
spihost[host]->id = host;
spicommon_bus_initialize_io(host, bus_config, dma_chan, SPICOMMON_BUSFLAG_SLAVE, &native);
gpio_set_direction(slave_config->spics_io_num, GPIO_MODE_INPUT);
spicommon_cs_initialize(host, slave_config->spics_io_num, 0, native==false);
// The slave DMA suffers from unexpected transactions. Forbid reading if DMA is enabled by disabling the CS line.
if (dma_chan != 0) spicommon_freeze_cs(host);

View file

@ -390,7 +390,7 @@ TEST_CASE("SPI Master DMA test, TX and RX in different regions", "[spi]")
trans[4].rxlength = 8*4;
trans[4].tx_buffer = data_drom;
trans[4].flags = SPI_TRANS_USE_RXDATA;
trans[5].length = 8*4;
trans[5].flags = SPI_TRANS_USE_RXDATA | SPI_TRANS_USE_TXDATA;
@ -412,7 +412,7 @@ TEST_CASE("SPI Master DMA test, TX and RX in different regions", "[spi]")
}
static inline void int_connect( uint32_t gpio, uint32_t sigo, uint32_t sigi )
static inline void int_connect( uint32_t gpio, uint32_t sigo, uint32_t sigi )
{
gpio_matrix_out( gpio, sigo, false, false );
gpio_matrix_in( gpio, sigi, false );
@ -430,7 +430,7 @@ TEST_CASE("SPI Master DMA test: length, start, not aligned", "[spi]")
esp_err_t ret;
spi_device_handle_t spi;
spi_bus_config_t buscfg={
.miso_io_num=PIN_NUM_MISO,
.miso_io_num=PIN_NUM_MISO,
.mosi_io_num=PIN_NUM_MOSI,
.sclk_io_num=PIN_NUM_CLK,
.quadwp_io_num=-1,
@ -441,7 +441,7 @@ TEST_CASE("SPI Master DMA test: length, start, not aligned", "[spi]")
.mode=0, //SPI mode 0
.spics_io_num=PIN_NUM_CS, //CS pin
.queue_size=7, //We want to be able to queue 7 transactions at a time
.pre_cb=NULL,
.pre_cb=NULL,
};
//Initialize the SPI bus
ret=spi_bus_initialize(HSPI_HOST, &buscfg, 1);
@ -454,14 +454,14 @@ TEST_CASE("SPI Master DMA test: length, start, not aligned", "[spi]")
int_connect( PIN_NUM_MOSI, HSPID_OUT_IDX, HSPIQ_IN_IDX );
memset(rx_buf, 0x66, 320);
for ( int i = 0; i < 8; i ++ ) {
memset( rx_buf, 0x66, sizeof(rx_buf));
spi_transaction_t t = {};
t.length = 8*(i+1);
t.rxlength = 0;
t.tx_buffer = tx_buf+2*i;
t.tx_buffer = tx_buf+2*i;
t.rx_buffer = rx_buf + i;
if ( i == 1 ) {
@ -470,7 +470,7 @@ TEST_CASE("SPI Master DMA test: length, start, not aligned", "[spi]")
} else if ( i == 2 ) {
//test rx length != tx_length
t.rxlength = t.length - 8;
}
}
spi_device_transmit( spi, &t );
for( int i = 0; i < 16; i ++ ) {
@ -486,7 +486,7 @@ TEST_CASE("SPI Master DMA test: length, start, not aligned", "[spi]")
} else {
//normal check
TEST_ASSERT( memcmp(t.tx_buffer, t.rx_buffer, t.length/8)==0 );
}
}
}
TEST_ASSERT(spi_bus_remove_device(spi) == ESP_OK);
@ -495,14 +495,15 @@ TEST_CASE("SPI Master DMA test: length, start, not aligned", "[spi]")
static const char MASTER_TAG[] = "test_master";
static const char SLAVE_TAG[] = "test_slave";
DRAM_ATTR static uint8_t master_send[] = {0x93, 0x34, 0x56, 0x78, 0x9a, 0xbc, 0xde, 0xf0, 0xaa, 0xcc, 0xff, 0xee, 0x55, 0x77, 0x88, 0x43};
//DRAM_ATTR static uint8_t master_send[] = {0x93, 0x34, 0x56, 0x78, 0x9a, 0xbc, 0xde, 0xf0, 0xaa, 0xcc, 0xff, 0xee, 0x55, 0x77, 0x88, 0x43};
DRAM_ATTR static uint8_t slave_send[] = { 0xaa, 0xdc, 0xba, 0x98, 0x76, 0x54, 0x32, 0x10, 0x13, 0x57, 0x9b, 0xdf, 0x24, 0x68, 0xac, 0xe0 };
/*
static void master_init( spi_device_handle_t* spi, int mode, uint32_t speed)
{
esp_err_t ret;
spi_bus_config_t buscfg={
.miso_io_num=PIN_NUM_MISO,
.miso_io_num=PIN_NUM_MISO,
.mosi_io_num=PIN_NUM_MOSI,
.sclk_io_num=PIN_NUM_CLK,
.quadwp_io_num=-1,
@ -513,7 +514,7 @@ static void master_init( spi_device_handle_t* spi, int mode, uint32_t speed)
.mode=mode, //SPI mode 0
.spics_io_num=PIN_NUM_CS, //CS pin
.queue_size=16, //We want to be able to queue 7 transactions at a time
.pre_cb=NULL,
.pre_cb=NULL,
.cs_ena_pretrans = 0,
};
//Initialize the SPI bus
@ -546,6 +547,7 @@ static void slave_init(int mode, int dma_chan)
//Initialize SPI slave interface
TEST_ESP_OK( spi_slave_initialize(VSPI_HOST, &buscfg, &slvcfg, dma_chan) );
}
*/
typedef struct {
uint32_t len;
@ -604,6 +606,7 @@ static void task_slave(void* arg)
t.tx_buffer = txdata.start;
t.rx_buffer = recvbuf+4;
//loop until trans_len != 0 to skip glitches
memset(recvbuf, 0x66, sizeof(recvbuf));
do {
TEST_ESP_OK( spi_slave_transmit( VSPI_HOST, &t, portMAX_DELAY ) );
} while ( t.trans_len == 0 );
@ -613,118 +616,177 @@ static void task_slave(void* arg)
}
}
TEST_CASE("SPI master variable cmd & addr test","[spi]")
#define TEST_SPI_HOST HSPI_HOST
#define TEST_SLAVE_HOST VSPI_HOST
static uint8_t bitswap(uint8_t in)
{
uint8_t *tx_buf=master_send;
uint8_t rx_buf[320];
uint8_t *rx_buf_ptr = rx_buf;
uint8_t out = 0;
for (int i = 0; i < 8; i++) {
out = out >> 1;
if (in&0x80) out |= 0x80;
in = in << 1;
}
return out;
}
spi_slave_task_context_t slave_context = {};
esp_err_t err = init_slave_context( &slave_context );
TEST_ASSERT( err == ESP_OK );
#define SPI_BUS_TEST_DEFAULT_CONFIG() {\
.miso_io_num=PIN_NUM_MISO, \
.mosi_io_num=PIN_NUM_MOSI,\
.sclk_io_num=PIN_NUM_CLK,\
.quadwp_io_num=-1,\
.quadhd_io_num=-1\
}
#define SPI_DEVICE_TEST_DEFAULT_CONFIG() {\
.clock_speed_hz=10*1000*1000,\
.mode=0,\
.spics_io_num=PIN_NUM_CS,\
.queue_size=16,\
.pre_cb=NULL, \
.cs_ena_pretrans = 0,\
.cs_ena_posttrans = 0,\
}
#define SPI_SLAVE_TEST_DEFAULT_CONFIG() {\
.mode=0,\
.spics_io_num=PIN_NUM_CS,\
.queue_size=3,\
.flags=0,\
}
void test_cmd_addr(spi_slave_task_context_t *slave_context, bool lsb_first)
{
spi_device_handle_t spi;
//initial master, mode 0, 1MHz
master_init( &spi, 0, 1*1000*1000 );
//initial slave, mode 0, no dma
slave_init(0, 0);
ESP_LOGI(MASTER_TAG, ">>>>>>>>> TEST %s FIRST <<<<<<<<<<<", lsb_first?"LSB":"MSB");
//do internal connection
//initial master, mode 0, 1MHz
spi_bus_config_t buscfg=SPI_BUS_TEST_DEFAULT_CONFIG();
TEST_ESP_OK(spi_bus_initialize(TEST_SPI_HOST, &buscfg, 1));
spi_device_interface_config_t devcfg=SPI_DEVICE_TEST_DEFAULT_CONFIG();
devcfg.clock_speed_hz = 1*1000*1000;
if (lsb_first) devcfg.flags |= SPI_DEVICE_BIT_LSBFIRST;
TEST_ESP_OK(spi_bus_add_device(TEST_SPI_HOST, &devcfg, &spi));
//connecting pins to two peripherals breaks the output, fix it.
int_connect( PIN_NUM_MOSI, HSPID_OUT_IDX, VSPIQ_IN_IDX );
int_connect( PIN_NUM_MISO, VSPIQ_OUT_IDX, HSPID_IN_IDX );
int_connect( PIN_NUM_CS, HSPICS0_OUT_IDX, VSPICS0_IN_IDX );
int_connect( PIN_NUM_CLK, HSPICLK_OUT_IDX, VSPICLK_IN_IDX );
for (int i= 0; i < 8; i++) {
//prepare slave tx data
slave_txdata_t slave_txdata = (slave_txdata_t) {
.start = slave_send,
.len = 256,
};
xQueueSend(slave_context->data_to_send, &slave_txdata, portMAX_DELAY);
vTaskDelay(50);
//prepare master tx data
int cmd_bits = (i+1)*2;
int addr_bits = 56-8*i;
int round_up = (cmd_bits+addr_bits+7)/8*8;
addr_bits = round_up - cmd_bits;
spi_transaction_ext_t trans = (spi_transaction_ext_t) {
.base = {
.flags = SPI_TRANS_VARIABLE_CMD | SPI_TRANS_VARIABLE_ADDR,
.addr = 0x456789abcdef0123,
.cmd = 0xcdef,
},
.command_bits = cmd_bits,
.address_bits = addr_bits,
};
ESP_LOGI( MASTER_TAG, "===== test%d =====", i );
ESP_LOGI(MASTER_TAG, "cmd_bits %d, addr_bits: %d", cmd_bits, addr_bits);
TEST_ESP_OK(spi_device_transmit(spi, (spi_transaction_t*)&trans));
//wait for both master and slave end
size_t rcv_len;
slave_rxdata_t *rcv_data = xRingbufferReceive(slave_context->data_received, &rcv_len, portMAX_DELAY);
rcv_len-=4;
uint8_t *buffer = rcv_data->data;
ESP_LOGI(SLAVE_TAG, "trans_len: %d", rcv_len);
TEST_ASSERT_EQUAL(rcv_len, (rcv_data->len+7)/8);
TEST_ASSERT_EQUAL(rcv_data->len, cmd_bits+addr_bits);
ESP_LOG_BUFFER_HEX("slave rx", buffer, rcv_len);
uint16_t cmd_expected = trans.base.cmd & (BIT(cmd_bits) - 1);
uint64_t addr_expected = trans.base.addr & ((1ULL<<addr_bits) - 1);
uint8_t *data_ptr = buffer;
uint16_t cmd_got = *(uint16_t*)data_ptr;
data_ptr += cmd_bits/8;
cmd_got = __builtin_bswap16(cmd_got);
cmd_got = cmd_got >> (16-cmd_bits);
int remain_bits = cmd_bits % 8;
uint64_t addr_got = *(uint64_t*)data_ptr;
data_ptr += 8;
addr_got = __builtin_bswap64(addr_got);
addr_got = (addr_got << remain_bits);
addr_got |= (*data_ptr >> (8-remain_bits));
addr_got = addr_got >> (64-addr_bits);
if (lsb_first) {
cmd_got = __builtin_bswap16(cmd_got);
addr_got = __builtin_bswap64(addr_got);
uint8_t *swap_ptr = (uint8_t*)&cmd_got;
swap_ptr[0] = bitswap(swap_ptr[0]);
swap_ptr[1] = bitswap(swap_ptr[1]);
cmd_got = cmd_got >> (16-cmd_bits);
swap_ptr = (uint8_t*)&addr_got;
for (int j = 0; j < 8; j++) swap_ptr[j] = bitswap(swap_ptr[j]);
addr_got = addr_got >> (64-addr_bits);
}
ESP_LOGI(SLAVE_TAG, "cmd_got: %04X, addr_got: %08X%08X", cmd_got, (uint32_t)(addr_got>>32), (uint32_t)addr_got);
TEST_ASSERT_EQUAL_HEX16(cmd_expected, cmd_got);
if (addr_bits > 0) {
TEST_ASSERT_EQUAL_HEX32(addr_expected, addr_got);
TEST_ASSERT_EQUAL_HEX32(addr_expected >> 8, addr_got >> 8);
}
//clean
vRingbufferReturnItem(slave_context->data_received, buffer);
}
TEST_ASSERT(spi_bus_remove_device(spi) == ESP_OK);
TEST_ASSERT(spi_bus_free(TEST_SPI_HOST) == ESP_OK);
}
TEST_CASE("SPI master variable cmd & addr test","[spi]")
{
spi_slave_task_context_t slave_context = {};
esp_err_t err = init_slave_context( &slave_context );
TEST_ASSERT( err == ESP_OK );
TaskHandle_t handle_slave;
xTaskCreate( task_slave, "spi_slave", 4096, &slave_context, 0, &handle_slave);
slave_txdata_t slave_txdata[16];
spi_transaction_ext_t trans[16];
for( int i= 0; i < 16; i ++ ) {
//prepare slave tx data
slave_txdata[i] = (slave_txdata_t) {
.start = slave_send + 4*(i%3),
.len = 256,
};
xQueueSend( slave_context.data_to_send, &slave_txdata[i], portMAX_DELAY );
//prepare master tx data
trans[i] = (spi_transaction_ext_t) {
.base = {
.flags = SPI_TRANS_VARIABLE_CMD | SPI_TRANS_VARIABLE_ADDR,
.addr = 0x456789ab,
.cmd = 0xcdef,
//initial slave, mode 0, no dma
int dma_chan = 0;
int slave_mode = 0;
spi_bus_config_t slv_buscfg=SPI_BUS_TEST_DEFAULT_CONFIG();
spi_slave_interface_config_t slvcfg=SPI_SLAVE_TEST_DEFAULT_CONFIG();
slvcfg.mode = slave_mode;
//Initialize SPI slave interface
TEST_ESP_OK( spi_slave_initialize(TEST_SLAVE_HOST, &slv_buscfg, &slvcfg, dma_chan) );
.length = 8*i,
.tx_buffer = tx_buf+i,
.rx_buffer = rx_buf_ptr,
},
.command_bits = ((i+1)%3) * 8,
.address_bits = ((i/3)%5) * 8,
};
if ( trans[i].base.length == 0 ) {
trans[i].base.tx_buffer = NULL;
trans[i].base.rx_buffer = NULL;
} else {
rx_buf_ptr += (trans[i].base.length + 31)/32*4;
}
}
vTaskDelay(10);
for ( int i = 0; i < 16; i ++ ) {
TEST_ESP_OK (spi_device_queue_trans( spi, (spi_transaction_t*)&trans[i], portMAX_DELAY ) );
vTaskDelay(10);
}
for( int i= 0; i < 16; i ++ ) {
//wait for both master and slave end
ESP_LOGI( MASTER_TAG, "===== test%d =====", i );
spi_transaction_ext_t *t;
size_t rcv_len;
spi_device_get_trans_result( spi, (spi_transaction_t**)&t, portMAX_DELAY );
TEST_ASSERT( t == &trans[i] );
if ( trans[i].base.length != 0 ) {
ESP_LOG_BUFFER_HEX( "master tx", trans[i].base.tx_buffer, trans[i].base.length/8 );
ESP_LOG_BUFFER_HEX( "master rx", trans[i].base.rx_buffer, trans[i].base.length/8 );
} else {
ESP_LOGI( "master tx", "no data" );
ESP_LOGI( "master rx", "no data" );
}
slave_rxdata_t *rcv_data = xRingbufferReceive( slave_context.data_received, &rcv_len, portMAX_DELAY );
uint8_t *buffer = rcv_data->data;
rcv_len = rcv_data->len;
ESP_LOGI(SLAVE_TAG, "trans_len: %d", rcv_len);
ESP_LOG_BUFFER_HEX( "slave tx", slave_txdata[i].start, (rcv_len+7)/8);
ESP_LOG_BUFFER_HEX( "slave rx", buffer, (rcv_len+7)/8);
//check result
uint8_t *ptr_addr = (uint8_t*)&t->base.addr;
uint8_t *ptr_cmd = (uint8_t*)&t->base.cmd;
for ( int j = 0; j < t->command_bits/8; j ++ ) {
TEST_ASSERT_EQUAL( buffer[j], ptr_cmd[t->command_bits/8-j-1] );
}
for ( int j = 0; j < t->address_bits/8; j ++ ) {
TEST_ASSERT_EQUAL( buffer[t->command_bits/8+j], ptr_addr[t->address_bits/8-j-1] );
}
if ( t->base.length != 0) {
TEST_ASSERT_EQUAL_HEX8_ARRAY(t->base.tx_buffer, buffer + (t->command_bits + t->address_bits)/8, t->base.length/8);
TEST_ASSERT_EQUAL_HEX8_ARRAY(slave_txdata[i].start + (t->command_bits + t->address_bits)/8, t->base.rx_buffer, t->base.length/8);
}
TEST_ASSERT_EQUAL( t->base.length + t->command_bits + t->address_bits, rcv_len );
//clean
vRingbufferReturnItem( slave_context.data_received, buffer );
}
test_cmd_addr(&slave_context, false);
test_cmd_addr(&slave_context, true);
vTaskDelete( handle_slave );
handle_slave = 0;
deinit_slave_context(&slave_context);
TEST_ASSERT(spi_slave_free(VSPI_HOST) == ESP_OK);
TEST_ASSERT(spi_bus_remove_device(spi) == ESP_OK);
TEST_ASSERT(spi_bus_free(HSPI_HOST) == ESP_OK);
TEST_ASSERT(spi_slave_free(TEST_SLAVE_HOST) == ESP_OK);
ESP_LOGI(MASTER_TAG, "test passed.");
}