mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 14:25:20 +03:00
SPI3 fix
reintroduce SPI timeout to avoid driver blockage AlienFlight related fixes
This commit is contained in:
parent
fda0794441
commit
47f1d7e955
6 changed files with 167 additions and 20 deletions
|
@ -2,7 +2,7 @@
|
|||
|
||||
Spektrum bind with hardware bind plug support.
|
||||
|
||||
The Spektrum bind code is actually enabled for the NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY, CC3D, ALIENWIIF1, ALIENWIIF3 targets.
|
||||
The Spektrum bind code is actually enabled for the NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY, CC3D, ALIENFLIGHTF1, ALIENFLIGHTF3 targets.
|
||||
|
||||
## Configure the bind code
|
||||
|
||||
|
|
|
@ -637,6 +637,7 @@ static void resetConf(void)
|
|||
#ifdef ALIENFLIGHTF3
|
||||
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||
masterConfig.batteryConfig.vbatscale = 20;
|
||||
masterConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||
#else
|
||||
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
|
||||
#endif
|
||||
|
|
|
@ -56,7 +56,6 @@ void initSpi1(void)
|
|||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
|
||||
RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE);
|
||||
|
||||
|
||||
#ifdef STM32F303xC
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
|
@ -65,9 +64,11 @@ 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
|
||||
GPIO_PinAFConfig(SPI1_GPIO, SPI1_NSS_PIN_SOURCE, GPIO_AF_5);
|
||||
#endif
|
||||
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
|
@ -106,29 +107,31 @@ void initSpi1(void)
|
|||
|
||||
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef STM32F10X
|
||||
gpio_config_t gpio;
|
||||
|
||||
// MOSI + SCK as output
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpio.pin = SPI1_MOSI_PIN | SPI1_SCK_PIN;
|
||||
gpio.speed = Speed_50MHz;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
gpioInit(SPI1_GPIO, &gpio);
|
||||
|
||||
// MISO as input
|
||||
gpio.pin = SPI1_MISO_PIN;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
gpioInit(SPI1_GPIO, &gpio);
|
||||
|
||||
#ifdef SPI1_NSS_PIN
|
||||
// NSS as gpio slave select
|
||||
gpio.pin = SPI1_NSS_PIN;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
gpioInit(SPI1_GPIO, &gpio);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Init SPI hardware
|
||||
// Init SPI1 hardware
|
||||
SPI_I2S_DeInit(SPI1);
|
||||
|
||||
spi.SPI_Mode = SPI_Mode_Master;
|
||||
|
@ -154,6 +157,11 @@ 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_GPIO, SPI1_NSS_PIN);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -187,7 +195,6 @@ void initSpi2(void)
|
|||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE);
|
||||
|
||||
|
||||
#ifdef STM32F303xC
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
|
@ -196,10 +203,12 @@ 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
|
||||
GPIO_PinAFConfig(SPI2_GPIO, SPI2_NSS_PIN_SOURCE, GPIO_AF_5);
|
||||
#endif
|
||||
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
|
@ -237,7 +246,6 @@ void initSpi2(void)
|
|||
|
||||
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef STM32F10X
|
||||
|
@ -248,6 +256,7 @@ void initSpi2(void)
|
|||
gpio.pin = SPI2_SCK_PIN | SPI2_MOSI_PIN;
|
||||
gpio.speed = Speed_50MHz;
|
||||
gpioInit(SPI2_GPIO, &gpio);
|
||||
|
||||
// MISO as input
|
||||
gpio.pin = SPI2_MISO_PIN;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
|
@ -264,13 +273,13 @@ void initSpi2(void)
|
|||
// Init SPI2 hardware
|
||||
SPI_I2S_DeInit(SPI2);
|
||||
|
||||
spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
|
||||
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_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
|
||||
spi.SPI_FirstBit = SPI_FirstBit_MSB;
|
||||
spi.SPI_CRCPolynomial = 7;
|
||||
spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
|
||||
|
||||
#ifdef USE_SDCARD_SPI2
|
||||
spi.SPI_CPOL = SPI_CPOL_Low;
|
||||
|
@ -284,19 +293,136 @@ void initSpi2(void)
|
|||
// 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_GPIO, SPI2_NSS_PIN);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC)
|
||||
|
||||
#ifndef SPI3_GPIO
|
||||
#define SPI3_GPIO GPIOB
|
||||
#define SPI3_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#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_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_NNS_PERIPHERAL, ENABLE);
|
||||
GPIO_PinAFConfig(SPI3_NNS_GPIO, SPI3_NSS_PIN_SOURCE, GPIO_AF_6);
|
||||
#endif
|
||||
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
|
||||
#ifdef USE_SDCARD_SPI3
|
||||
// Configure pins and pullups for SD-card use
|
||||
|
||||
// No pull-up needed since we drive this pin as an output
|
||||
GPIO_InitStructure.GPIO_Pin = SPI3_MOSI_PIN;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
|
||||
|
||||
// Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected
|
||||
GPIO_InitStructure.GPIO_Pin = SPI3_MISO_PIN;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
|
||||
GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
|
||||
|
||||
// In clock-low mode, STM32 manual says we should enable a pulldown to match
|
||||
GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
|
||||
GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
|
||||
#else
|
||||
// General-purpose pin config
|
||||
GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN | SPI3_MISO_PIN | SPI3_MOSI_PIN;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
|
||||
#endif
|
||||
|
||||
#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_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
|
||||
|
||||
#ifdef USE_SDCARD_SPI3
|
||||
spi.SPI_CPOL = SPI_CPOL_Low;
|
||||
spi.SPI_CPHA = SPI_CPHA_1Edge;
|
||||
#else
|
||||
spi.SPI_CPOL = SPI_CPOL_High;
|
||||
spi.SPI_CPHA = SPI_CPHA_2Edge;
|
||||
#endif
|
||||
|
||||
// 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)))
|
||||
#if (!(defined(USE_SPI_DEVICE_1) && defined(USE_SPI_DEVICE_2) && defined(USE_SPI_DEVICE_3)))
|
||||
UNUSED(instance);
|
||||
#endif
|
||||
|
||||
|
@ -311,13 +437,23 @@ 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;
|
||||
}
|
||||
|
||||
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)
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef STM32F303xC
|
||||
|
@ -326,7 +462,10 @@ 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)
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef STM32F303xC
|
||||
|
@ -353,11 +492,15 @@ bool spiIsBusBusy(SPI_TypeDef *instance)
|
|||
|
||||
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)
|
||||
break;
|
||||
}
|
||||
#ifdef STM32F303xC
|
||||
SPI_SendData8(instance, b);
|
||||
|
@ -366,7 +509,10 @@ void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
|||
#ifdef STM32F10X
|
||||
SPI_I2S_SendData(instance, b);
|
||||
#endif
|
||||
spiTimeout = 1000;
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
|
||||
if ((spiTimeout--) == 0)
|
||||
break;
|
||||
}
|
||||
#ifdef STM32F303xC
|
||||
b = SPI_ReceiveData8(instance);
|
||||
|
|
|
@ -632,7 +632,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
for (i = 0; i < BOARD_IDENTIFIER_LENGTH; i++) {
|
||||
serialize8(boardIdentifier[i]);
|
||||
}
|
||||
#ifdef NAZE
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
serialize16(hardwareRevision);
|
||||
#else
|
||||
serialize16(0); // No other build targets currently have hardware revision detection.
|
||||
|
|
|
@ -171,7 +171,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
|
|||
|
||||
#ifdef ALIENFLIGHTF3
|
||||
// MPU_INT output on V1 PA15
|
||||
static const extiConfig_t alienWiiF3V1MPUIntExtiConfig = {
|
||||
static const extiConfig_t alienFlightF3V1MPUIntExtiConfig = {
|
||||
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
|
||||
.gpioPort = GPIOA,
|
||||
.gpioPin = Pin_15,
|
||||
|
@ -181,7 +181,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
|
|||
.exti_irqn = EXTI15_10_IRQn
|
||||
};
|
||||
// MPU_INT output on V2 PB13
|
||||
static const extiConfig_t alienWiiF3V2MPUIntExtiConfig = {
|
||||
static const extiConfig_t alienFlightF3V2MPUIntExtiConfig = {
|
||||
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOB,
|
||||
.gpioPort = GPIOB,
|
||||
.gpioPin = Pin_13,
|
||||
|
@ -191,9 +191,9 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
|
|||
.exti_irqn = EXTI15_10_IRQn
|
||||
};
|
||||
if (hardwareRevision == AFF3_REV_1) {
|
||||
return &alienWiiF3V1MPUIntExtiConfig;
|
||||
return &alienFlightF3V1MPUIntExtiConfig;
|
||||
} else {
|
||||
return &alienWiiF3V2MPUIntExtiConfig;
|
||||
return &alienFlightF3V2MPUIntExtiConfig;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -48,7 +48,7 @@
|
|||
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
|
||||
|
||||
#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
// Using MPU6050 for the moment.
|
||||
|
@ -72,7 +72,7 @@
|
|||
//#define BARO
|
||||
//#define USE_BARO_MS5611
|
||||
|
||||
// No mag support for now (option to use MPU9150 in the future).
|
||||
// option to use MPU9150 or MPU9250 integrated AK89xx Mag
|
||||
#define MAG
|
||||
#define USE_MAG_AK8963
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue