Merge pull request #3336 from jflyper/bfdev-configurable-spi-phase-1
Configurable SPI
This commit is contained in:
commit
1d5145b869
3
Makefile
3
Makefile
|
@ -682,6 +682,7 @@ COMMON_SRC = \
|
||||||
drivers/bus_i2c_soft.c \
|
drivers/bus_i2c_soft.c \
|
||||||
drivers/bus_spi.c \
|
drivers/bus_spi.c \
|
||||||
drivers/bus_spi_config.c \
|
drivers/bus_spi_config.c \
|
||||||
|
drivers/bus_spi_pinconfig.c \
|
||||||
drivers/bus_spi_soft.c \
|
drivers/bus_spi_soft.c \
|
||||||
drivers/buttons.c \
|
drivers/buttons.c \
|
||||||
drivers/display.c \
|
drivers/display.c \
|
||||||
|
@ -903,6 +904,7 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
|
||||||
SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
|
SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
|
||||||
drivers/bus_i2c_config.c \
|
drivers/bus_i2c_config.c \
|
||||||
drivers/bus_spi_config.c \
|
drivers/bus_spi_config.c \
|
||||||
|
drivers/bus_spi_pinconfig.c \
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_init.c \
|
drivers/serial_uart_init.c \
|
||||||
|
@ -1033,6 +1035,7 @@ SITLEXCLUDES = \
|
||||||
drivers/bus_i2c_config.c \
|
drivers/bus_i2c_config.c \
|
||||||
drivers/bus_spi.c \
|
drivers/bus_spi.c \
|
||||||
drivers/bus_spi_config.c \
|
drivers/bus_spi_config.c \
|
||||||
|
drivers/bus_spi_pinconfig.c \
|
||||||
drivers/dma.c \
|
drivers/dma.c \
|
||||||
drivers/pwm_output.c \
|
drivers/pwm_output.c \
|
||||||
drivers/timer.c \
|
drivers/timer.c \
|
||||||
|
|
|
@ -108,7 +108,8 @@
|
||||||
#define PG_ESC_SENSOR_CONFIG 517
|
#define PG_ESC_SENSOR_CONFIG 517
|
||||||
#define PG_I2C_CONFIG 518
|
#define PG_I2C_CONFIG 518
|
||||||
#define PG_DASHBOARD_CONFIG 519
|
#define PG_DASHBOARD_CONFIG 519
|
||||||
#define PG_BETAFLIGHT_END 519
|
#define PG_SPI_PIN_CONFIG 520
|
||||||
|
#define PG_BETAFLIGHT_END 520
|
||||||
|
|
||||||
|
|
||||||
// OSD configuration (subject to change)
|
// OSD configuration (subject to change)
|
||||||
|
|
|
@ -17,90 +17,49 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
|
#ifdef USE_SPI
|
||||||
|
|
||||||
#include "drivers/bus.h"
|
#include "drivers/bus.h"
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/bus_spi_impl.h"
|
||||||
#include "drivers/exti.h"
|
#include "drivers/exti.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/io_impl.h"
|
|
||||||
#include "drivers/rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
/* for F30x processors */
|
spiDevice_t spiDevice[SPIDEV_COUNT];
|
||||||
#if defined(STM32F303xC)
|
|
||||||
#ifndef GPIO_AF_SPI1
|
|
||||||
#define GPIO_AF_SPI1 GPIO_AF_5
|
|
||||||
#endif
|
|
||||||
#ifndef GPIO_AF_SPI2
|
|
||||||
#define GPIO_AF_SPI2 GPIO_AF_5
|
|
||||||
#endif
|
|
||||||
#ifndef GPIO_AF_SPI3
|
|
||||||
#define GPIO_AF_SPI3 GPIO_AF_6
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef SPI1_SCK_PIN
|
|
||||||
#define SPI1_NSS_PIN PA4
|
|
||||||
#define SPI1_SCK_PIN PA5
|
|
||||||
#define SPI1_MISO_PIN PA6
|
|
||||||
#define SPI1_MOSI_PIN PA7
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef SPI2_SCK_PIN
|
|
||||||
#define SPI2_NSS_PIN PB12
|
|
||||||
#define SPI2_SCK_PIN PB13
|
|
||||||
#define SPI2_MISO_PIN PB14
|
|
||||||
#define SPI2_MOSI_PIN PB15
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef SPI3_SCK_PIN
|
|
||||||
#define SPI3_NSS_PIN PA15
|
|
||||||
#define SPI3_SCK_PIN PB3
|
|
||||||
#define SPI3_MISO_PIN PB4
|
|
||||||
#define SPI3_MOSI_PIN PB5
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef SPI1_NSS_PIN
|
|
||||||
#define SPI1_NSS_PIN NONE
|
|
||||||
#endif
|
|
||||||
#ifndef SPI2_NSS_PIN
|
|
||||||
#define SPI2_NSS_PIN NONE
|
|
||||||
#endif
|
|
||||||
#ifndef SPI3_NSS_PIN
|
|
||||||
#define SPI3_NSS_PIN NONE
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static spiDevice_t spiHardwareMap[] = {
|
|
||||||
#if defined(STM32F1)
|
|
||||||
{ .dev = SPI1, .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = 0, false },
|
|
||||||
{ .dev = SPI2, .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = 0, false },
|
|
||||||
#else
|
|
||||||
{ .dev = SPI1, .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF_SPI1, false },
|
|
||||||
{ .dev = SPI2, .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF_SPI2, false },
|
|
||||||
#endif
|
|
||||||
#if defined(STM32F3) || defined(STM32F4)
|
|
||||||
{ .dev = SPI3, .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF_SPI3, false }
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
|
|
||||||
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
|
#ifdef USE_SPI_DEVICE_1
|
||||||
if (instance == SPI1)
|
if (instance == SPI1)
|
||||||
return SPIDEV_1;
|
return SPIDEV_1;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SPI_DEVICE_2
|
||||||
if (instance == SPI2)
|
if (instance == SPI2)
|
||||||
return SPIDEV_2;
|
return SPIDEV_2;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SPI_DEVICE_3
|
||||||
if (instance == SPI3)
|
if (instance == SPI3)
|
||||||
return SPIDEV_3;
|
return SPIDEV_3;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SPI_DEVICE_4
|
||||||
|
if (instance == SPI4)
|
||||||
|
return SPIDEV_3;
|
||||||
|
#endif
|
||||||
|
|
||||||
return SPIINVALID;
|
return SPIINVALID;
|
||||||
}
|
}
|
||||||
|
|
||||||
void spiInitDevice(SPIDevice device)
|
void spiInitDevice(SPIDevice device)
|
||||||
{
|
{
|
||||||
spiDevice_t *spi = &(spiHardwareMap[device]);
|
spiDevice_t *spi = &(spiDevice[device]);
|
||||||
|
|
||||||
#ifdef SDCARD_SPI_INSTANCE
|
#ifdef SDCARD_SPI_INSTANCE
|
||||||
if (spi->dev == SDCARD_SPI_INSTANCE) {
|
if (spi->dev == SDCARD_SPI_INSTANCE) {
|
||||||
|
@ -204,8 +163,8 @@ uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance)
|
||||||
SPIDevice device = spiDeviceByInstance(instance);
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
if (device == SPIINVALID)
|
if (device == SPIINVALID)
|
||||||
return -1;
|
return -1;
|
||||||
spiHardwareMap[device].errorCount++;
|
spiDevice[device].errorCount++;
|
||||||
return spiHardwareMap[device].errorCount;
|
return spiDevice[device].errorCount;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return uint8_t value or -1 when failure
|
// return uint8_t value or -1 when failure
|
||||||
|
@ -284,56 +243,12 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
||||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
||||||
{
|
{
|
||||||
#define BR_CLEAR_MASK 0xFFC7
|
#define BR_CLEAR_MASK 0xFFC7
|
||||||
|
|
||||||
uint16_t tempRegister;
|
uint16_t tempRegister;
|
||||||
|
|
||||||
SPI_Cmd(instance, DISABLE);
|
SPI_Cmd(instance, DISABLE);
|
||||||
|
|
||||||
tempRegister = instance->CR1;
|
tempRegister = (instance->CR1 & BR_CLEAR_MASK);
|
||||||
|
instance->CR1 = (tempRegister | ((ffs(divisor | 0x100) - 2) << 3));
|
||||||
switch (divisor) {
|
|
||||||
case 2:
|
|
||||||
tempRegister &= BR_CLEAR_MASK;
|
|
||||||
tempRegister |= SPI_BaudRatePrescaler_2;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 4:
|
|
||||||
tempRegister &= BR_CLEAR_MASK;
|
|
||||||
tempRegister |= SPI_BaudRatePrescaler_4;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 8:
|
|
||||||
tempRegister &= BR_CLEAR_MASK;
|
|
||||||
tempRegister |= SPI_BaudRatePrescaler_8;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 16:
|
|
||||||
tempRegister &= BR_CLEAR_MASK;
|
|
||||||
tempRegister |= SPI_BaudRatePrescaler_16;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 32:
|
|
||||||
tempRegister &= BR_CLEAR_MASK;
|
|
||||||
tempRegister |= SPI_BaudRatePrescaler_32;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 64:
|
|
||||||
tempRegister &= BR_CLEAR_MASK;
|
|
||||||
tempRegister |= SPI_BaudRatePrescaler_64;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 128:
|
|
||||||
tempRegister &= BR_CLEAR_MASK;
|
|
||||||
tempRegister |= SPI_BaudRatePrescaler_128;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 256:
|
|
||||||
tempRegister &= BR_CLEAR_MASK;
|
|
||||||
tempRegister |= SPI_BaudRatePrescaler_256;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
instance->CR1 = tempRegister;
|
|
||||||
|
|
||||||
SPI_Cmd(instance, ENABLE);
|
SPI_Cmd(instance, ENABLE);
|
||||||
}
|
}
|
||||||
|
@ -343,14 +258,14 @@ uint16_t spiGetErrorCounter(SPI_TypeDef *instance)
|
||||||
SPIDevice device = spiDeviceByInstance(instance);
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
if (device == SPIINVALID)
|
if (device == SPIINVALID)
|
||||||
return 0;
|
return 0;
|
||||||
return spiHardwareMap[device].errorCount;
|
return spiDevice[device].errorCount;
|
||||||
}
|
}
|
||||||
|
|
||||||
void spiResetErrorCounter(SPI_TypeDef *instance)
|
void spiResetErrorCounter(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
SPIDevice device = spiDeviceByInstance(instance);
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
if (device != SPIINVALID)
|
if (device != SPIINVALID)
|
||||||
spiHardwareMap[device].errorCount = 0;
|
spiDevice[device].errorCount = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
|
bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
|
||||||
|
@ -388,3 +303,4 @@ void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
bus->spi.instance = instance;
|
bus->spi.instance = instance;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -70,21 +70,16 @@ typedef enum SPIDevice {
|
||||||
SPIDEV_4
|
SPIDEV_4
|
||||||
} SPIDevice;
|
} SPIDevice;
|
||||||
|
|
||||||
typedef struct SPIDevice_s {
|
#if defined(STM32F1)
|
||||||
SPI_TypeDef *dev;
|
#define SPIDEV_COUNT 2
|
||||||
ioTag_t sck;
|
#elif defined(STM32F3) || defined(STM32F4)
|
||||||
ioTag_t mosi;
|
#define SPIDEV_COUNT 3
|
||||||
ioTag_t miso;
|
#elif defined(STM32F7)
|
||||||
rccPeriphTag_t rcc;
|
#define SPIDEV_COUNT 4
|
||||||
uint8_t af;
|
#else
|
||||||
volatile uint16_t errorCount;
|
#define SPIDEV_COUNT 4
|
||||||
bool leadingEdge;
|
|
||||||
#if defined(STM32F7)
|
|
||||||
SPI_HandleTypeDef hspi;
|
|
||||||
DMA_HandleTypeDef hdma;
|
|
||||||
uint8_t dmaIrqHandler;
|
|
||||||
#endif
|
#endif
|
||||||
} spiDevice_t;
|
|
||||||
|
|
||||||
void spiPreInitCs(ioTag_t iotag);
|
void spiPreInitCs(ioTag_t iotag);
|
||||||
bool spiInit(SPIDevice device);
|
bool spiInit(SPIDevice device);
|
||||||
|
@ -107,3 +102,11 @@ bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data);
|
||||||
bool spiReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data);
|
bool spiReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data);
|
||||||
uint8_t spiReadRegister(const busDevice_t *bus, uint8_t reg);
|
uint8_t spiReadRegister(const busDevice_t *bus, uint8_t reg);
|
||||||
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance);
|
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance);
|
||||||
|
|
||||||
|
typedef struct spiPinConfig_s {
|
||||||
|
ioTag_t ioTagSck[SPIDEV_COUNT];
|
||||||
|
ioTag_t ioTagMiso[SPIDEV_COUNT];
|
||||||
|
ioTag_t ioTagMosi[SPIDEV_COUNT];
|
||||||
|
} spiPinConfig_t;
|
||||||
|
|
||||||
|
void spiPinConfigure(void);
|
||||||
|
|
|
@ -17,22 +17,20 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
|
#ifdef USE_SPI
|
||||||
|
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/bus_spi_impl.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/io_impl.h"
|
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "drivers/rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
#ifndef SPI1_SCK_PIN
|
spiDevice_t spiDevice[SPIDEV_COUNT];
|
||||||
#define SPI1_NSS_PIN PA4
|
|
||||||
#define SPI1_SCK_PIN PA5
|
|
||||||
#define SPI1_MISO_PIN PA6
|
|
||||||
#define SPI1_MOSI_PIN PA7
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef SPI2_SCK_PIN
|
#ifndef SPI2_SCK_PIN
|
||||||
#define SPI2_NSS_PIN PB12
|
#define SPI2_NSS_PIN PB12
|
||||||
|
@ -70,65 +68,65 @@
|
||||||
|
|
||||||
#define SPI_DEFAULT_TIMEOUT 10
|
#define SPI_DEFAULT_TIMEOUT 10
|
||||||
|
|
||||||
|
|
||||||
static spiDevice_t spiHardwareMap[] = {
|
|
||||||
{ .dev = SPI1, .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF5_SPI1, .leadingEdge = false, .dmaIrqHandler = DMA2_ST3_HANDLER },
|
|
||||||
{ .dev = SPI2, .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF5_SPI2, .leadingEdge = false, .dmaIrqHandler = DMA1_ST4_HANDLER },
|
|
||||||
{ .dev = SPI3, .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF6_SPI3, .leadingEdge = false, .dmaIrqHandler = DMA1_ST7_HANDLER },
|
|
||||||
{ .dev = SPI4, .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .af = GPIO_AF5_SPI4, .leadingEdge = false, .dmaIrqHandler = DMA2_ST1_HANDLER }
|
|
||||||
};
|
|
||||||
|
|
||||||
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
|
#ifdef USE_SPI_DEVICE_1
|
||||||
if (instance == SPI1)
|
if (instance == SPI1)
|
||||||
return SPIDEV_1;
|
return SPIDEV_1;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SPI_DEVICE_2
|
||||||
if (instance == SPI2)
|
if (instance == SPI2)
|
||||||
return SPIDEV_2;
|
return SPIDEV_2;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SPI_DEVICE_3
|
||||||
if (instance == SPI3)
|
if (instance == SPI3)
|
||||||
return SPIDEV_3;
|
return SPIDEV_3;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SPI_DEVICE_4
|
||||||
if (instance == SPI4)
|
if (instance == SPI4)
|
||||||
return SPIDEV_4;
|
return SPIDEV_4;
|
||||||
|
#endif
|
||||||
|
|
||||||
return SPIINVALID;
|
return SPIINVALID;
|
||||||
}
|
}
|
||||||
|
|
||||||
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance)
|
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
return &spiHardwareMap[spiDeviceByInstance(instance)].hspi;
|
return &spiDevice[spiDeviceByInstance(instance)].hspi;
|
||||||
}
|
}
|
||||||
|
|
||||||
DMA_HandleTypeDef* dmaHandleByInstance(SPI_TypeDef *instance)
|
DMA_HandleTypeDef* dmaHandleByInstance(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
return &spiHardwareMap[spiDeviceByInstance(instance)].hdma;
|
return &spiDevice[spiDeviceByInstance(instance)].hdma;
|
||||||
}
|
}
|
||||||
|
|
||||||
void SPI1_IRQHandler(void)
|
void SPI1_IRQHandler(void)
|
||||||
{
|
{
|
||||||
HAL_SPI_IRQHandler(&spiHardwareMap[SPIDEV_1].hspi);
|
HAL_SPI_IRQHandler(&spiDevice[SPIDEV_1].hspi);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SPI2_IRQHandler(void)
|
void SPI2_IRQHandler(void)
|
||||||
{
|
{
|
||||||
HAL_SPI_IRQHandler(&spiHardwareMap[SPIDEV_2].hspi);
|
HAL_SPI_IRQHandler(&spiDevice[SPIDEV_2].hspi);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SPI3_IRQHandler(void)
|
void SPI3_IRQHandler(void)
|
||||||
{
|
{
|
||||||
HAL_SPI_IRQHandler(&spiHardwareMap[SPIDEV_3].hspi);
|
HAL_SPI_IRQHandler(&spiDevice[SPIDEV_3].hspi);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SPI4_IRQHandler(void)
|
void SPI4_IRQHandler(void)
|
||||||
{
|
{
|
||||||
HAL_SPI_IRQHandler(&spiHardwareMap[SPIDEV_4].hspi);
|
HAL_SPI_IRQHandler(&spiDevice[SPIDEV_4].hspi);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void spiInitDevice(SPIDevice device)
|
void spiInitDevice(SPIDevice device)
|
||||||
{
|
{
|
||||||
spiDevice_t *spi = &(spiHardwareMap[device]);
|
spiDevice_t *spi = &(spiDevice[device]);
|
||||||
|
|
||||||
#ifdef SDCARD_SPI_INSTANCE
|
#ifdef SDCARD_SPI_INSTANCE
|
||||||
if (spi->dev == SDCARD_SPI_INSTANCE) {
|
if (spi->dev == SDCARD_SPI_INSTANCE) {
|
||||||
|
@ -154,7 +152,15 @@ void spiInitDevice(SPIDevice device)
|
||||||
IOInit(IOGetByTag(spi->miso), OWNER_SPI_MISO, RESOURCE_INDEX(device));
|
IOInit(IOGetByTag(spi->miso), OWNER_SPI_MISO, RESOURCE_INDEX(device));
|
||||||
IOInit(IOGetByTag(spi->mosi), OWNER_SPI_MOSI, RESOURCE_INDEX(device));
|
IOInit(IOGetByTag(spi->mosi), OWNER_SPI_MOSI, RESOURCE_INDEX(device));
|
||||||
|
|
||||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
|
#if defined(STM32F7)
|
||||||
|
if(spi->leadingEdge == true)
|
||||||
|
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->sckAF);
|
||||||
|
else
|
||||||
|
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_HIGH, spi->sckAF);
|
||||||
|
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->misoAF);
|
||||||
|
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->mosiAF);
|
||||||
|
#endif
|
||||||
|
#if defined(STM32F3) || defined(STM32F4)
|
||||||
if(spi->leadingEdge == true)
|
if(spi->leadingEdge == true)
|
||||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->af);
|
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->af);
|
||||||
else
|
else
|
||||||
|
@ -167,30 +173,31 @@ void spiInitDevice(SPIDevice device)
|
||||||
IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG);
|
IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG);
|
||||||
IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG);
|
IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG);
|
||||||
#endif
|
#endif
|
||||||
spiHardwareMap[device].hspi.Instance = spi->dev;
|
spiDevice[device].hspi.Instance = spi->dev;
|
||||||
// Init SPI hardware
|
// Init SPI hardware
|
||||||
HAL_SPI_DeInit(&spiHardwareMap[device].hspi);
|
HAL_SPI_DeInit(&spiDevice[device].hspi);
|
||||||
|
|
||||||
spiHardwareMap[device].hspi.Init.Mode = SPI_MODE_MASTER;
|
spiDevice[device].hspi.Init.Mode = SPI_MODE_MASTER;
|
||||||
spiHardwareMap[device].hspi.Init.Direction = SPI_DIRECTION_2LINES;
|
spiDevice[device].hspi.Init.Direction = SPI_DIRECTION_2LINES;
|
||||||
spiHardwareMap[device].hspi.Init.DataSize = SPI_DATASIZE_8BIT;
|
spiDevice[device].hspi.Init.DataSize = SPI_DATASIZE_8BIT;
|
||||||
spiHardwareMap[device].hspi.Init.NSS = SPI_NSS_SOFT;
|
spiDevice[device].hspi.Init.NSS = SPI_NSS_SOFT;
|
||||||
spiHardwareMap[device].hspi.Init.FirstBit = SPI_FIRSTBIT_MSB;
|
spiDevice[device].hspi.Init.FirstBit = SPI_FIRSTBIT_MSB;
|
||||||
spiHardwareMap[device].hspi.Init.CRCPolynomial = 7;
|
spiDevice[device].hspi.Init.CRCPolynomial = 7;
|
||||||
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
|
spiDevice[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
|
||||||
spiHardwareMap[device].hspi.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
|
spiDevice[device].hspi.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
|
||||||
spiHardwareMap[device].hspi.Init.TIMode = SPI_TIMODE_DISABLED;
|
spiDevice[device].hspi.Init.TIMode = SPI_TIMODE_DISABLED;
|
||||||
|
|
||||||
if (spi->leadingEdge) {
|
if (spi->leadingEdge) {
|
||||||
spiHardwareMap[device].hspi.Init.CLKPolarity = SPI_POLARITY_LOW;
|
spiDevice[device].hspi.Init.CLKPolarity = SPI_POLARITY_LOW;
|
||||||
spiHardwareMap[device].hspi.Init.CLKPhase = SPI_PHASE_1EDGE;
|
spiDevice[device].hspi.Init.CLKPhase = SPI_PHASE_1EDGE;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
spiHardwareMap[device].hspi.Init.CLKPolarity = SPI_POLARITY_HIGH;
|
spiDevice[device].hspi.Init.CLKPolarity = SPI_POLARITY_HIGH;
|
||||||
spiHardwareMap[device].hspi.Init.CLKPhase = SPI_PHASE_2EDGE;
|
spiDevice[device].hspi.Init.CLKPhase = SPI_PHASE_2EDGE;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (HAL_SPI_Init(&spiHardwareMap[device].hspi) == HAL_OK) {
|
if (HAL_SPI_Init(&spiDevice[device].hspi) == HAL_OK)
|
||||||
|
{
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -237,8 +244,8 @@ uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance)
|
||||||
SPIDevice device = spiDeviceByInstance(instance);
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
if (device == SPIINVALID)
|
if (device == SPIINVALID)
|
||||||
return -1;
|
return -1;
|
||||||
spiHardwareMap[device].errorCount++;
|
spiDevice[device].errorCount++;
|
||||||
return spiHardwareMap[device].errorCount;
|
return spiDevice[device].errorCount;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -247,7 +254,7 @@ uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance)
|
||||||
bool spiIsBusBusy(SPI_TypeDef *instance)
|
bool spiIsBusBusy(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
SPIDevice device = spiDeviceByInstance(instance);
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
if(spiHardwareMap[device].hspi.State == HAL_SPI_STATE_BUSY)
|
if(spiDevice[device].hspi.State == HAL_SPI_STATE_BUSY)
|
||||||
return true;
|
return true;
|
||||||
else
|
else
|
||||||
return false;
|
return false;
|
||||||
|
@ -260,15 +267,15 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
||||||
|
|
||||||
if(!out) // Tx only
|
if(!out) // Tx only
|
||||||
{
|
{
|
||||||
status = HAL_SPI_Transmit(&spiHardwareMap[device].hspi, (uint8_t *)in, len, SPI_DEFAULT_TIMEOUT);
|
status = HAL_SPI_Transmit(&spiDevice[device].hspi, (uint8_t *)in, len, SPI_DEFAULT_TIMEOUT);
|
||||||
}
|
}
|
||||||
else if(!in) // Rx only
|
else if(!in) // Rx only
|
||||||
{
|
{
|
||||||
status = HAL_SPI_Receive(&spiHardwareMap[device].hspi, out, len, SPI_DEFAULT_TIMEOUT);
|
status = HAL_SPI_Receive(&spiDevice[device].hspi, out, len, SPI_DEFAULT_TIMEOUT);
|
||||||
}
|
}
|
||||||
else // Tx and Rx
|
else // Tx and Rx
|
||||||
{
|
{
|
||||||
status = HAL_SPI_TransmitReceive(&spiHardwareMap[device].hspi, (uint8_t *)in, out, len, SPI_DEFAULT_TIMEOUT);
|
status = HAL_SPI_TransmitReceive(&spiDevice[device].hspi, (uint8_t *)in, out, len, SPI_DEFAULT_TIMEOUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
if( status != HAL_OK)
|
if( status != HAL_OK)
|
||||||
|
@ -306,45 +313,19 @@ static uint8_t spiBusTransferByte(const busDevice_t *bus, uint8_t in)
|
||||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
||||||
{
|
{
|
||||||
SPIDevice device = spiDeviceByInstance(instance);
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
if (HAL_SPI_DeInit(&spiHardwareMap[device].hspi) == HAL_OK)
|
if (HAL_SPI_DeInit(&spiDevice[device].hspi) == HAL_OK)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (divisor) {
|
spiDevice[device].hspi.Init.BaudRatePrescaler = (uint8_t []) {
|
||||||
case 2:
|
0, 0,
|
||||||
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
|
SPI_BAUDRATEPRESCALER_2, SPI_BAUDRATEPRESCALER_4,
|
||||||
break;
|
SPI_BAUDRATEPRESCALER_8, SPI_BAUDRATEPRESCALER_16,
|
||||||
|
SPI_BAUDRATEPRESCALER_32, SPI_BAUDRATEPRESCALER_64,
|
||||||
|
SPI_BAUDRATEPRESCALER_128, SPI_BAUDRATEPRESCALER_256
|
||||||
|
}[ffs(divisor | 0x100)];
|
||||||
|
|
||||||
case 4:
|
if (HAL_SPI_Init(&spiDevice[device].hspi) == HAL_OK)
|
||||||
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 8:
|
|
||||||
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 16:
|
|
||||||
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 32:
|
|
||||||
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_32;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 64:
|
|
||||||
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_64;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 128:
|
|
||||||
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_128;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 256:
|
|
||||||
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (HAL_SPI_Init(&spiHardwareMap[device].hspi) == HAL_OK)
|
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -354,14 +335,14 @@ uint16_t spiGetErrorCounter(SPI_TypeDef *instance)
|
||||||
SPIDevice device = spiDeviceByInstance(instance);
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
if (device == SPIINVALID)
|
if (device == SPIINVALID)
|
||||||
return 0;
|
return 0;
|
||||||
return spiHardwareMap[device].errorCount;
|
return spiDevice[device].errorCount;
|
||||||
}
|
}
|
||||||
|
|
||||||
void spiResetErrorCounter(SPI_TypeDef *instance)
|
void spiResetErrorCounter(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
SPIDevice device = spiDeviceByInstance(instance);
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
if (device != SPIINVALID)
|
if (device != SPIINVALID)
|
||||||
spiHardwareMap[device].errorCount = 0;
|
spiDevice[device].errorCount = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
|
bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
|
||||||
|
@ -405,7 +386,7 @@ void dmaSPIIRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
{
|
{
|
||||||
SPIDevice device = descriptor->userParam;
|
SPIDevice device = descriptor->userParam;
|
||||||
if (device != SPIINVALID)
|
if (device != SPIINVALID)
|
||||||
HAL_DMA_IRQHandler(&spiHardwareMap[device].hdma);
|
HAL_DMA_IRQHandler(&spiDevice[device].hdma);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -413,35 +394,36 @@ DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channe
|
||||||
{
|
{
|
||||||
SPIDevice device = spiDeviceByInstance(Instance);
|
SPIDevice device = spiDeviceByInstance(Instance);
|
||||||
|
|
||||||
spiHardwareMap[device].hdma.Instance = Stream;
|
spiDevice[device].hdma.Instance = Stream;
|
||||||
spiHardwareMap[device].hdma.Init.Channel = Channel;
|
spiDevice[device].hdma.Init.Channel = Channel;
|
||||||
spiHardwareMap[device].hdma.Init.Direction = DMA_MEMORY_TO_PERIPH;
|
spiDevice[device].hdma.Init.Direction = DMA_MEMORY_TO_PERIPH;
|
||||||
spiHardwareMap[device].hdma.Init.PeriphInc = DMA_PINC_DISABLE;
|
spiDevice[device].hdma.Init.PeriphInc = DMA_PINC_DISABLE;
|
||||||
spiHardwareMap[device].hdma.Init.MemInc = DMA_MINC_ENABLE;
|
spiDevice[device].hdma.Init.MemInc = DMA_MINC_ENABLE;
|
||||||
spiHardwareMap[device].hdma.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
|
spiDevice[device].hdma.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
|
||||||
spiHardwareMap[device].hdma.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
|
spiDevice[device].hdma.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
|
||||||
spiHardwareMap[device].hdma.Init.Mode = DMA_NORMAL;
|
spiDevice[device].hdma.Init.Mode = DMA_NORMAL;
|
||||||
spiHardwareMap[device].hdma.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
|
spiDevice[device].hdma.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
|
||||||
spiHardwareMap[device].hdma.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
|
spiDevice[device].hdma.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
|
||||||
spiHardwareMap[device].hdma.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
spiDevice[device].hdma.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||||
spiHardwareMap[device].hdma.Init.MemBurst = DMA_MBURST_SINGLE;
|
spiDevice[device].hdma.Init.MemBurst = DMA_MBURST_SINGLE;
|
||||||
spiHardwareMap[device].hdma.Init.Priority = DMA_PRIORITY_LOW;
|
spiDevice[device].hdma.Init.Priority = DMA_PRIORITY_LOW;
|
||||||
|
|
||||||
HAL_DMA_DeInit(&spiHardwareMap[device].hdma);
|
HAL_DMA_DeInit(&spiDevice[device].hdma);
|
||||||
HAL_DMA_Init(&spiHardwareMap[device].hdma);
|
HAL_DMA_Init(&spiDevice[device].hdma);
|
||||||
|
|
||||||
__HAL_DMA_ENABLE(&spiHardwareMap[device].hdma);
|
__HAL_DMA_ENABLE(&spiDevice[device].hdma);
|
||||||
__HAL_SPI_ENABLE(&spiHardwareMap[device].hspi);
|
__HAL_SPI_ENABLE(&spiDevice[device].hspi);
|
||||||
|
|
||||||
/* Associate the initialized DMA handle to the spi handle */
|
/* Associate the initialized DMA handle to the spi handle */
|
||||||
__HAL_LINKDMA(&spiHardwareMap[device].hspi, hdmatx, spiHardwareMap[device].hdma);
|
__HAL_LINKDMA(&spiDevice[device].hspi, hdmatx, spiDevice[device].hdma);
|
||||||
|
|
||||||
// DMA TX Interrupt
|
// DMA TX Interrupt
|
||||||
dmaSetHandler(spiHardwareMap[device].dmaIrqHandler, dmaSPIIRQHandler, NVIC_BUILD_PRIORITY(3, 0), (uint32_t)device);
|
dmaSetHandler(spiDevice[device].dmaIrqHandler, dmaSPIIRQHandler, NVIC_BUILD_PRIORITY(3, 0), (uint32_t)device);
|
||||||
|
|
||||||
//HAL_CLEANCACHE(pData,Size);
|
//HAL_CLEANCACHE(pData,Size);
|
||||||
// And Transmit
|
// And Transmit
|
||||||
HAL_SPI_Transmit_DMA(&spiHardwareMap[device].hspi, pData, Size);
|
HAL_SPI_Transmit_DMA(&spiDevice[device].hspi, pData, Size);
|
||||||
|
|
||||||
return &spiHardwareMap[device].hdma;
|
return &spiDevice[device].hdma;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -0,0 +1,73 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#if defined(STM32F1) || defined(STM32F3) || defined(STM32F4)
|
||||||
|
#define MAX_SPI_PIN_SEL 2
|
||||||
|
#else
|
||||||
|
#define MAX_SPI_PIN_SEL 4
|
||||||
|
#endif
|
||||||
|
|
||||||
|
typedef struct spiPinDef_s {
|
||||||
|
ioTag_t pin;
|
||||||
|
#ifdef STM32F7
|
||||||
|
uint8_t af;
|
||||||
|
#endif
|
||||||
|
} spiPinDef_t;
|
||||||
|
|
||||||
|
typedef struct spiHardware_s {
|
||||||
|
SPIDevice device;
|
||||||
|
SPI_TypeDef *reg;
|
||||||
|
spiPinDef_t sckPins[MAX_SPI_PIN_SEL];
|
||||||
|
spiPinDef_t misoPins[MAX_SPI_PIN_SEL];
|
||||||
|
spiPinDef_t mosiPins[MAX_SPI_PIN_SEL];
|
||||||
|
#ifndef STM32F7
|
||||||
|
uint8_t af;
|
||||||
|
#endif
|
||||||
|
rccPeriphTag_t rcc;
|
||||||
|
#if defined(USE_HAL_DRIVER)
|
||||||
|
uint8_t dmaIrqHandler;
|
||||||
|
#endif
|
||||||
|
} spiHardware_t;
|
||||||
|
|
||||||
|
extern const spiHardware_t spiHardware[];
|
||||||
|
|
||||||
|
typedef struct SPIDevice_s {
|
||||||
|
SPI_TypeDef *dev;
|
||||||
|
ioTag_t sck;
|
||||||
|
ioTag_t miso;
|
||||||
|
ioTag_t mosi;
|
||||||
|
#ifdef STM32F7
|
||||||
|
uint8_t sckAF;
|
||||||
|
uint8_t misoAF;
|
||||||
|
uint8_t mosiAF;
|
||||||
|
#else
|
||||||
|
uint8_t af;
|
||||||
|
#endif
|
||||||
|
rccPeriphTag_t rcc;
|
||||||
|
volatile uint16_t errorCount;
|
||||||
|
bool leadingEdge;
|
||||||
|
#if defined(USE_HAL_DRIVER)
|
||||||
|
SPI_HandleTypeDef hspi;
|
||||||
|
DMA_HandleTypeDef hdma;
|
||||||
|
uint8_t dmaIrqHandler;
|
||||||
|
#endif
|
||||||
|
} spiDevice_t;
|
||||||
|
|
||||||
|
extern spiDevice_t spiDevice[SPIDEV_COUNT];
|
||||||
|
|
|
@ -0,0 +1,386 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#include <platform.h>
|
||||||
|
|
||||||
|
#ifdef USE_SPI
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/bus_spi_impl.h"
|
||||||
|
#include "drivers/dma.h"
|
||||||
|
#include "drivers/exti.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
|
#include "config/parameter_group.h"
|
||||||
|
#include "config/parameter_group_ids.h"
|
||||||
|
|
||||||
|
// Pin defaults for backward compatibility
|
||||||
|
#ifndef SPI1_SCK_PIN
|
||||||
|
#define SPI1_SCK_PIN PA5
|
||||||
|
#define SPI1_MISO_PIN PA6
|
||||||
|
#define SPI1_MOSI_PIN PA7
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SPI2_SCK_PIN
|
||||||
|
#define SPI2_SCK_PIN PB13
|
||||||
|
#define SPI2_MISO_PIN PB14
|
||||||
|
#define SPI2_MOSI_PIN PB15
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SPI3_SCK_PIN
|
||||||
|
#define SPI3_SCK_PIN PB3
|
||||||
|
#define SPI3_MISO_PIN PB4
|
||||||
|
#define SPI3_MOSI_PIN PB5
|
||||||
|
#endif
|
||||||
|
|
||||||
|
PG_DECLARE(spiPinConfig_t, spiPinConfig);
|
||||||
|
|
||||||
|
PG_REGISTER_WITH_RESET_FN(spiPinConfig_t, spiPinConfig, PG_SPI_PIN_CONFIG, 0);
|
||||||
|
|
||||||
|
typedef struct spiDefaultConfig_s {
|
||||||
|
SPIDevice device;
|
||||||
|
ioTag_t sck;
|
||||||
|
ioTag_t miso;
|
||||||
|
ioTag_t mosi;
|
||||||
|
} spiDefaultConfig_t;
|
||||||
|
|
||||||
|
const spiDefaultConfig_t spiDefaultConfig[] = {
|
||||||
|
#ifdef USE_SPI_DEVICE_1
|
||||||
|
{ SPIDEV_1, IO_TAG(SPI1_SCK_PIN), IO_TAG(SPI1_MISO_PIN), IO_TAG(SPI1_MOSI_PIN) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_2
|
||||||
|
{ SPIDEV_2, IO_TAG(SPI2_SCK_PIN), IO_TAG(SPI2_MISO_PIN), IO_TAG(SPI2_MOSI_PIN) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_3
|
||||||
|
{ SPIDEV_3, IO_TAG(SPI3_SCK_PIN), IO_TAG(SPI3_MISO_PIN), IO_TAG(SPI3_MOSI_PIN) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_4
|
||||||
|
{ SPIDEV_4, IO_TAG(SPI4_SCK_PIN), IO_TAG(SPI4_MISO_PIN), IO_TAG(SPI4_MOSI_PIN) },
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
|
void pgResetFn_spiPinConfig(spiPinConfig_t *spiPinConfig)
|
||||||
|
{
|
||||||
|
for (size_t i = 0 ; i < ARRAYLEN(spiDefaultConfig) ; i++) {
|
||||||
|
const spiDefaultConfig_t *defconf = &spiDefaultConfig[i];
|
||||||
|
spiPinConfig->ioTagSck[defconf->device] = defconf->sck;
|
||||||
|
spiPinConfig->ioTagMiso[defconf->device] = defconf->miso;
|
||||||
|
spiPinConfig->ioTagMosi[defconf->device] = defconf->mosi;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
const spiHardware_t spiHardware[] = {
|
||||||
|
#ifdef STM32F1
|
||||||
|
// Remapping is not supported and corresponding lines are commented out.
|
||||||
|
// There also is some errata that may prevent these assignments from working:
|
||||||
|
// http://www.st.com/content/ccc/resource/technical/document/errata_sheet/7d/02/75/64/17/fc/4d/fd/CD00190234.pdf/files/CD00190234.pdf/jcr:content/translations/en.CD00190234.pdf
|
||||||
|
{
|
||||||
|
.device = SPIDEV_1,
|
||||||
|
.reg = SPI1,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PA5) },
|
||||||
|
// { DEFIO_TAG_E(PB3) },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PA6) },
|
||||||
|
// { DEFIO_TAG_E(PB4) },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PA7) },
|
||||||
|
// { DEFIO_TAG_E(PB5) },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB2(SPI1),
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.device = SPIDEV_2,
|
||||||
|
.reg = SPI2,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PB13) },
|
||||||
|
// { DEFIO_TAG_E(PB3) },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PB14) },
|
||||||
|
// { DEFIO_TAG_E(PB4) },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PB15) },
|
||||||
|
// { DEFIO_TAG_E(PB5) },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB1(SPI2),
|
||||||
|
},
|
||||||
|
#endif
|
||||||
|
#ifdef STM32F3
|
||||||
|
|
||||||
|
#ifndef GPIO_AF_SPI1
|
||||||
|
#define GPIO_AF_SPI1 GPIO_AF_5
|
||||||
|
#endif
|
||||||
|
#ifndef GPIO_AF_SPI2
|
||||||
|
#define GPIO_AF_SPI2 GPIO_AF_5
|
||||||
|
#endif
|
||||||
|
#ifndef GPIO_AF_SPI3
|
||||||
|
#define GPIO_AF_SPI3 GPIO_AF_6
|
||||||
|
#endif
|
||||||
|
|
||||||
|
{
|
||||||
|
.device = SPIDEV_1,
|
||||||
|
.reg = SPI1,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PA5) },
|
||||||
|
{ DEFIO_TAG_E(PB3) },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PA6) },
|
||||||
|
{ DEFIO_TAG_E(PB4) },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PA7) },
|
||||||
|
{ DEFIO_TAG_E(PB5) },
|
||||||
|
},
|
||||||
|
.af = GPIO_AF_SPI1,
|
||||||
|
.rcc = RCC_APB2(SPI1),
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.device = SPIDEV_2,
|
||||||
|
.reg = SPI2,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PB13) },
|
||||||
|
{ DEFIO_TAG_E(PB3) },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PB14) },
|
||||||
|
{ DEFIO_TAG_E(PB4) },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PB15) },
|
||||||
|
{ DEFIO_TAG_E(PB5) },
|
||||||
|
},
|
||||||
|
.af = GPIO_AF_SPI2,
|
||||||
|
.rcc = RCC_APB1(SPI2),
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.device = SPIDEV_3,
|
||||||
|
.reg = SPI3,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PB3) },
|
||||||
|
{ DEFIO_TAG_E(PC10) },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PB4) },
|
||||||
|
{ DEFIO_TAG_E(PC11) },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PB5) },
|
||||||
|
{ DEFIO_TAG_E(PC12) },
|
||||||
|
},
|
||||||
|
.af = GPIO_AF_SPI3,
|
||||||
|
.rcc = RCC_APB1(SPI3),
|
||||||
|
},
|
||||||
|
#endif
|
||||||
|
#ifdef STM32F4
|
||||||
|
{
|
||||||
|
.device = SPIDEV_1,
|
||||||
|
.reg = SPI1,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PA5) },
|
||||||
|
{ DEFIO_TAG_E(PB3) },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PA6) },
|
||||||
|
{ DEFIO_TAG_E(PB4) },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PA7) },
|
||||||
|
{ DEFIO_TAG_E(PB5) },
|
||||||
|
},
|
||||||
|
.af = GPIO_AF_SPI1,
|
||||||
|
.rcc = RCC_APB2(SPI1),
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.device = SPIDEV_2,
|
||||||
|
.reg = SPI2,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PB10) },
|
||||||
|
{ DEFIO_TAG_E(PB13) },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PB14) },
|
||||||
|
{ DEFIO_TAG_E(PC2) },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PB15) },
|
||||||
|
{ DEFIO_TAG_E(PC3) },
|
||||||
|
},
|
||||||
|
.af = GPIO_AF_SPI2,
|
||||||
|
.rcc = RCC_APB1(SPI2),
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.device = SPIDEV_3,
|
||||||
|
.reg = SPI3,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PB3) },
|
||||||
|
{ DEFIO_TAG_E(PC10) },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PB4) },
|
||||||
|
{ DEFIO_TAG_E(PC11) },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PB5) },
|
||||||
|
{ DEFIO_TAG_E(PC12) },
|
||||||
|
},
|
||||||
|
.af = GPIO_AF_SPI3,
|
||||||
|
.rcc = RCC_APB1(SPI3),
|
||||||
|
},
|
||||||
|
#endif
|
||||||
|
#ifdef STM32F7
|
||||||
|
{
|
||||||
|
.device = SPIDEV_1,
|
||||||
|
.reg = SPI1,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PA5), GPIO_AF5_SPI1 },
|
||||||
|
{ DEFIO_TAG_E(PB3), GPIO_AF5_SPI1 },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PA6), GPIO_AF5_SPI1 },
|
||||||
|
{ DEFIO_TAG_E(PB4), GPIO_AF5_SPI1 },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PA7), GPIO_AF5_SPI1 },
|
||||||
|
{ DEFIO_TAG_E(PB5), GPIO_AF5_SPI1 },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB2(SPI1),
|
||||||
|
.dmaIrqHandler = DMA2_ST3_HANDLER,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.device = SPIDEV_2,
|
||||||
|
.reg = SPI2,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PA9), GPIO_AF5_SPI2 },
|
||||||
|
{ DEFIO_TAG_E(PB10), GPIO_AF5_SPI2 },
|
||||||
|
{ DEFIO_TAG_E(PB13), GPIO_AF5_SPI2 },
|
||||||
|
{ DEFIO_TAG_E(PD3), GPIO_AF5_SPI2 },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PB14), GPIO_AF5_SPI2 },
|
||||||
|
{ DEFIO_TAG_E(PC2), GPIO_AF5_SPI2 },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PB15), GPIO_AF5_SPI2 },
|
||||||
|
{ DEFIO_TAG_E(PC1), GPIO_AF5_SPI2 },
|
||||||
|
{ DEFIO_TAG_E(PC3), GPIO_AF5_SPI2 },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB1(SPI2),
|
||||||
|
.dmaIrqHandler = DMA1_ST4_HANDLER,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.device = SPIDEV_3,
|
||||||
|
.reg = SPI3,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PB3), GPIO_AF6_SPI3 },
|
||||||
|
{ DEFIO_TAG_E(PC10), GPIO_AF6_SPI3 },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PB4), GPIO_AF6_SPI3 },
|
||||||
|
{ DEFIO_TAG_E(PC11), GPIO_AF6_SPI3 },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PB2), GPIO_AF7_SPI3 },
|
||||||
|
{ DEFIO_TAG_E(PB5), GPIO_AF6_SPI3 },
|
||||||
|
{ DEFIO_TAG_E(PC12), GPIO_AF6_SPI3 },
|
||||||
|
{ DEFIO_TAG_E(PD6), GPIO_AF5_SPI3 },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB1(SPI3),
|
||||||
|
.dmaIrqHandler = DMA1_ST7_HANDLER,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.device = SPIDEV_4,
|
||||||
|
.reg = SPI4,
|
||||||
|
.sckPins = {
|
||||||
|
{ DEFIO_TAG_E(PE2), GPIO_AF5_SPI4 },
|
||||||
|
{ DEFIO_TAG_E(PE12), GPIO_AF5_SPI4 },
|
||||||
|
},
|
||||||
|
.misoPins = {
|
||||||
|
{ DEFIO_TAG_E(PE5), GPIO_AF5_SPI4 },
|
||||||
|
{ DEFIO_TAG_E(PE13), GPIO_AF5_SPI4 },
|
||||||
|
},
|
||||||
|
.mosiPins = {
|
||||||
|
{ DEFIO_TAG_E(PE6), GPIO_AF5_SPI4 },
|
||||||
|
{ DEFIO_TAG_E(PE14), GPIO_AF5_SPI4 },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB2(SPI4),
|
||||||
|
.dmaIrqHandler = DMA2_ST1_HANDLER,
|
||||||
|
},
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
|
void spiPinConfigure(void)
|
||||||
|
{
|
||||||
|
const spiPinConfig_t *pConfig = spiPinConfig();
|
||||||
|
|
||||||
|
for (size_t hwindex = 0 ; hwindex < ARRAYLEN(spiHardware) ; hwindex++) {
|
||||||
|
const spiHardware_t *hw = &spiHardware[hwindex];
|
||||||
|
|
||||||
|
if (!hw->reg) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
SPIDevice device = hw->device;
|
||||||
|
spiDevice_t *pDev = &spiDevice[device];
|
||||||
|
|
||||||
|
for (int pindex = 0 ; pindex < MAX_SPI_PIN_SEL ; pindex++) {
|
||||||
|
if (pConfig->ioTagSck[device] == hw->sckPins[pindex].pin) {
|
||||||
|
pDev->sck = hw->sckPins[pindex].pin;
|
||||||
|
#ifdef STM32F7
|
||||||
|
pDev->sckAF = hw->sckPins[pindex].af;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
if (pConfig->ioTagMiso[device] == hw->misoPins[pindex].pin) {
|
||||||
|
pDev->miso = hw->misoPins[pindex].pin;
|
||||||
|
#ifdef STM32F7
|
||||||
|
pDev->misoAF = hw->misoPins[pindex].af;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
if (pConfig->ioTagMosi[device] == hw->mosiPins[pindex].pin) {
|
||||||
|
pDev->mosi = hw->mosiPins[pindex].pin;
|
||||||
|
#ifdef STM32F7
|
||||||
|
pDev->mosiAF = hw->mosiPins[pindex].af;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (pDev->sck && pDev->miso && pDev->mosi) {
|
||||||
|
pDev->dev = hw->reg;
|
||||||
|
#ifndef STM32F7
|
||||||
|
pDev->af = hw->af;
|
||||||
|
#endif
|
||||||
|
pDev->rcc = hw->rcc;
|
||||||
|
pDev->leadingEdge = false; // XXX Should be part of transfer context
|
||||||
|
#ifdef USE_HAL_DRIVER
|
||||||
|
pDev->dmaIrqHandler = hw->dmaIrqHandler;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
|
@ -56,6 +56,7 @@ extern uint8_t __config_end;
|
||||||
#include "drivers/accgyro/accgyro.h"
|
#include "drivers/accgyro/accgyro.h"
|
||||||
#include "drivers/buf_writer.h"
|
#include "drivers/buf_writer.h"
|
||||||
#include "drivers/bus_i2c.h"
|
#include "drivers/bus_i2c.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/compass/compass.h"
|
#include "drivers/compass/compass.h"
|
||||||
#include "drivers/display.h"
|
#include "drivers/display.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
|
@ -2848,6 +2849,11 @@ const cliResourceValue_t resourceTable[] = {
|
||||||
#ifdef TRANSPONDER
|
#ifdef TRANSPONDER
|
||||||
{ OWNER_TRANSPONDER, PG_TRANSPONDER_CONFIG, offsetof(transponderConfig_t, ioTag), 0 },
|
{ OWNER_TRANSPONDER, PG_TRANSPONDER_CONFIG, offsetof(transponderConfig_t, ioTag), 0 },
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef USE_SPI
|
||||||
|
{ OWNER_SPI_SCK, PG_SPI_PIN_CONFIG, offsetof(spiPinConfig_t, ioTagSck[0]), SPIDEV_COUNT },
|
||||||
|
{ OWNER_SPI_MISO, PG_SPI_PIN_CONFIG, offsetof(spiPinConfig_t, ioTagMiso[0]), SPIDEV_COUNT },
|
||||||
|
{ OWNER_SPI_MOSI, PG_SPI_PIN_CONFIG, offsetof(spiPinConfig_t, ioTagMosi[0]), SPIDEV_COUNT },
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
|
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
|
||||||
|
|
|
@ -408,6 +408,8 @@ void init(void)
|
||||||
#else
|
#else
|
||||||
|
|
||||||
#ifdef USE_SPI
|
#ifdef USE_SPI
|
||||||
|
spiPinConfigure();
|
||||||
|
|
||||||
// Initialize CS lines and keep them high
|
// Initialize CS lines and keep them high
|
||||||
spiPreInit();
|
spiPreInit();
|
||||||
|
|
||||||
|
|
|
@ -29,6 +29,7 @@ extern void spiPreInit(void); // XXX In fc/fc_init.c
|
||||||
void targetBusInit(void)
|
void targetBusInit(void)
|
||||||
{
|
{
|
||||||
#if defined(USE_SPI) && defined(USE_SPI_DEVICE_1)
|
#if defined(USE_SPI) && defined(USE_SPI_DEVICE_1)
|
||||||
|
spiPinConfigure();
|
||||||
spiPreInit();
|
spiPreInit();
|
||||||
spiInit(SPIDEV_1);
|
spiInit(SPIDEV_1);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#include "drivers/bus_i2c.h"
|
#include "drivers/bus_i2c.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
|
@ -53,8 +54,14 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
#ifdef USE_BST
|
#ifdef USE_BST
|
||||||
void targetBusInit(void)
|
void targetBusInit(void)
|
||||||
{
|
{
|
||||||
|
#ifdef USE_SPI
|
||||||
|
spiPinConfigure();
|
||||||
|
#ifdef USE_SPI_DEVICE_1
|
||||||
|
spiInit(SPIDEV_1);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
i2cHardwareConfigure();
|
i2cHardwareConfigure();
|
||||||
bstInit(BST_DEVICE);
|
bstInit(BST_DEVICE);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -30,6 +30,7 @@ extern void spiPreInit(void); // XXX In fc/fc_init.c
|
||||||
void targetBusInit(void)
|
void targetBusInit(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_SPI
|
#ifdef USE_SPI
|
||||||
|
spiPinConfigure();
|
||||||
spiPreInit();
|
spiPreInit();
|
||||||
#ifdef USE_SPI_DEVICE_2
|
#ifdef USE_SPI_DEVICE_2
|
||||||
spiInit(SPIDEV_2);
|
spiInit(SPIDEV_2);
|
||||||
|
|
Loading…
Reference in New Issue