Browse Source

Fix STM32F1 SPI warning (gcc 8.2.1) (#15104)

pull/1/head
Tanguy Pruvot 5 years ago
committed by Scott Lahteine
parent
commit
c014f8dc78
  1. 115
      Marlin/src/HAL/HAL_STM32F1/SPI.cpp

115
Marlin/src/HAL/HAL_STM32F1/SPI.cpp

@ -47,12 +47,7 @@
#warning "Unexpected clock speed; SPI frequency calculation will be incorrect" #warning "Unexpected clock speed; SPI frequency calculation will be incorrect"
#endif #endif
struct spi_pins { struct spi_pins { uint8_t nss, sck, miso, mosi; };
uint8_t nss;
uint8_t sck;
uint8_t miso;
uint8_t mosi;
};
static const spi_pins* dev_to_spi_pins(spi_dev *dev); static const spi_pins* dev_to_spi_pins(spi_dev *dev);
static void configure_gpios(spi_dev *dev, bool as_master); static void configure_gpios(spi_dev *dev, bool as_master);
@ -84,13 +79,13 @@ static const spi_pins board_spi_pins[] __FLASH__ = {
}; };
#if BOARD_NR_SPI >= 1 #if BOARD_NR_SPI >= 1
static void (*_spi1_this); static void *_spi1_this;
#endif #endif
#if BOARD_NR_SPI >= 2 #if BOARD_NR_SPI >= 2
static void (*_spi2_this); static void *_spi2_this;
#endif #endif
#if BOARD_NR_SPI >= 3 #if BOARD_NR_SPI >= 3
static void (*_spi3_this); static void *_spi3_this;
#endif #endif
/** /**
@ -149,7 +144,7 @@ SPIClass::SPIClass(uint32_t spi_num) {
_currentSetting->state = SPI_STATE_IDLE; _currentSetting->state = SPI_STATE_IDLE;
} }
/* /**
* Set up/tear down * Set up/tear down
*/ */
void SPIClass::updateSettings() { void SPIClass::updateSettings() {
@ -175,8 +170,7 @@ void SPIClass::beginSlave() {
} }
void SPIClass::end() { void SPIClass::end() {
if (!spi_is_enabled(_currentSetting->spi_d)) if (!spi_is_enabled(_currentSetting->spi_d)) return;
return;
// Follows RM0008's sequence for disabling a SPI in master/slave // Follows RM0008's sequence for disabling a SPI in master/slave
// full duplex mode. // full duplex mode.
@ -184,8 +178,8 @@ void SPIClass::end() {
// FIXME [0.1.0] remove this once you have an interrupt based driver // FIXME [0.1.0] remove this once you have an interrupt based driver
volatile uint16_t rx __attribute__((unused)) = spi_rx_reg(_currentSetting->spi_d); volatile uint16_t rx __attribute__((unused)) = spi_rx_reg(_currentSetting->spi_d);
} }
while (!spi_is_tx_empty(_currentSetting->spi_d)) {}; while (!spi_is_tx_empty(_currentSetting->spi_d)) { /* nada */ }
while (spi_is_busy(_currentSetting->spi_d)) {}; while (spi_is_busy(_currentSetting->spi_d)) { /* nada */ }
spi_peripheral_disable(_currentSetting->spi_d); spi_peripheral_disable(_currentSetting->spi_d);
// added for DMA callbacks. // added for DMA callbacks.
@ -207,9 +201,9 @@ void SPIClass::setBitOrder(BitOrder bitOrder) {
_currentSetting->spi_d->regs->CR1 = cr1; _currentSetting->spi_d->regs->CR1 = cr1;
} }
/* Victor Perez. Added to test changing datasize from 8 to 16 bit modes on the fly. /**
* Victor Perez. Added to test changing datasize from 8 to 16 bit modes on the fly.
* Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word. * Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word.
*
*/ */
void SPIClass::setDataSize(uint32_t datasize) { void SPIClass::setDataSize(uint32_t datasize) {
_currentSetting->dataSize = datasize; _currentSetting->dataSize = datasize;
@ -220,9 +214,11 @@ void SPIClass::setDataSize(uint32_t datasize) {
} }
void SPIClass::setDataMode(uint8_t dataMode) { void SPIClass::setDataMode(uint8_t dataMode) {
/* Notes: /*
As far as I can tell, the AVR numbers for dataMode appear to match the numbers required by the STM32 Notes:
As far as we know the AVR numbers for dataMode match the numbers required by the STM32.
From the AVR doc http://www.atmel.com/images/doc2585.pdf section 2.4 From the AVR doc http://www.atmel.com/images/doc2585.pdf section 2.4
SPI Mode CPOL CPHA Shift SCK-edge Capture SCK-edge SPI Mode CPOL CPHA Shift SCK-edge Capture SCK-edge
0 0 0 Falling Rising 0 0 0 Falling Rising
1 0 1 Rising Falling 1 0 1 Rising Falling
@ -265,13 +261,12 @@ void SPIClass::beginTransactionSlave(SPISettings settings) {
void SPIClass::endTransaction() { } void SPIClass::endTransaction() { }
/**
/*
* I/O * I/O
*/ */
uint16_t SPIClass::read() { uint16_t SPIClass::read() {
while ( spi_is_rx_nonempty(_currentSetting->spi_d)==0 ) ; while (!spi_is_rx_nonempty(_currentSetting->spi_d)) { /* nada */ }
return (uint16)spi_rx_reg(_currentSetting->spi_d); return (uint16)spi_rx_reg(_currentSetting->spi_d);
} }
@ -282,16 +277,16 @@ void SPIClass::read(uint8_t *buf, uint32_t len) {
// start sequence: write byte 0 // start sequence: write byte 0
regs->DR = 0x00FF; // write the first byte regs->DR = 0x00FF; // write the first byte
// main loop // main loop
while ( (--len) ) { while (--len) {
while( !(regs->SR & SPI_SR_TXE) ); // wait for TXE flag while(!(regs->SR & SPI_SR_TXE)) { /* nada */ } // wait for TXE flag
noInterrupts(); // go atomic level - avoid interrupts to surely get the previously received data noInterrupts(); // go atomic level - avoid interrupts to surely get the previously received data
regs->DR = 0x00FF; // write the next data item to be transmitted into the SPI_DR register. This clears the TXE flag. regs->DR = 0x00FF; // write the next data item to be transmitted into the SPI_DR register. This clears the TXE flag.
while ( !(regs->SR & SPI_SR_RXNE) ); // wait till data is available in the DR register while (!(regs->SR & SPI_SR_RXNE)) { /* nada */ } // wait till data is available in the DR register
*buf++ = (uint8)(regs->DR); // read and store the received byte. This clears the RXNE flag. *buf++ = (uint8)(regs->DR); // read and store the received byte. This clears the RXNE flag.
interrupts(); // let systick do its job interrupts(); // let systick do its job
} }
// read remaining last byte // read remaining last byte
while ( !(regs->SR & SPI_SR_RXNE) ) {} // wait till data is available in the Rx register while (!(regs->SR & SPI_SR_RXNE)) { /* nada */ } // wait till data is available in the Rx register
*buf++ = (uint8)(regs->DR); // read and store the received byte *buf++ = (uint8)(regs->DR); // read and store the received byte
} }
@ -302,42 +297,42 @@ void SPIClass::write(uint16_t data) {
* This almost doubles the speed of this function. * This almost doubles the speed of this function.
*/ */
spi_tx_reg(_currentSetting->spi_d, data); // write the data to be transmitted into the SPI_DR register (this clears the TXE flag) 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_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..." while (!spi_is_tx_empty(_currentSetting->spi_d)) { /* nada */ } // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI." while (spi_is_busy(_currentSetting->spi_d)) { /* nada */ } // "... and then wait until BSY=0 before disabling the SPI."
} }
void SPIClass::write16(uint16_t data) { void SPIClass::write16(uint16_t data) {
// Added by stevestrong: write two consecutive bytes in 8 bit mode (DFF=0) // Added by stevestrong: write two consecutive bytes in 8 bit mode (DFF=0)
spi_tx_reg(_currentSetting->spi_d, data>>8); // write high byte spi_tx_reg(_currentSetting->spi_d, data>>8); // write high byte
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // Wait until TXE=1 while (!spi_is_tx_empty(_currentSetting->spi_d)) { /* nada */ } // Wait until TXE=1
spi_tx_reg(_currentSetting->spi_d, data); // write low byte spi_tx_reg(_currentSetting->spi_d, data); // write low byte
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // Wait until TXE=1 while (!spi_is_tx_empty(_currentSetting->spi_d)) { /* nada */ } // Wait until TXE=1
while (spi_is_busy(_currentSetting->spi_d) != 0); // wait until BSY=0 while (spi_is_busy(_currentSetting->spi_d)) { /* nada */ } // wait until BSY=0
} }
void SPIClass::write(uint16_t data, uint32_t n) { void SPIClass::write(uint16_t data, uint32_t n) {
// Added by stevstrong: Repeatedly send same data by the specified number of times // Added by stevstrong: Repeatedly send same data by the specified number of times
spi_reg_map * regs = _currentSetting->spi_d->regs; spi_reg_map * regs = _currentSetting->spi_d->regs;
while ( (n--)>0 ) { while (n--) {
regs->DR = data; // write the data to be transmitted into the SPI_DR register (this clears the TXE flag) 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_TXE)) { /* nada */ } // wait till Tx empty
} }
while ( (regs->SR & SPI_SR_BSY) != 0); // wait until BSY=0 before returning while (regs->SR & SPI_SR_BSY) { /* nada */ } // wait until BSY=0 before returning
} }
void SPIClass::write(const void *data, uint32_t length) { void SPIClass::write(const void *data, uint32_t length) {
spi_dev * spi_d = _currentSetting->spi_d; spi_dev * spi_d = _currentSetting->spi_d;
spi_tx(spi_d, data, length); // data can be array of bytes or words spi_tx(spi_d, data, length); // data can be array of bytes or words
while (spi_is_tx_empty(spi_d) == 0); // "5. Wait until TXE=1 ..." while (!spi_is_tx_empty(spi_d)) { /* nada */ } // "5. Wait until TXE=1 ..."
while (spi_is_busy(spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI." while (spi_is_busy(spi_d)) { /* nada */ } // "... and then wait until BSY=0 before disabling the SPI."
} }
uint8_t SPIClass::transfer(uint8_t byte) const { uint8_t SPIClass::transfer(uint8_t byte) const {
spi_dev * spi_d = _currentSetting->spi_d; spi_dev * spi_d = _currentSetting->spi_d;
spi_rx_reg(spi_d); // read any previous data spi_rx_reg(spi_d); // read any previous data
spi_tx_reg(spi_d, byte); // Write the data item to be transmitted into the SPI_DR register spi_tx_reg(spi_d, byte); // Write the data item to be transmitted into the SPI_DR register
while (spi_is_tx_empty(spi_d) == 0); // "5. Wait until TXE=1 ..." while (!spi_is_tx_empty(spi_d)) { /* nada */ } // "5. Wait until TXE=1 ..."
while (spi_is_busy(spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI." while (spi_is_busy(spi_d)) { /* nada */ } // "... and then wait until BSY=0 before disabling the SPI."
return (uint8)spi_rx_reg(spi_d); // "... and read the last received data." return (uint8)spi_rx_reg(spi_d); // "... and read the last received data."
} }
@ -347,17 +342,18 @@ uint16_t SPIClass::transfer16(uint16_t data) const {
spi_dev * spi_d = _currentSetting->spi_d; spi_dev * spi_d = _currentSetting->spi_d;
spi_rx_reg(spi_d); // read any previous data spi_rx_reg(spi_d); // read any previous data
spi_tx_reg(spi_d, data>>8); // write high byte spi_tx_reg(spi_d, data>>8); // write high byte
while (spi_is_tx_empty(spi_d) == 0); // wait until TXE=1 while (!spi_is_tx_empty(spi_d)) { /* nada */ } // wait until TXE=1
while (spi_is_busy(spi_d) != 0); // wait until BSY=0 while (spi_is_busy(spi_d)) { /* nada */ } // wait until BSY=0
uint16_t ret = spi_rx_reg(spi_d)<<8; // read and shift high byte uint16_t ret = spi_rx_reg(spi_d)<<8; // read and shift high byte
spi_tx_reg(spi_d, data); // write low byte spi_tx_reg(spi_d, data); // write low byte
while (spi_is_tx_empty(spi_d) == 0); // wait until TXE=1 while (!spi_is_tx_empty(spi_d)) { /* nada */ } // wait until TXE=1
while (spi_is_busy(spi_d) != 0); // wait until BSY=0 while (spi_is_busy(spi_d)) { /* nada */ } // wait until BSY=0
ret += spi_rx_reg(spi_d); // read low byte ret += spi_rx_reg(spi_d); // read low byte
return ret; return ret;
} }
/* Roger Clark and Victor Perez, 2015 /**
* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI transfer with at least a receive buffer. * 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 lenght of the transfer. * If a TX buffer is not provided, FF is sent over and over for the lenght of the transfer.
* On exit TX buffer is not modified, and RX buffer cotains the received data. * On exit TX buffer is not modified, and RX buffer cotains the received data.
@ -399,13 +395,13 @@ uint8_t SPIClass::dmaTransferRepeat(uint16_t length) {
//uint32_t m = millis(); //uint32_t m = millis();
uint8_t b = 0; uint8_t b = 0;
uint32_t m = millis(); uint32_t m = millis();
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1) == 0) { while (!(dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)) {
// Avoid interrupts and just loop waiting for the flag to be set. // Avoid interrupts and just loop waiting for the flag to be set.
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; } if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
} }
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..." while (!spi_is_tx_empty(_currentSetting->spi_d)) { /* nada */ } // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI." while (spi_is_busy(_currentSetting->spi_d)) { /* nada */ } // "... and then wait until BSY=0 before disabling the SPI."
spi_tx_dma_disable(_currentSetting->spi_d); spi_tx_dma_disable(_currentSetting->spi_d);
spi_rx_dma_disable(_currentSetting->spi_d); spi_rx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
@ -416,7 +412,8 @@ uint8_t SPIClass::dmaTransferRepeat(uint16_t length) {
return b; return b;
} }
/* Roger Clark and Victor Perez, 2015 /**
* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI transfer with at least a receive buffer. * 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. * If a TX buffer is not provided, FF is sent over and over for the length of the transfer.
* On exit TX buffer is not modified, and RX buffer contains the received data. * On exit TX buffer is not modified, and RX buffer contains the received data.
@ -427,7 +424,8 @@ uint8_t SPIClass::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_
return dmaTransferRepeat(length); return dmaTransferRepeat(length);
} }
/* Roger Clark and Victor Perez, 2015 /**
* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI send using a TX buffer. * Performs a DMA SPI send using a TX buffer.
* On exit TX buffer is not modified. * On exit TX buffer is not modified.
* Still in progress. * Still in progress.
@ -450,17 +448,16 @@ uint8_t SPIClass::dmaSendRepeat(uint16_t length) {
_currentSetting->state = SPI_STATE_TRANSMIT; _currentSetting->state = SPI_STATE_TRANSMIT;
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); // enable transmit dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); // enable transmit
spi_tx_dma_enable(_currentSetting->spi_d); spi_tx_dma_enable(_currentSetting->spi_d);
if (_currentSetting->transmitCallback) if (_currentSetting->transmitCallback) return 0;
return 0;
uint32_t m = millis(); uint32_t m = millis();
uint8_t b = 0; uint8_t b = 0;
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)==0) { while (!(dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)) {
// Avoid interrupts and just loop waiting for the flag to be set. // Avoid interrupts and just loop waiting for the flag to be set.
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; } if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
} }
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..." while (!spi_is_tx_empty(_currentSetting->spi_d)) { /* nada */ } // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI." while (spi_is_busy(_currentSetting->spi_d)) { /* nada */ } // "... and then wait until BSY=0 before disabling the SPI."
spi_tx_dma_disable(_currentSetting->spi_d); spi_tx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
@ -478,14 +475,14 @@ uint8_t SPIClass::dmaSendAsync(const void * transmitBuf, uint16_t length, bool m
if (_currentSetting->state != SPI_STATE_READY) { if (_currentSetting->state != SPI_STATE_READY) {
uint32_t m = millis(); uint32_t m = millis();
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)==0) { while (!(dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)) {
//Avoid interrupts and just loop waiting for the flag to be set. //Avoid interrupts and just loop waiting for the flag to be set.
//delayMicroseconds(10); //delayMicroseconds(10);
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; } if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
} }
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..." while (!spi_is_tx_empty(_currentSetting->spi_d)) { /* nada */ } // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI." while (spi_is_busy(_currentSetting->spi_d)) { /* nada */ } // "... and then wait until BSY=0 before disabling the SPI."
spi_tx_dma_disable(_currentSetting->spi_d); spi_tx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY; _currentSetting->state = SPI_STATE_READY;
@ -575,11 +572,11 @@ void SPIClass::onTransmit(void(*callback)(void)) {
* during the initial setup and only set the callback to EventCallback if they are set. * during the initial setup and only set the callback to EventCallback if they are set.
*/ */
void SPIClass::EventCallback() { void SPIClass::EventCallback() {
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..." while (!spi_is_tx_empty(_currentSetting->spi_d)) { /* nada */ } // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0" while (spi_is_busy(_currentSetting->spi_d)) { /* nada */ } // "... and then wait until BSY=0"
switch (_currentSetting->state) { switch (_currentSetting->state) {
case SPI_STATE_TRANSFER: case SPI_STATE_TRANSFER:
while (spi_is_rx_nonempty(_currentSetting->spi_d)); while (spi_is_rx_nonempty(_currentSetting->spi_d)) { /* nada */ }
_currentSetting->state = SPI_STATE_READY; _currentSetting->state = SPI_STATE_READY;
spi_tx_dma_disable(_currentSetting->spi_d); spi_tx_dma_disable(_currentSetting->spi_d);
spi_rx_dma_disable(_currentSetting->spi_d); spi_rx_dma_disable(_currentSetting->spi_d);
@ -718,7 +715,7 @@ static const spi_baud_rate baud_rates[8] __FLASH__ = {
SPI_BAUD_PCLK_DIV_256, SPI_BAUD_PCLK_DIV_256,
}; };
/* /**
* Note: This assumes you're on a LeafLabs-style board * Note: This assumes you're on a LeafLabs-style board
* (CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz). * (CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz).
*/ */

Loading…
Cancel
Save