mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 03:20:00 +03:00
Refactor SPI pre init to make it generic and usable from io.h (#14174)
This commit is contained in:
parent
01af6d13bf
commit
908a347d2f
35 changed files with 107 additions and 126 deletions
|
@ -104,6 +104,7 @@ COMMON_SRC = \
|
||||||
drivers/display_canvas.c \
|
drivers/display_canvas.c \
|
||||||
drivers/dma_common.c \
|
drivers/dma_common.c \
|
||||||
drivers/io.c \
|
drivers/io.c \
|
||||||
|
drivers/io_preinit.c \
|
||||||
drivers/light_led.c \
|
drivers/light_led.c \
|
||||||
drivers/mco.c \
|
drivers/mco.c \
|
||||||
drivers/motor.c \
|
drivers/motor.c \
|
||||||
|
|
|
@ -410,9 +410,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyro
|
||||||
}
|
}
|
||||||
|
|
||||||
// Detection failed, disable CS pin again
|
// Detection failed, disable CS pin again
|
||||||
|
ioPreinitByIO(gyro->dev.busType_u.spi.csnPin, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
spiPreinitByTag(config->csnTag);
|
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -420,7 +418,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyro
|
||||||
void mpuPreInit(const struct gyroDeviceConfig_s *config)
|
void mpuPreInit(const struct gyroDeviceConfig_s *config)
|
||||||
{
|
{
|
||||||
#ifdef USE_SPI_GYRO
|
#ifdef USE_SPI_GYRO
|
||||||
spiPreinitRegister(config->csnTag, IOCFG_IPU, 1);
|
ioPreinitByTag(config->csnTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
#else
|
#else
|
||||||
UNUSED(config);
|
UNUSED(config);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -192,7 +192,7 @@ static void busDeviceDeInit(const extDevice_t *dev)
|
||||||
{
|
{
|
||||||
#ifdef USE_BARO_SPI_2SMBP_02B
|
#ifdef USE_BARO_SPI_2SMBP_02B
|
||||||
if (dev->bus->busType == BUS_TYPE_SPI) {
|
if (dev->bus->busType == BUS_TYPE_SPI) {
|
||||||
spiPreinitByIO(dev->busType_u.spi.csnPin);
|
ioPreinitByIO(dev->busType_u.spi.csnPin, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
UNUSED(dev);
|
UNUSED(dev);
|
||||||
|
|
|
@ -135,7 +135,7 @@ void bmp280BusDeinit(const extDevice_t *dev)
|
||||||
{
|
{
|
||||||
#ifdef USE_BARO_SPI_BMP280
|
#ifdef USE_BARO_SPI_BMP280
|
||||||
if (dev->bus->busType == BUS_TYPE_SPI) {
|
if (dev->bus->busType == BUS_TYPE_SPI) {
|
||||||
spiPreinitByIO(dev->busType_u.spi.csnPin);
|
ioPreinitByIO(dev->busType_u.spi.csnPin, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
UNUSED(dev);
|
UNUSED(dev);
|
||||||
|
|
|
@ -230,7 +230,7 @@ void bmp388BusDeinit(const extDevice_t *dev)
|
||||||
{
|
{
|
||||||
#ifdef USE_BARO_SPI_BMP388
|
#ifdef USE_BARO_SPI_BMP388
|
||||||
if (dev->bus->busType == BUS_TYPE_SPI) {
|
if (dev->bus->busType == BUS_TYPE_SPI) {
|
||||||
spiPreinitByIO(dev->busType_u.spi.csnPin);
|
ioPreinitByIO(dev->busType_u.spi.csnPin, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
UNUSED(dev);
|
UNUSED(dev);
|
||||||
|
|
|
@ -377,7 +377,7 @@ static void deviceDeInit(const extDevice_t *dev)
|
||||||
{
|
{
|
||||||
#ifdef USE_BARO_SPI_DPS310
|
#ifdef USE_BARO_SPI_DPS310
|
||||||
if (dev->bus->busType == BUS_TYPE_SPI) {
|
if (dev->bus->busType == BUS_TYPE_SPI) {
|
||||||
spiPreinitByIO(dev->busType_u.spi.csnPin);
|
ioPreinitByIO(dev->busType_u.spi.csnPin, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
UNUSED(dev);
|
UNUSED(dev);
|
||||||
|
|
|
@ -245,7 +245,7 @@ void lps22dfBusDeinit(const extDevice_t *dev)
|
||||||
{
|
{
|
||||||
#ifdef USE_BARO_SPI_LPS22DF
|
#ifdef USE_BARO_SPI_LPS22DF
|
||||||
if (dev->bus->busType == BUS_TYPE_SPI) {
|
if (dev->bus->busType == BUS_TYPE_SPI) {
|
||||||
spiPreinitByIO(dev->busType_u.spi.csnPin);
|
ioPreinitByIO(dev->busType_u.spi.csnPin, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
UNUSED(dev);
|
UNUSED(dev);
|
||||||
|
|
|
@ -80,7 +80,7 @@ void ms5611BusDeinit(const extDevice_t *dev)
|
||||||
{
|
{
|
||||||
#ifdef USE_BARO_SPI_MS5611
|
#ifdef USE_BARO_SPI_MS5611
|
||||||
if (dev->bus->busType == BUS_TYPE_SPI) {
|
if (dev->bus->busType == BUS_TYPE_SPI) {
|
||||||
spiPreinitByIO(dev->busType_u.spi.csnPin);
|
ioPreinitByIO(dev->busType_u.spi.csnPin, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
UNUSED(dev);
|
UNUSED(dev);
|
||||||
|
|
|
@ -65,10 +65,6 @@ typedef enum SPIDevice {
|
||||||
#define SPI_DEV_TO_CFG(x) ((x) + 1)
|
#define SPI_DEV_TO_CFG(x) ((x) + 1)
|
||||||
|
|
||||||
void spiPreinit(void);
|
void spiPreinit(void);
|
||||||
void spiPreinitRegister(ioTag_t iotag, uint8_t iocfg, uint8_t init);
|
|
||||||
void spiPreinitByIO(const IO_t io);
|
|
||||||
void spiPreinitByTag(ioTag_t tag);
|
|
||||||
|
|
||||||
bool spiInit(SPIDevice device);
|
bool spiInit(SPIDevice device);
|
||||||
|
|
||||||
// Called after all devices are initialised to enable SPI DMA where streams are available.
|
// Called after all devices are initialised to enable SPI DMA where streams are available.
|
||||||
|
|
|
@ -39,48 +39,10 @@
|
||||||
#include "pg/rx_spi.h"
|
#include "pg/rx_spi.h"
|
||||||
#include "pg/sdcard.h"
|
#include "pg/sdcard.h"
|
||||||
|
|
||||||
typedef struct spiPreinit_s {
|
|
||||||
ioTag_t iotag;
|
|
||||||
uint8_t iocfg;
|
|
||||||
bool init;
|
|
||||||
} spiPreinit_t;
|
|
||||||
|
|
||||||
static spiPreinit_t spiPreinitArray[SPI_PREINIT_COUNT];
|
|
||||||
static int spiPreinitCount = 0;
|
|
||||||
|
|
||||||
void spiPreinitRegister(ioTag_t iotag, uint8_t iocfg, bool init)
|
|
||||||
{
|
|
||||||
if (!iotag) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (spiPreinitCount == SPI_PREINIT_COUNT) {
|
|
||||||
indicateFailure(FAILURE_DEVELOPER, 5);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
spiPreinitArray[spiPreinitCount].iotag = iotag;
|
|
||||||
spiPreinitArray[spiPreinitCount].iocfg = iocfg;
|
|
||||||
spiPreinitArray[spiPreinitCount].init = init;
|
|
||||||
++spiPreinitCount;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void spiPreinitPin(spiPreinit_t *preinit, int index)
|
|
||||||
{
|
|
||||||
IO_t io = IOGetByTag(preinit->iotag);
|
|
||||||
IOInit(io, OWNER_PREINIT, RESOURCE_INDEX(index));
|
|
||||||
IOConfigGPIO(io, preinit->iocfg);
|
|
||||||
if (preinit->init) {
|
|
||||||
IOHi(io);
|
|
||||||
} else {
|
|
||||||
IOLo(io);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void spiPreinit(void)
|
void spiPreinit(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_SDCARD_SPI
|
#ifdef USE_SDCARD_SPI
|
||||||
sdcard_preInit(sdcardConfig());
|
sdcard_preinit(sdcardConfig());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(RTC6705_CS_PIN) && !defined(USE_VTX_RTC6705_SOFTSPI) // RTC6705 soft SPI initialisation handled elsewhere.
|
#if defined(RTC6705_CS_PIN) && !defined(USE_VTX_RTC6705_SOFTSPI) // RTC6705 soft SPI initialisation handled elsewhere.
|
||||||
|
@ -88,34 +50,16 @@ void spiPreinit(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FLASH_CHIP
|
#ifdef USE_FLASH_CHIP
|
||||||
flashPreInit(flashConfig());
|
flashPreinit(flashConfig());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_RX_SPI)
|
#if defined(USE_RX_SPI)
|
||||||
rxSpiDevicePreInit(rxSpiConfig());
|
rxSpiDevicePreinit(rxSpiConfig());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_MAX7456
|
#ifdef USE_MAX7456
|
||||||
max7456PreInit(max7456Config());
|
max7456Preinit(max7456Config());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
for (int i = 0; i < spiPreinitCount; i++) {
|
|
||||||
spiPreinitPin(&spiPreinitArray[i], i);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void spiPreinitByIO(const IO_t io)
|
|
||||||
{
|
|
||||||
for (int i = 0; i < spiPreinitCount; i++) {
|
|
||||||
if (io == IOGetByTag(spiPreinitArray[i].iotag)) {
|
|
||||||
spiPreinitPin(&spiPreinitArray[i], i);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void spiPreinitByTag(ioTag_t tag)
|
|
||||||
{
|
|
||||||
spiPreinitByIO(IOGetByTag(tag));
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -420,7 +420,7 @@ void ak8963BusDeInit(const extDevice_t *dev)
|
||||||
|
|
||||||
#ifdef USE_MAG_SPI_AK8963
|
#ifdef USE_MAG_SPI_AK8963
|
||||||
case BUS_TYPE_SPI:
|
case BUS_TYPE_SPI:
|
||||||
spiPreinitByIO(dev->busType_u.spi.csnPin);
|
ioPreinitByIO(dev->busType_u.spi.csnPin, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -350,15 +350,14 @@ static bool flashSpiInit(const flashConfig_t *flashConfig)
|
||||||
return detected;
|
return detected;
|
||||||
}
|
}
|
||||||
|
|
||||||
spiPreinitByTag(flashConfig->csTag);
|
ioPreinitByTag(flashConfig->csTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#endif // USE_FLASH_SPI
|
#endif // USE_FLASH_SPI
|
||||||
|
|
||||||
void flashPreInit(const flashConfig_t *flashConfig)
|
void flashPreinit(const flashConfig_t *flashConfig)
|
||||||
{
|
{
|
||||||
spiPreinitRegister(flashConfig->csTag, IOCFG_IPU, 1);
|
ioPreinitByTag(flashConfig->csTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool flashDeviceInit(const flashConfig_t *flashConfig)
|
bool flashDeviceInit(const flashConfig_t *flashConfig)
|
||||||
|
|
|
@ -57,7 +57,7 @@ typedef enum {
|
||||||
FLASH_CF_SYSTEM_IS_MEMORY_MAPPED = (1 << 0),
|
FLASH_CF_SYSTEM_IS_MEMORY_MAPPED = (1 << 0),
|
||||||
} flashConfigurationFlags_e;
|
} flashConfigurationFlags_e;
|
||||||
|
|
||||||
void flashPreInit(const flashConfig_t *flashConfig);
|
void flashPreinit(const flashConfig_t *flashConfig);
|
||||||
bool flashInit(const flashConfig_t *flashConfig);
|
bool flashInit(const flashConfig_t *flashConfig);
|
||||||
|
|
||||||
bool flashIsReady(void);
|
bool flashIsReady(void);
|
||||||
|
|
|
@ -64,3 +64,12 @@ void IOTraversePins(IOTraverseFuncPtr_t func);
|
||||||
|
|
||||||
GPIO_TypeDef* IO_GPIO(IO_t io);
|
GPIO_TypeDef* IO_GPIO(IO_t io);
|
||||||
uint16_t IO_Pin(IO_t io);
|
uint16_t IO_Pin(IO_t io);
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
PREINIT_PIN_STATE_NOCHANGE = 0,
|
||||||
|
PREINIT_PIN_STATE_LOW,
|
||||||
|
PREINIT_PIN_STATE_HIGH,
|
||||||
|
} ioPreinitPinState_e;
|
||||||
|
|
||||||
|
void ioPreinitByIO(const IO_t io, uint8_t iocfg, ioPreinitPinState_e init);
|
||||||
|
void ioPreinitByTag(ioTag_t tag, uint8_t iocfg, ioPreinitPinState_e init);
|
||||||
|
|
58
src/main/drivers/io_preinit.c
Normal file
58
src/main/drivers/io_preinit.c
Normal file
|
@ -0,0 +1,58 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Betaflight.
|
||||||
|
*
|
||||||
|
* Betaflight is free software. You can redistribute this software
|
||||||
|
* and/or modify this software 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.
|
||||||
|
*
|
||||||
|
* Betaflight 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 this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "drivers/resource.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
static unsigned preinitIndex = 0;
|
||||||
|
|
||||||
|
void ioPreinitByIO(const IO_t io, uint8_t iocfg, ioPreinitPinState_e init)
|
||||||
|
{
|
||||||
|
if (!io) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
preinitIndex++;
|
||||||
|
|
||||||
|
IOInit(io, OWNER_PREINIT, preinitIndex);
|
||||||
|
IOConfigGPIO(io, iocfg);
|
||||||
|
|
||||||
|
switch(init) {
|
||||||
|
case PREINIT_PIN_STATE_LOW:
|
||||||
|
IOLo(io);
|
||||||
|
break;
|
||||||
|
case PREINIT_PIN_STATE_HIGH:
|
||||||
|
IOHi(io);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
// Do nothing
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ioPreinitByTag(ioTag_t tag, uint8_t iocfg, ioPreinitPinState_e init)
|
||||||
|
{
|
||||||
|
ioPreinitByIO(IOGetByTag(tag), iocfg, init);
|
||||||
|
}
|
|
@ -330,9 +330,9 @@ void max7456ReInit(void)
|
||||||
max7456ClearShadowBuffer();
|
max7456ClearShadowBuffer();
|
||||||
}
|
}
|
||||||
|
|
||||||
void max7456PreInit(const max7456Config_t *max7456Config)
|
void max7456Preinit(const max7456Config_t *max7456Config)
|
||||||
{
|
{
|
||||||
spiPreinitRegister(max7456Config->csTag, max7456Config->preInitOPU ? IOCFG_OUT_PP : IOCFG_IPU, 1);
|
ioPreinitByTag(max7456Config->csTag, max7456Config->preInitOPU ? IOCFG_OUT_PP : IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Here we init only CS and try to init MAX for first time.
|
// Here we init only CS and try to init MAX for first time.
|
||||||
|
|
|
@ -43,7 +43,7 @@ extern uint16_t maxScreenSize;
|
||||||
struct vcdProfile_s;
|
struct vcdProfile_s;
|
||||||
void max7456HardwareReset(void);
|
void max7456HardwareReset(void);
|
||||||
struct max7456Config_s;
|
struct max7456Config_s;
|
||||||
void max7456PreInit(const struct max7456Config_s *max7456Config);
|
void max7456Preinit(const struct max7456Config_s *max7456Config);
|
||||||
max7456InitStatus_e max7456Init(const struct max7456Config_s *max7456Config, const struct vcdProfile_s *vcdProfile, bool cpuOverclock);
|
max7456InitStatus_e max7456Init(const struct max7456Config_s *max7456Config, const struct vcdProfile_s *vcdProfile, bool cpuOverclock);
|
||||||
void max7456Invert(bool invert);
|
void max7456Invert(bool invert);
|
||||||
void max7456Brightness(uint8_t black, uint8_t white);
|
void max7456Brightness(uint8_t black, uint8_t white);
|
||||||
|
|
|
@ -70,9 +70,9 @@ extDevice_t *rxSpiGetDevice(void)
|
||||||
return dev;
|
return dev;
|
||||||
}
|
}
|
||||||
|
|
||||||
void rxSpiDevicePreInit(const rxSpiConfig_t *rxSpiConfig)
|
void rxSpiDevicePreinit(const rxSpiConfig_t *rxSpiConfig)
|
||||||
{
|
{
|
||||||
spiPreinitRegister(rxSpiConfig->csnTag, IOCFG_IPU, 1);
|
ioPreinitByTag(rxSpiConfig->csnTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
|
|
||||||
void rxSpiExtiHandler(extiCallbackRec_t* callback)
|
void rxSpiExtiHandler(extiCallbackRec_t* callback)
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
struct rxSpiConfig_s;
|
struct rxSpiConfig_s;
|
||||||
|
|
||||||
extDevice_t *rxSpiGetDevice(void);
|
extDevice_t *rxSpiGetDevice(void);
|
||||||
void rxSpiDevicePreInit(const struct rxSpiConfig_s *rxSpiConfig);
|
void rxSpiDevicePreinit(const struct rxSpiConfig_s *rxSpiConfig);
|
||||||
bool rxSpiDeviceInit(const struct rxSpiConfig_s *rxSpiConfig);
|
bool rxSpiDeviceInit(const struct rxSpiConfig_s *rxSpiConfig);
|
||||||
void rxSpiSetNormalSpeedMhz(uint32_t mhz);
|
void rxSpiSetNormalSpeedMhz(uint32_t mhz);
|
||||||
void rxSpiNormalSpeed();
|
void rxSpiNormalSpeed();
|
||||||
|
|
|
@ -103,10 +103,10 @@ bool sdcard_isInserted(void)
|
||||||
*/
|
*/
|
||||||
sdcardVTable_t *sdcardVTable;
|
sdcardVTable_t *sdcardVTable;
|
||||||
|
|
||||||
void sdcard_preInit(const sdcardConfig_t *config)
|
void sdcard_preinit(const sdcardConfig_t *config)
|
||||||
{
|
{
|
||||||
#ifdef USE_SDCARD_SPI
|
#ifdef USE_SDCARD_SPI
|
||||||
sdcardSpiVTable.sdcard_preInit(config);
|
sdcardSpiVTable.sdcard_preinit(config);
|
||||||
#else
|
#else
|
||||||
UNUSED(config);
|
UNUSED(config);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -57,7 +57,7 @@ typedef void(*sdcard_operationCompleteCallback_c)(sdcardBlockOperation_e operati
|
||||||
|
|
||||||
typedef void(*sdcard_profilerCallback_c)(sdcardBlockOperation_e operation, uint32_t blockIndex, uint32_t duration);
|
typedef void(*sdcard_profilerCallback_c)(sdcardBlockOperation_e operation, uint32_t blockIndex, uint32_t duration);
|
||||||
|
|
||||||
void sdcard_preInit(const sdcardConfig_t *config);
|
void sdcard_preinit(const sdcardConfig_t *config);
|
||||||
void sdcard_init(const sdcardConfig_t *config);
|
void sdcard_init(const sdcardConfig_t *config);
|
||||||
|
|
||||||
bool sdcard_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData);
|
bool sdcard_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData);
|
||||||
|
|
|
@ -109,7 +109,7 @@ STATIC_ASSERT(sizeof(sdcardCSD_t) == 16, sdcard_csd_bitfields_didnt_pack_properl
|
||||||
bool sdcard_isInserted(void);
|
bool sdcard_isInserted(void);
|
||||||
|
|
||||||
typedef struct sdcardVTable_s {
|
typedef struct sdcardVTable_s {
|
||||||
void (*sdcard_preInit)(const sdcardConfig_t *config);
|
void (*sdcard_preinit)(const sdcardConfig_t *config);
|
||||||
void (*sdcard_init)(const sdcardConfig_t *config, const spiPinConfig_t *spiConfig);
|
void (*sdcard_init)(const sdcardConfig_t *config, const spiPinConfig_t *spiConfig);
|
||||||
bool (*sdcard_readBlock)(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData);
|
bool (*sdcard_readBlock)(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData);
|
||||||
sdcardOperationStatus_e (*sdcard_beginWriteBlocks)(uint32_t blockIndex, uint32_t blockCount);
|
sdcardOperationStatus_e (*sdcard_beginWriteBlocks)(uint32_t blockIndex, uint32_t blockCount);
|
||||||
|
|
|
@ -536,9 +536,9 @@ static bool sdcard_checkInitDone(void)
|
||||||
return status == 0x00;
|
return status == 0x00;
|
||||||
}
|
}
|
||||||
|
|
||||||
void sdcardSpi_preInit(const sdcardConfig_t *config)
|
void sdcardSpi_preinit(const sdcardConfig_t *config)
|
||||||
{
|
{
|
||||||
spiPreinitRegister(config->chipSelectTag, IOCFG_IPU, 1);
|
ioPreinitByTag(config->chipSelectTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -1101,7 +1101,7 @@ static void sdcardSpi_setProfilerCallback(sdcard_profilerCallback_c callback)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
sdcardVTable_t sdcardSpiVTable = {
|
sdcardVTable_t sdcardSpiVTable = {
|
||||||
sdcardSpi_preInit,
|
sdcardSpi_preinit,
|
||||||
sdcardSpi_init,
|
sdcardSpi_init,
|
||||||
sdcardSpi_readBlock,
|
sdcardSpi_readBlock,
|
||||||
sdcardSpi_beginWriteBlocks,
|
sdcardSpi_beginWriteBlocks,
|
||||||
|
|
|
@ -180,7 +180,7 @@ void baroPreInit(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_SPI
|
#ifdef USE_SPI
|
||||||
if (barometerConfig()->baro_busType == BUS_TYPE_SPI) {
|
if (barometerConfig()->baro_busType == BUS_TYPE_SPI) {
|
||||||
spiPreinitRegister(barometerConfig()->baro_spi_csn, IOCFG_IPU, 1);
|
ioPreinitByTag(barometerConfig()->baro_spi_csn, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -150,7 +150,7 @@ void compassPreInit(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_SPI
|
#ifdef USE_SPI
|
||||||
if (compassConfig()->mag_busType == BUS_TYPE_SPI) {
|
if (compassConfig()->mag_busType == BUS_TYPE_SPI) {
|
||||||
spiPreinitRegister(compassConfig()->mag_spi_csn, IOCFG_IPU, 1);
|
ioPreinitByTag(compassConfig()->mag_spi_csn, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -498,14 +498,6 @@
|
||||||
#define SYSTEM_HSE_MHZ 0
|
#define SYSTEM_HSE_MHZ 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Number of pins that needs pre-init
|
|
||||||
#ifdef USE_SPI
|
|
||||||
#ifndef SPI_PREINIT_COUNT
|
|
||||||
// 2 x 8 (GYROx2, BARO, MAG, MAX, FLASHx2, RX)
|
|
||||||
#define SPI_PREINIT_COUNT 16
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef USE_BLACKBOX
|
#ifndef USE_BLACKBOX
|
||||||
#undef USE_USB_MSC
|
#undef USE_USB_MSC
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -205,8 +205,6 @@ MCU_COMMON_SRC = \
|
||||||
STM32/usbd_msc_desc.c \
|
STM32/usbd_msc_desc.c \
|
||||||
STM32/camera_control_stm32.c \
|
STM32/camera_control_stm32.c \
|
||||||
drivers/adc.c \
|
drivers/adc.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_pinconfig.c \
|
drivers/serial_uart_pinconfig.c \
|
||||||
|
@ -219,8 +217,6 @@ SPEED_OPTIMISED_SRC += \
|
||||||
SIZE_OPTIMISED_SRC += \
|
SIZE_OPTIMISED_SRC += \
|
||||||
STM32/serial_usb_vcp.c \
|
STM32/serial_usb_vcp.c \
|
||||||
drivers/inverter.c \
|
drivers/inverter.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c
|
drivers/serial_pinconfig.c
|
||||||
|
|
||||||
|
|
|
@ -170,8 +170,6 @@ MCU_COMMON_SRC = \
|
||||||
STM32/transponder_ir_io_hal.c \
|
STM32/transponder_ir_io_hal.c \
|
||||||
STM32/camera_control_stm32.c \
|
STM32/camera_control_stm32.c \
|
||||||
drivers/adc.c \
|
drivers/adc.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_pinconfig.c \
|
drivers/serial_uart_pinconfig.c \
|
||||||
|
@ -199,8 +197,6 @@ SIZE_OPTIMISED_SRC += \
|
||||||
drivers/bus_i2c_timing.c \
|
drivers/bus_i2c_timing.c \
|
||||||
STM32/bus_i2c_hal_init.c \
|
STM32/bus_i2c_hal_init.c \
|
||||||
STM32/serial_usb_vcp.c \
|
STM32/serial_usb_vcp.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_pinconfig.c
|
drivers/serial_uart_pinconfig.c
|
||||||
|
|
|
@ -147,8 +147,6 @@ MCU_COMMON_SRC = \
|
||||||
STM32/transponder_ir_io_hal.c \
|
STM32/transponder_ir_io_hal.c \
|
||||||
STM32/camera_control_stm32.c \
|
STM32/camera_control_stm32.c \
|
||||||
drivers/adc.c \
|
drivers/adc.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_pinconfig.c \
|
drivers/serial_uart_pinconfig.c \
|
||||||
|
@ -172,8 +170,6 @@ SIZE_OPTIMISED_SRC += \
|
||||||
drivers/bus_i2c_timing.c \
|
drivers/bus_i2c_timing.c \
|
||||||
STM32/bus_i2c_hal_init.c \
|
STM32/bus_i2c_hal_init.c \
|
||||||
STM32/serial_usb_vcp.c \
|
STM32/serial_usb_vcp.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_pinconfig.c
|
drivers/serial_uart_pinconfig.c
|
||||||
|
|
|
@ -173,8 +173,6 @@ MCU_COMMON_SRC = \
|
||||||
STM32/camera_control_stm32.c \
|
STM32/camera_control_stm32.c \
|
||||||
STM32/system_stm32h5xx.c \
|
STM32/system_stm32h5xx.c \
|
||||||
drivers/adc.c \
|
drivers/adc.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_pinconfig.c \
|
drivers/serial_uart_pinconfig.c \
|
||||||
|
@ -206,8 +204,6 @@ SIZE_OPTIMISED_SRC += \
|
||||||
drivers/bus_i2c_timing.c \
|
drivers/bus_i2c_timing.c \
|
||||||
STM32/bus_i2c_hal_init.c \
|
STM32/bus_i2c_hal_init.c \
|
||||||
STM32/serial_usb_vcp.c \
|
STM32/serial_usb_vcp.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_pinconfig.c
|
drivers/serial_uart_pinconfig.c
|
||||||
|
|
|
@ -297,8 +297,6 @@ MCU_COMMON_SRC = \
|
||||||
STM32/transponder_ir_io_hal.c \
|
STM32/transponder_ir_io_hal.c \
|
||||||
STM32/camera_control_stm32.c \
|
STM32/camera_control_stm32.c \
|
||||||
drivers/adc.c \
|
drivers/adc.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_pinconfig.c \
|
drivers/serial_uart_pinconfig.c \
|
||||||
|
@ -321,8 +319,6 @@ SIZE_OPTIMISED_SRC += \
|
||||||
drivers/bus_i2c_timing.c \
|
drivers/bus_i2c_timing.c \
|
||||||
STM32/bus_i2c_hal_init.c \
|
STM32/bus_i2c_hal_init.c \
|
||||||
STM32/serial_usb_vcp.c \
|
STM32/serial_usb_vcp.c \
|
||||||
drivers/bus_i2c_config.c \
|
|
||||||
drivers/bus_spi_config.c \
|
|
||||||
drivers/serial_escserial.c \
|
drivers/serial_escserial.c \
|
||||||
drivers/serial_pinconfig.c \
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart_pinconfig.c
|
drivers/serial_uart_pinconfig.c
|
||||||
|
|
|
@ -5,11 +5,15 @@ MCU_COMMON_SRC += \
|
||||||
common/stm32/system.c \
|
common/stm32/system.c \
|
||||||
common/stm32/config_flash.c \
|
common/stm32/config_flash.c \
|
||||||
common/stm32/bus_spi_pinconfig.c \
|
common/stm32/bus_spi_pinconfig.c \
|
||||||
|
drivers/bus_i2c_config.c \
|
||||||
|
drivers/bus_spi_config.c \
|
||||||
common/stm32/bus_spi_hw.c \
|
common/stm32/bus_spi_hw.c \
|
||||||
common/stm32/io_impl.c \
|
common/stm32/io_impl.c \
|
||||||
common/stm32/serial_uart_hw.c
|
common/stm32/serial_uart_hw.c
|
||||||
|
|
||||||
SIZE_OPTIMISED_SRC += \
|
SIZE_OPTIMISED_SRC += \
|
||||||
|
drivers/bus_i2c_config.c \
|
||||||
|
drivers/bus_spi_config.c \
|
||||||
common/stm32/config_flash.c \
|
common/stm32/config_flash.c \
|
||||||
common/stm32/bus_spi_pinconfig.c
|
common/stm32/bus_spi_pinconfig.c
|
||||||
|
|
||||||
|
|
|
@ -163,7 +163,7 @@ void spiSetClkDivisor()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void spiPreinitByIO()
|
void ioPreinitByIO()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -160,7 +160,7 @@ void spiSetClkDivisor()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void spiPreinitByIO(IO_t)
|
void ioPreinitByIO()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -162,7 +162,7 @@ void spiSetClkDivisor()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void spiPreinitByIO()
|
void ioPreinitByIO()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue