Delete dubious SPI timeout mechanism

The result from this mechanism is never checked, and SPI is not a bus
prone to timeouts anyway (the master generates the clock and the
transmission happens in a deterministic amount of time no matter if the
slave is cooperative, absent, or uncooperative.)

The timeout counter was set *per transfer*, and is fixed no matter what
the SPI clock speed. If the transfer size is large, and the SPI clock is
slow, stalls on the SPI bus are unavoidable (as we can generate data
faster than SPI can transmit it). These accumulate over the length of a
long transfer and trigger a "timeout". Detecting these as fatal timeouts
is not helpful.
This commit is contained in:
Nicholas Sherlock 2015-11-18 20:04:55 +13:00 committed by borisbstyle
parent 264c094eef
commit 3941c6c252
3 changed files with 26 additions and 207 deletions

View File

@ -126,8 +126,6 @@ void mpu6000SpiGyroInit(uint8_t lpf)
mpu6000AccAndGyroInit();
mpuIntExtiInit();
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
@ -139,8 +137,7 @@ void mpu6000SpiGyroInit(uint8_t lpf)
int16_t data[3];
mpuGyroRead(data);
if ((((int8_t)data[1]) == -1 && ((int8_t)data[0]) == -1) || spiGetErrorCounter(MPU6000_SPI_INSTANCE) != 0) {
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
if (((int8_t)data[1]) == -1 && ((int8_t)data[0]) == -1) {
failureMode(FAILURE_GYRO_INIT_FAILED);
}
}

View File

@ -26,21 +26,13 @@
#include "bus_spi.h"
static volatile uint16_t spi1ErrorCount = 0;
static volatile uint16_t spi2ErrorCount = 0;
#ifdef STM32F303xC
static volatile uint16_t spi3ErrorCount = 0;
#endif
#ifdef USE_SPI_DEVICE_1
#ifndef SPI1_GPIO
#define SPI1_NSS_GPIO GPIOA
#define SPI1_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA
#define SPI1_NSS_PIN GPIO_Pin_4
#define SPI1_NSS_PIN_SOURCE GPIO_PinSource4
#define SPI1_GPIO GPIOA
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOA
#define SPI1_NSS_PIN GPIO_Pin_4
#define SPI1_NSS_PIN_SOURCE GPIO_PinSource4
#define SPI1_SCK_PIN GPIO_Pin_5
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource5
#define SPI1_MISO_PIN GPIO_Pin_6
@ -73,10 +65,7 @@ void initSpi1(void)
GPIO_PinAFConfig(SPI1_GPIO, SPI1_SCK_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MISO_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MOSI_PIN_SOURCE, GPIO_AF_5);
#ifdef SPI1_NSS_PIN_SOURCE
RCC_AHBPeriphClockCmd(SPI1_NSS_PERIPHERAL, ENABLE);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_NSS_PIN_SOURCE, GPIO_AF_5);
#endif
// Init pins
@ -94,7 +83,7 @@ void initSpi1(void)
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI1_NSS_GPIO, &GPIO_InitStructure);
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
#endif
#endif
@ -105,20 +94,20 @@ void initSpi1(void)
gpio.mode = Mode_AF_PP;
gpio.pin = SPI1_MOSI_PIN | SPI1_SCK_PIN;
gpio.speed = Speed_50MHz;
gpioInit(SPI1_GPIO, &gpio);
gpioInit(GPIOA, &gpio);
// MISO as input
gpio.pin = SPI1_MISO_PIN;
gpio.mode = Mode_IN_FLOATING;
gpioInit(SPI1_GPIO, &gpio);
gpioInit(GPIOA, &gpio);
#ifdef SPI1_NSS_PIN
// NSS as gpio slave select
gpio.pin = SPI1_NSS_PIN;
gpio.mode = Mode_Out_PP;
gpioInit(SPI1_NSS_GPIO, &gpio);
gpioInit(GPIOA, &gpio);
#endif
#endif
// Init SPI1 hardware
// Init SPI hardware
SPI_I2S_DeInit(SPI1);
spi.SPI_Mode = SPI_Mode_Master;
@ -138,23 +127,16 @@ void initSpi1(void)
SPI_Init(SPI1, &spi);
SPI_Cmd(SPI1, ENABLE);
#ifdef SPI1_NSS_PIN
// Drive NSS high to disable connected SPI device.
GPIO_SetBits(SPI1_NSS_GPIO, SPI1_NSS_PIN);
#endif
}
#endif
#ifdef USE_SPI_DEVICE_2
#ifndef SPI2_GPIO
#define SPI2_NSS_GPIO GPIOB
#define SPI2_NSS_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI2_NSS_PIN GPIO_Pin_12
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
#define SPI2_GPIO GPIOB
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI2_NSS_PIN GPIO_Pin_12
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
#define SPI2_SCK_PIN GPIO_Pin_13
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
#define SPI2_MISO_PIN GPIO_Pin_14
@ -187,10 +169,7 @@ void initSpi2(void)
GPIO_PinAFConfig(SPI2_GPIO, SPI2_SCK_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI2_GPIO, SPI2_MISO_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI2_GPIO, SPI2_MOSI_PIN_SOURCE, GPIO_AF_5);
#ifdef SPI2_NSS_PIN_SOURCE
RCC_AHBPeriphClockCmd(SPI2_NSS_PERIPHERAL, ENABLE);
GPIO_PinAFConfig(SPI2_GPIO, SPI2_NSS_PIN_SOURCE, GPIO_AF_5);
#endif
@ -208,13 +187,14 @@ void initSpi2(void)
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI2_NSS_GPIO, &GPIO_InitStructure);
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
#endif
#endif
#ifdef STM32F10X
gpio_config_t gpio;
// MOSI + SCK as output
gpio.mode = Mode_AF_PP;
gpio.pin = SPI2_SCK_PIN | SPI2_MOSI_PIN;
@ -224,135 +204,45 @@ void initSpi2(void)
gpio.pin = SPI2_MISO_PIN;
gpio.mode = Mode_IN_FLOATING;
gpioInit(SPI2_GPIO, &gpio);
#ifdef SPI2_NSS_PIN
// NSS as gpio slave select
gpio.pin = SPI2_NSS_PIN;
gpio.mode = Mode_Out_PP;
gpioInit(SPI2_NSS_GPIO, &gpio);
gpioInit(SPI2_GPIO, &gpio);
#endif
#endif
// Init SPI2 hardware
SPI_I2S_DeInit(SPI2);
spi.SPI_Mode = SPI_Mode_Master;
spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spi.SPI_Mode = SPI_Mode_Master;
spi.SPI_DataSize = SPI_DataSize_8b;
spi.SPI_NSS = SPI_NSS_Soft;
spi.SPI_FirstBit = SPI_FirstBit_MSB;
spi.SPI_CRCPolynomial = 7;
spi.SPI_CPOL = SPI_CPOL_High;
spi.SPI_CPHA = SPI_CPHA_2Edge;
spi.SPI_NSS = SPI_NSS_Soft;
spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
spi.SPI_FirstBit = SPI_FirstBit_MSB;
spi.SPI_CRCPolynomial = 7;
#ifdef STM32F303xC
// Configure for 8-bit reads.
SPI_RxFIFOThresholdConfig(SPI2, SPI_RxFIFOThreshold_QF);
#endif
SPI_Init(SPI2, &spi);
SPI_Cmd(SPI2, ENABLE);
#ifdef SPI2_NSS_PIN
// Drive NSS high to disable connected SPI device.
GPIO_SetBits(SPI2_NSS_GPIO, SPI2_NSS_PIN);
#endif
}
#endif
GPIO_SetBits(SPI2_GPIO, SPI2_NSS_PIN);
#if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC)
#ifndef SPI3_GPIO
#define SPI3_NSS_GPIO GPIOA
#define SPI3_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA
#define SPI3_NSS_PIN GPIO_Pin_15
#define SPI3_NSS_PIN_SOURCE GPIO_PinSource15
#define SPI3_GPIO GPIOB
#define SPI3_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI3_SCK_PIN GPIO_Pin_3
#define SPI3_SCK_PIN_SOURCE GPIO_PinSource3
#define SPI3_MISO_PIN GPIO_Pin_4
#define SPI3_MISO_PIN_SOURCE GPIO_PinSource4
#define SPI3_MOSI_PIN GPIO_Pin_5
#define SPI3_MOSI_PIN_SOURCE GPIO_PinSource5
#endif
void initSpi3(void)
{
// Specific to the STM32F303 (AF6)
// SPI3 Driver
// PA15 38 SPI3_NSS
// PB3 39 SPI3_SCK
// PB4 40 SPI3_MISO
// PB5 41 SPI3_MOSI
SPI_InitTypeDef spi;
// Enable SPI3 clock
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE);
GPIO_InitTypeDef GPIO_InitStructure;
RCC_AHBPeriphClockCmd(SPI3_GPIO_PERIPHERAL, ENABLE);
GPIO_PinAFConfig(SPI3_GPIO, SPI3_SCK_PIN_SOURCE, GPIO_AF_6);
GPIO_PinAFConfig(SPI3_GPIO, SPI3_MISO_PIN_SOURCE, GPIO_AF_6);
GPIO_PinAFConfig(SPI3_GPIO, SPI3_MOSI_PIN_SOURCE, GPIO_AF_6);
#ifdef SPI2_NSS_PIN_SOURCE
RCC_AHBPeriphClockCmd(SPI3_NSS_PERIPHERAL, ENABLE);
GPIO_PinAFConfig(SPI3_NSS_GPIO, SPI3_NSS_PIN_SOURCE, GPIO_AF_6);
#endif
// Init pins
GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN | SPI3_MISO_PIN | SPI3_MOSI_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
#ifdef SPI3_NSS_PIN
GPIO_InitStructure.GPIO_Pin = SPI3_NSS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI3_NSS_GPIO, &GPIO_InitStructure);
#endif
// Init SPI hardware
SPI_I2S_DeInit(SPI3);
spi.SPI_Mode = SPI_Mode_Master;
spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spi.SPI_DataSize = SPI_DataSize_8b;
spi.SPI_NSS = SPI_NSS_Soft;
spi.SPI_FirstBit = SPI_FirstBit_MSB;
spi.SPI_CRCPolynomial = 7;
spi.SPI_CPOL = SPI_CPOL_High;
spi.SPI_CPHA = SPI_CPHA_2Edge;
spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
// Configure for 8-bit reads.
SPI_RxFIFOThresholdConfig(SPI3, SPI_RxFIFOThreshold_QF);
SPI_Init(SPI3, &spi);
SPI_Cmd(SPI3, ENABLE);
#ifdef SPI3_NSS_PIN
// Drive NSS high to disable connected SPI device.
GPIO_SetBits(SPI3_NSS_GPIO, SPI3_NSS_PIN);
#endif
}
#endif
bool spiInit(SPI_TypeDef *instance)
{
#if (!(defined(USE_SPI_DEVICE_1) && defined(USE_SPI_DEVICE_2) && defined(USE_SPI_DEVICE_3)))
#if (!(defined(USE_SPI_DEVICE_1) && defined(USE_SPI_DEVICE_2)))
UNUSED(instance);
#endif
@ -367,41 +257,14 @@ bool spiInit(SPI_TypeDef *instance)
initSpi2();
return true;
}
#endif
#if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC)
if (instance == SPI3) {
initSpi3();
return true;
}
#endif
return false;
}
uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance)
{
if (instance == SPI1) {
spi1ErrorCount++;
return spi1ErrorCount;
} else if (instance == SPI2) {
spi2ErrorCount++;
return spi2ErrorCount;
#ifdef STM32F303xC
} else if (instance == SPI3) {
spi3ErrorCount++;
return spi3ErrorCount;
#endif
}
return -1;
}
// return uint8_t value or -1 when failure
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
{
uint16_t spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET)
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
}
#ifdef STM32F303xC
SPI_SendData8(instance, data);
@ -409,10 +272,8 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
#ifdef STM32F10X
SPI_I2S_SendData(instance, data);
#endif
spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET)
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET){
}
#ifdef STM32F303xC
return ((uint8_t)SPI_ReceiveData8(instance));
@ -436,17 +297,13 @@ bool spiIsBusBusy(SPI_TypeDef *instance)
}
bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
{
uint16_t spiTimeout = 1000;
uint8_t b;
instance->DR;
while (len--) {
b = in ? *(in++) : 0xFF;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
}
#ifdef STM32F303xC
SPI_SendData8(instance, b);
@ -456,8 +313,6 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
SPI_I2S_SendData(instance, b);
#endif
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
}
#ifdef STM32F303xC
b = SPI_ReceiveData8(instance);
@ -469,8 +324,6 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
if (out)
*(out++) = b;
}
return true;
}
@ -530,31 +383,3 @@ void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
SPI_Cmd(instance, ENABLE);
}
uint16_t spiGetErrorCounter(SPI_TypeDef *instance)
{
if (instance == SPI1) {
return spi1ErrorCount;
} else if (instance == SPI2) {
return spi2ErrorCount;
#ifdef STM32F303xC
} else if (instance == SPI3) {
return spi3ErrorCount;
#endif
}
return 0;
}
void spiResetErrorCounter(SPI_TypeDef *instance)
{
if (instance == SPI1) {
spi1ErrorCount = 0;
} else if (instance == SPI2) {
spi2ErrorCount = 0;
#ifdef STM32F303xC
} else if (instance == SPI3) {
spi3ErrorCount = 0;
#endif
}
}

View File

@ -26,7 +26,4 @@ void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor);
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in);
bool spiIsBusBusy(SPI_TypeDef *instance);
bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len);
uint16_t spiGetErrorCounter(SPI_TypeDef *instance);
void spiResetErrorCounter(SPI_TypeDef *instance);
void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len);