further optimizations
- extend read function to 16bit - add repeated write the same byte/word a specified number of time - revert increment option to dmaSend
This commit is contained in:
parent
b2e349ca36
commit
e7456e1916
|
@ -93,16 +93,21 @@ void spi_slave_enable(spi_dev *dev, spi_mode mode, uint32 flags) {
|
|||
* @return Number of elements transmitted.
|
||||
*/
|
||||
uint32 spi_tx(spi_dev *dev, const void *buf, uint32 len) {
|
||||
uint32 txed = 0;
|
||||
uint8 byte_frame = spi_dff(dev) == SPI_DFF_8_BIT;
|
||||
while ( txed < len ) {
|
||||
while ( spi_is_tx_empty(dev)==0 ); // wait Tx to be empty
|
||||
if (byte_frame) {
|
||||
dev->regs->DR = ((const uint8*)buf)[txed++];
|
||||
} else {
|
||||
dev->regs->DR = ((const uint16*)buf)[txed++];
|
||||
}
|
||||
}
|
||||
uint32 txed = len;
|
||||
spi_reg_map *regs = dev->regs;
|
||||
if ( spi_dff(dev) == SPI_DFF_8_BIT ) {
|
||||
const uint8 * dp8 = (const uint8*)buf;
|
||||
while ( len-- ) {
|
||||
while ( (regs->SR & SPI_SR_TXE)==0 ) ; //while ( spi_is_tx_empty(dev)==0 ); // wait Tx to be empty
|
||||
regs->DR = *dp8++;
|
||||
}
|
||||
} else {
|
||||
const uint16 * dp16 = (const uint16*)buf;
|
||||
while ( len-- ) {
|
||||
while ( (regs->SR & SPI_SR_TXE)==0 ) ; //while ( spi_is_tx_empty(dev)==0 ); // wait Tx to be empty
|
||||
regs->DR = *dp16++;
|
||||
}
|
||||
}
|
||||
return txed;
|
||||
}
|
||||
|
||||
|
@ -163,6 +168,5 @@ static void spi_reconfigure(spi_dev *dev, uint32 cr1_config) {
|
|||
spi_irq_disable(dev, SPI_INTERRUPTS_ALL);
|
||||
if ( (dev->regs->CR1&MASK)!=(cr1_config&MASK) ) spi_peripheral_disable(dev);
|
||||
dev->regs->CR1 = cr1_config;
|
||||
//spi_rx_dma_enable(dev);
|
||||
spi_peripheral_enable(dev);
|
||||
}
|
||||
|
|
|
@ -160,7 +160,7 @@ void SPIClass::begin(void) {
|
|||
void SPIClass::beginSlave(void) {
|
||||
spi_init(_currentSetting->spi_d);
|
||||
configure_gpios(_currentSetting->spi_d, 0);
|
||||
uint32 flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_SW_SLAVE);
|
||||
uint32 flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_RX_ONLY);
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.print("spi_slave_enable("); Serial.print(_currentSetting->dataMode); Serial.print(","); Serial.print(flags); Serial.println(")");
|
||||
#endif
|
||||
|
@ -306,10 +306,10 @@ void SPIClass::endTransaction(void)
|
|||
* I/O
|
||||
*/
|
||||
|
||||
uint8 SPIClass::read(void)
|
||||
uint16 SPIClass::read(void)
|
||||
{
|
||||
while ( spi_is_rx_nonempty(_currentSetting->spi_d)==0 ) ;
|
||||
return (uint8)spi_rx_reg(_currentSetting->spi_d);
|
||||
return (uint16)spi_rx_reg(_currentSetting->spi_d);
|
||||
}
|
||||
|
||||
void SPIClass::read(uint8 *buf, uint32 len)
|
||||
|
@ -321,7 +321,7 @@ void SPIClass::read(uint8 *buf, uint32 len)
|
|||
while ( rxed < len) {
|
||||
regs->DR = 0x00FF; // " write the data item to be transmitted into the SPI_DR register (this clears the TXE flag)."
|
||||
while ( (regs->SR & SPI_SR_RXNE)==0 ) ; // wait till data is available in the Rx register
|
||||
buf[rxed++] = (uint8)(regs->DR); // read and store the received byte
|
||||
*buf++ = (regs->DR); // read and store the received byte
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -332,11 +332,21 @@ void SPIClass::write(uint16 data)
|
|||
* by taking the Tx code from transfer(byte)
|
||||
* This almost doubles the speed of this function.
|
||||
*/
|
||||
spi_tx_reg(_currentSetting->spi_d, data); // "2. Write the first data item to be transmitted into the SPI_DR register (this clears the TXE flag)."
|
||||
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
|
||||
spi_tx_reg(_currentSetting->spi_d, data); // write the data to be transmitted into the SPI_DR register (this clears the TXE flag)
|
||||
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
|
||||
}
|
||||
|
||||
void SPIClass::write(uint16 data, uint32 n)
|
||||
{
|
||||
// Added by stevstrong: Repeatedly send same data by the specified number of times
|
||||
spi_reg_map * regs = _currentSetting->spi_d->regs;
|
||||
while ( (n--)>0 ) {
|
||||
regs->DR = data; // write the data to be transmitted into the SPI_DR register (this clears the TXE flag)
|
||||
while ( (regs->SR & SPI_SR_TXE)==0 ) ; // wait till Tx empty
|
||||
}
|
||||
while ( (regs->SR & SPI_SR_BSY) != 0); // wait until BSY=0 before returning
|
||||
}
|
||||
|
||||
void SPIClass::write(const void *data, uint32 length)
|
||||
{
|
||||
spi_tx(_currentSetting->spi_d, data, length); // data can be array of bytes or words
|
||||
|
@ -346,13 +356,6 @@ void SPIClass::write(const void *data, uint32 length)
|
|||
uint16 b = spi_rx_reg(_currentSetting->spi_d); // dummy read, needed, don't remove!
|
||||
}
|
||||
|
||||
uint16_t SPIClass::transfer16(uint16_t wr_data) const {
|
||||
spi_tx_reg(_currentSetting->spi_d, wr_data); // "2. Write the first data item to be transmitted into the SPI_DR register (this clears the TXE flag)."
|
||||
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
|
||||
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
|
||||
return (uint16)spi_rx_reg(_currentSetting->spi_d); // "... and read the last received data."
|
||||
}
|
||||
|
||||
uint8 SPIClass::transfer(uint8 byte) const {
|
||||
spi_tx_reg(_currentSetting->spi_d, byte); // "2. Write the first data item to be transmitted into the SPI_DR register (this clears the TXE flag)."
|
||||
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
|
||||
|
@ -360,6 +363,13 @@ uint8 SPIClass::transfer(uint8 byte) const {
|
|||
return (uint8)spi_rx_reg(_currentSetting->spi_d); // "... and read the last received data."
|
||||
}
|
||||
|
||||
uint16_t SPIClass::transfer16(uint16_t wr_data) const {
|
||||
spi_tx_reg(_currentSetting->spi_d, wr_data); // "2. Write the first data item to be transmitted into the SPI_DR register (this clears the TXE flag)."
|
||||
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
|
||||
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
|
||||
return (uint16)spi_rx_reg(_currentSetting->spi_d); // "... and read the last received data."
|
||||
}
|
||||
|
||||
/* Roger Clark and Victor Perez, 2015
|
||||
* Performs a DMA SPI transfer with at least a receive buffer.
|
||||
* If a TX buffer is not provided, FF is sent over and over for the length of the transfer.
|
||||
|
@ -419,10 +429,10 @@ uint8 SPIClass::dmaTransfer(void * transmitBuf, void * receiveBuf, uint16 length
|
|||
* Still in progress.
|
||||
* 2016 - stevstrong - reworked to automatically detect bit size from SPI setting
|
||||
*/
|
||||
uint8 SPIClass::dmaSend(void * transmitBuf, uint16 length)
|
||||
uint8 SPIClass::dmaSend(void * transmitBuf, uint16 length, bool minc)
|
||||
{
|
||||
if (length == 0) return 0;
|
||||
uint32 flags = (DMA_MINC_MODE | DMA_FROM_MEM | DMA_TRNS_CMPLT);
|
||||
uint32 flags = ( (DMA_MINC_MODE*minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT);
|
||||
uint8 b = 0;
|
||||
// dma1_ch3_Active=true;
|
||||
dma_init(_currentSetting->spiDmaDev);
|
||||
|
@ -438,7 +448,7 @@ uint8 SPIClass::dmaSend(void * transmitBuf, uint16 length)
|
|||
|
||||
// while (dma1_ch3_Active);
|
||||
uint32_t m = millis();
|
||||
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & 0x2)==0) {//Avoid interrupts and just loop waiting for the flag to be set.
|
||||
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)==0) {//Avoid interrupts and just loop waiting for the flag to be set.
|
||||
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
|
||||
}
|
||||
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
|
||||
|
|
|
@ -115,6 +115,13 @@ public:
|
|||
init_MightInline(clock, bitOrder, dataMode, dataSize);
|
||||
}
|
||||
}
|
||||
SPISettings(uint32_t clock) {
|
||||
if (__builtin_constant_p(clock)) {
|
||||
init_AlwaysInline(clock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
|
||||
} else {
|
||||
init_MightInline(clock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
|
||||
}
|
||||
}
|
||||
SPISettings() { init_AlwaysInline(4000000, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT); }
|
||||
private:
|
||||
void init_MightInline(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) {
|
||||
|
@ -216,38 +223,38 @@ public:
|
|||
*/
|
||||
|
||||
/**
|
||||
* @brief Return the next unread byte.
|
||||
* @brief Return the next unread byte/word.
|
||||
*
|
||||
* If there is no unread byte waiting, this function will block
|
||||
* If there is no unread byte/word waiting, this function will block
|
||||
* until one is received.
|
||||
*/
|
||||
uint8 read(void);
|
||||
uint16 read(void);
|
||||
|
||||
/**
|
||||
* @brief Read length bytes, storing them into buffer.
|
||||
* @param buffer Buffer to store received bytes into.
|
||||
* @param length Number of bytes to store in buffer. This
|
||||
* @param length Number of bytes to store in buffer. This
|
||||
* function will block until the desired number of
|
||||
* bytes have been read.
|
||||
*/
|
||||
void read(uint8 *buffer, uint32 length);
|
||||
|
||||
/**
|
||||
* @brief Transmit a byte.
|
||||
* @param data Byte to transmit.
|
||||
*/
|
||||
// void write(uint8 data);
|
||||
|
||||
/**
|
||||
* @brief Transmit a half word.
|
||||
* @brief Transmit one byte/word.
|
||||
* @param data to transmit.
|
||||
*/
|
||||
void write(uint16 data);
|
||||
|
||||
/**
|
||||
* @brief Transmit multiple bytes.
|
||||
* @param buffer Bytes to transmit.
|
||||
* @param length Number of bytes in buffer to transmit.
|
||||
* @brief Transmit one byte/word a specified number of times.
|
||||
* @param data to transmit.
|
||||
*/
|
||||
void write(uint16 data, uint32 n);
|
||||
|
||||
/**
|
||||
* @brief Transmit multiple bytes/words.
|
||||
* @param buffer Bytes/words to transmit.
|
||||
* @param length Number of bytes/words in buffer to transmit.
|
||||
*/
|
||||
void write(const void * buffer, uint32 length);
|
||||
|
||||
|
@ -283,7 +290,7 @@ public:
|
|||
* @param data buffer half words to transmit,
|
||||
* @param length Number of bytes in buffer to transmit.
|
||||
*/
|
||||
uint8 dmaSend(void * transmitBuf, uint16 length);
|
||||
uint8 dmaSend(void * transmitBuf, uint16 length, bool minc = 1);
|
||||
|
||||
/*
|
||||
* Pin accessors
|
||||
|
|
Loading…
Reference in New Issue