Introduce per device pin pre-init
This commit is contained in:
parent
2e81109be1
commit
9ea1428d11
|
@ -242,12 +242,21 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyro
|
|||
}
|
||||
}
|
||||
|
||||
spiPreinitCsByTag(config->csnTag);
|
||||
spiPreinitByTag(config->csnTag);
|
||||
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
void mpuPreInit(const struct gyroDeviceConfig_s *config)
|
||||
{
|
||||
#ifdef USE_SPI_GYRO
|
||||
spiPreinitRegister(config->csnTag, IOCFG_IPU, 1);
|
||||
#else
|
||||
UNUSED(config);
|
||||
#endif
|
||||
}
|
||||
|
||||
void mpuDetect(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
|
||||
{
|
||||
// MPU datasheet specifies 30ms.
|
||||
|
|
|
@ -222,6 +222,7 @@ struct gyroDeviceConfig_s;
|
|||
void mpuGyroInit(struct gyroDev_s *gyro);
|
||||
bool mpuGyroRead(struct gyroDev_s *gyro);
|
||||
bool mpuGyroReadSPI(struct gyroDev_s *gyro);
|
||||
void mpuPreInit(const struct gyroDeviceConfig_s *config);
|
||||
void mpuDetect(struct gyroDev_s *gyro, const struct gyroDeviceConfig_s *config);
|
||||
uint8_t mpuGyroDLPF(struct gyroDev_s *gyro);
|
||||
uint8_t mpuGyroFCHOICE(struct gyroDev_s *gyro);
|
||||
|
|
|
@ -86,7 +86,7 @@ void bmp280BusDeinit(busDevice_t *busdev)
|
|||
{
|
||||
#ifdef USE_BARO_SPI_BMP280
|
||||
if (busdev->bustype == BUSTYPE_SPI) {
|
||||
spiPreinitCsByIO(busdev->busdev_u.spi.csnPin);
|
||||
spiPreinitByIO(busdev->busdev_u.spi.csnPin);
|
||||
}
|
||||
#else
|
||||
UNUSED(busdev);
|
||||
|
|
|
@ -82,7 +82,7 @@ void ms5611BusDeinit(busDevice_t *busdev)
|
|||
{
|
||||
#ifdef USE_BARO_SPI_MS5611
|
||||
if (busdev->bustype == BUSTYPE_SPI) {
|
||||
spiPreinitCsByIO(busdev->busdev_u.spi.csnPin);
|
||||
spiPreinitByIO(busdev->busdev_u.spi.csnPin);
|
||||
}
|
||||
#else
|
||||
UNUSED(busdev);
|
||||
|
|
|
@ -92,13 +92,10 @@ typedef enum SPIDevice {
|
|||
#define SPI_CFG_TO_DEV(x) ((x) - 1)
|
||||
#define SPI_DEV_TO_CFG(x) ((x) + 1)
|
||||
|
||||
// Size of SPI CS pre-initialization tag arrays
|
||||
#define SPI_PREINIT_IPU_COUNT 11
|
||||
#define SPI_PREINIT_OPU_COUNT 2
|
||||
|
||||
void spiPreinitCsByTag(ioTag_t iotag);
|
||||
void spiPreinitCsByIO(IO_t io);
|
||||
void spiPreInit(void);
|
||||
void spiPreinit(void);
|
||||
void spiPreinitRegister(ioTag_t iotag, uint8_t iocfg, uint8_t init);
|
||||
void spiPreinitByIO(IO_t io);
|
||||
void spiPreinitByTag(ioTag_t tag);
|
||||
|
||||
bool spiInit(SPIDevice device);
|
||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor);
|
||||
|
|
|
@ -25,83 +25,101 @@
|
|||
|
||||
#ifdef USE_SPI
|
||||
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/resource.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "pg/bus_spi.h"
|
||||
#include "drivers/flash.h"
|
||||
#include "drivers/max7456.h"
|
||||
#include "drivers/rx/rx_spi.h"
|
||||
#include "drivers/sdcard.h"
|
||||
|
||||
// Bring a pin for possible CS line to pull-up state in preparation for
|
||||
// sequential initialization by relevant drivers.
|
||||
#include "pg/flash.h"
|
||||
#include "pg/max7456.h"
|
||||
#include "pg/rx_spi.h"
|
||||
#include "pg/sdcard.h"
|
||||
|
||||
// There are two versions locally:
|
||||
// spiPreInitCsIPU set the pin to input with pullup (IOCFG_IPU) for safety.
|
||||
// spiPreInitCsOPU actually drive the pin for digital hi.
|
||||
//
|
||||
// The later is required for SPI slave devices on some targets, interfaced through level shifters, such as Kakute F4.
|
||||
//
|
||||
// Two ioTag_t array PGs, spiPreinitIPUConfig and spiPreinitOPUConfig are used to
|
||||
// determine pin to be IPU or OPU.
|
||||
// The IPU array is initialized with a hard coded initialization array,
|
||||
// while the OPU array is initialized from target dependent config.c.
|
||||
// With generic targets, both arrays are setup with resource commands.
|
||||
#include "sensors/initialisation.h"
|
||||
|
||||
static void spiPreInitCsIPU(ioTag_t iotag, int index)
|
||||
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)
|
||||
{
|
||||
IO_t io = IOGetByTag(iotag);
|
||||
if (io) {
|
||||
IOInit(io, OWNER_SPI_PREINIT_IPU, index);
|
||||
IOConfigGPIO(io, IOCFG_IPU);
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
static void spiPreInitCsOPU(ioTag_t iotag, int index)
|
||||
void spiPreinit(void)
|
||||
{
|
||||
IO_t io = IOGetByTag(iotag);
|
||||
if (io) {
|
||||
IOInit(io, OWNER_SPI_PREINIT_OPU, index);
|
||||
IOConfigGPIO(io, IOCFG_OUT_PP);
|
||||
IOHi(io);
|
||||
}
|
||||
}
|
||||
|
||||
void spiPreInit(void)
|
||||
{
|
||||
for (int i = 0 ; i < SPI_PREINIT_IPU_COUNT ; i++) {
|
||||
if (spiPreinitIPUConfig(i)->csnTag) {
|
||||
spiPreInitCsIPU(spiPreinitIPUConfig(i)->csnTag, i);
|
||||
}
|
||||
}
|
||||
|
||||
for (int i = 0 ; i < SPI_PREINIT_OPU_COUNT ; i++) {
|
||||
if (spiPreinitOPUConfig(i)->csnTag) {
|
||||
spiPreInitCsOPU(spiPreinitOPUConfig(i)->csnTag, i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Back to pre-init state
|
||||
|
||||
void spiPreinitCsByIO(IO_t io)
|
||||
{
|
||||
for (int i = 0 ; i < SPI_PREINIT_IPU_COUNT ; i++) {
|
||||
if (IOGetByTag(spiPreinitIPUConfig(i)->csnTag) == io) {
|
||||
spiPreInitCsIPU(spiPreinitIPUConfig(i)->csnTag, i);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
for (int i = 0 ; i < SPI_PREINIT_OPU_COUNT ; i++) {
|
||||
if (IOGetByTag(spiPreinitOPUConfig(i)->csnTag) == io) {
|
||||
spiPreInitCsOPU(spiPreinitOPUConfig(i)->csnTag, i);
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void spiPreinitCsByTag(ioTag_t iotag)
|
||||
{
|
||||
spiPreinitCsByIO(IOGetByTag(iotag));
|
||||
}
|
||||
sensorsPreInit();
|
||||
|
||||
#ifdef USE_SDCARD_SPI
|
||||
sdcard_preInit(sdcardConfig());
|
||||
#endif
|
||||
|
||||
#if defined(RTC6705_CS_PIN) && !defined(USE_VTX_RTC6705_SOFTSPI) // RTC6705 soft SPI initialisation handled elsewhere.
|
||||
// XXX Waiting for "RTC6705 cleanup #7114" to be done
|
||||
#endif
|
||||
|
||||
#ifdef USE_FLASH_CHIP
|
||||
flashPreInit(flashConfig());
|
||||
#endif
|
||||
|
||||
#if defined(USE_RX_SPI) && !defined(USE_RX_SOFTSPI)
|
||||
rxSpiDevicePreInit(rxSpiConfig());
|
||||
#endif
|
||||
|
||||
#ifdef USE_MAX7456
|
||||
max7456PreInit(max7456Config());
|
||||
#endif
|
||||
|
||||
for (int i = 0; i < spiPreinitCount; i++) {
|
||||
spiPreinitPin(&spiPreinitArray[i], i);
|
||||
}
|
||||
}
|
||||
|
||||
void spiPreinitByIO(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
|
||||
|
|
|
@ -410,7 +410,7 @@ void ak8963BusDeInit(const busDevice_t *busdev)
|
|||
|
||||
#ifdef USE_MAG_SPI_AK8963
|
||||
case BUSTYPE_SPI:
|
||||
spiPreinitCsByIO(busdev->busdev_u.spi.csnPin);
|
||||
spiPreinitByIO(busdev->busdev_u.spi.csnPin);
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -40,6 +40,11 @@ static busDevice_t *busdev;
|
|||
|
||||
static flashDevice_t flashDevice;
|
||||
|
||||
void flashPreInit(const flashConfig_t *flashConfig)
|
||||
{
|
||||
spiPreinitRegister(flashConfig->csTag, IOCFG_IPU, 1);
|
||||
}
|
||||
|
||||
// Read chip identification and send it to device detect
|
||||
|
||||
bool flashInit(const flashConfig_t *flashConfig)
|
||||
|
@ -99,7 +104,7 @@ bool flashInit(const flashConfig_t *flashConfig)
|
|||
}
|
||||
#endif
|
||||
|
||||
spiPreinitCsByTag(flashConfig->csTag);
|
||||
spiPreinitByTag(flashConfig->csTag);
|
||||
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -45,6 +45,7 @@ typedef struct flashGeometry_s {
|
|||
flashType_e flashType;
|
||||
} flashGeometry_t;
|
||||
|
||||
void flashPreInit(const flashConfig_t *flashConfig);
|
||||
bool flashInit(const flashConfig_t *flashConfig);
|
||||
|
||||
bool flashIsReady(void);
|
||||
|
|
|
@ -279,7 +279,7 @@ bool IOIsFreeOrPreinit(IO_t io)
|
|||
{
|
||||
resourceOwner_e owner = IOGetOwner(io);
|
||||
|
||||
if (owner == OWNER_FREE || owner == OWNER_SPI_PREINIT_IPU || owner == OWNER_SPI_PREINIT_OPU) {
|
||||
if (owner == OWNER_FREE || owner == OWNER_PREINIT) {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -407,6 +407,10 @@ void max7456ReInit(void)
|
|||
}
|
||||
}
|
||||
|
||||
void max7456PreInit(const max7456Config_t *max7456Config)
|
||||
{
|
||||
spiPreinitRegister(max7456Config->csTag, max7456Config->preInitOPU ? IOCFG_OUT_PP : IOCFG_IPU, 1);
|
||||
}
|
||||
|
||||
// Here we init only CS and try to init MAX for first time.
|
||||
// Also detect device type (MAX v.s. AT)
|
||||
|
|
|
@ -31,6 +31,7 @@ extern uint16_t maxScreenSize;
|
|||
struct vcdProfile_s;
|
||||
void max7456HardwareReset(void);
|
||||
struct max7456Config_s;
|
||||
void max7456PreInit(const struct max7456Config_s *max7456Config);
|
||||
bool max7456Init(const struct max7456Config_s *max7456Config, const struct vcdProfile_s *vcdProfile, bool cpuOverclock);
|
||||
void max7456Invert(bool invert);
|
||||
void max7456Brightness(uint8_t black, uint8_t white);
|
||||
|
|
|
@ -74,9 +74,8 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
|||
"RX_SPI",
|
||||
"PINIO",
|
||||
"USB_MSC_PIN",
|
||||
"SPI_PREINIT_IPU",
|
||||
"SPI_PREINIT_OPU",
|
||||
"MCO",
|
||||
"RX_SPI_BIND",
|
||||
"RX_SPI_LED",
|
||||
"PREINIT",
|
||||
};
|
||||
|
|
|
@ -74,11 +74,10 @@ typedef enum {
|
|||
OWNER_RX_SPI,
|
||||
OWNER_PINIO,
|
||||
OWNER_USB_MSC_PIN,
|
||||
OWNER_SPI_PREINIT_IPU,
|
||||
OWNER_SPI_PREINIT_OPU,
|
||||
OWNER_MCO,
|
||||
OWNER_RX_SPI_BIND,
|
||||
OWNER_RX_SPI_LED,
|
||||
OWNER_PREINIT,
|
||||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_e;
|
||||
|
||||
|
|
|
@ -47,6 +47,11 @@
|
|||
static busDevice_t rxSpiDevice;
|
||||
static busDevice_t *busdev = &rxSpiDevice;
|
||||
|
||||
void rxSpiDevicePreInit(const rxSpiConfig_t *rxSpiConfig)
|
||||
{
|
||||
spiPreinitRegister(rxSpiConfig->csnTag, IOCFG_IPU, 1);
|
||||
}
|
||||
|
||||
bool rxSpiDeviceInit(const rxSpiConfig_t *rxSpiConfig)
|
||||
{
|
||||
if (!rxSpiConfig->spibus) {
|
||||
|
|
|
@ -26,6 +26,7 @@
|
|||
|
||||
struct rxSpiConfig_s;
|
||||
|
||||
void rxSpiDevicePreInit(const struct rxSpiConfig_s *rxSpiConfig);
|
||||
bool rxSpiDeviceInit(const struct rxSpiConfig_s *rxSpiConfig);
|
||||
uint8_t rxSpiTransferByte(uint8_t data);
|
||||
void rxSpiWriteByte(uint8_t data);
|
||||
|
|
|
@ -101,6 +101,15 @@ bool sdcard_isInserted(void)
|
|||
*/
|
||||
sdcardVTable_t *sdcardVTable;
|
||||
|
||||
void sdcard_preInit(const sdcardConfig_t *config)
|
||||
{
|
||||
#ifdef USE_SDCARD_SPI
|
||||
sdcardSpiVTable.sdcard_preInit(config);
|
||||
#else
|
||||
UNUSED(config);
|
||||
#endif
|
||||
}
|
||||
|
||||
void sdcard_init(const sdcardConfig_t *config)
|
||||
{
|
||||
switch (config->mode) {
|
||||
|
|
|
@ -57,6 +57,7 @@ typedef void(*sdcard_operationCompleteCallback_c)(sdcardBlockOperation_e operati
|
|||
|
||||
typedef void(*sdcard_profilerCallback_c)(sdcardBlockOperation_e operation, uint32_t blockIndex, uint32_t duration);
|
||||
|
||||
void sdcard_preInit(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);
|
||||
|
|
|
@ -112,6 +112,7 @@ void sdcardInsertionDetectDeinit(void);
|
|||
bool sdcard_isInserted(void);
|
||||
|
||||
typedef struct sdcardVTable_s {
|
||||
void (*sdcard_preInit)(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);
|
||||
sdcardOperationStatus_e (*sdcard_beginWriteBlocks)(uint32_t blockIndex, uint32_t blockCount);
|
||||
|
|
|
@ -631,6 +631,7 @@ static void sdcardSdio_setProfilerCallback(sdcard_profilerCallback_c callback)
|
|||
#endif
|
||||
|
||||
sdcardVTable_t sdcardSdioVTable = {
|
||||
NULL,
|
||||
sdcardSdio_init,
|
||||
sdcardSdio_readBlock,
|
||||
sdcardSdio_beginWriteBlocks,
|
||||
|
|
|
@ -465,6 +465,11 @@ static bool sdcard_checkInitDone(void)
|
|||
return status == 0x00;
|
||||
}
|
||||
|
||||
void sdcardSpi_preInit(const sdcardConfig_t *config)
|
||||
{
|
||||
spiPreinitRegister(config->chipSelectTag, IOCFG_IPU, 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Begin the initialization process for the SD card. This must be called first before any other sdcard_ routine.
|
||||
*/
|
||||
|
@ -1075,6 +1080,7 @@ static void sdcardSpi_setProfilerCallback(sdcard_profilerCallback_c callback)
|
|||
#endif
|
||||
|
||||
sdcardVTable_t sdcardSpiVTable = {
|
||||
sdcardSpi_preInit,
|
||||
sdcardSpi_init,
|
||||
sdcardSpi_readBlock,
|
||||
sdcardSpi_beginWriteBlocks,
|
||||
|
|
|
@ -393,13 +393,13 @@ void init(void)
|
|||
|
||||
#ifdef TARGET_BUS_INIT
|
||||
targetBusInit();
|
||||
|
||||
#else
|
||||
|
||||
#ifdef USE_SPI
|
||||
spiPinConfigure(spiPinConfig(0));
|
||||
|
||||
// Initialize CS lines and keep them high
|
||||
spiPreInit();
|
||||
spiPreinit();
|
||||
|
||||
#ifdef USE_SPI_DEVICE_1
|
||||
spiInit(SPIDEV_1);
|
||||
|
|
|
@ -3934,10 +3934,6 @@ const cliResourceValue_t resourceTable[] = {
|
|||
#ifdef USE_MAX7456
|
||||
DEFS( OWNER_OSD_CS, PG_MAX7456_CONFIG, max7456Config_t, csTag ),
|
||||
#endif
|
||||
#ifdef USE_SPI
|
||||
DEFA( OWNER_SPI_PREINIT_IPU, PG_SPI_PREINIT_IPU_CONFIG, spiCs_t, csnTag, SPI_PREINIT_IPU_COUNT ),
|
||||
DEFA( OWNER_SPI_PREINIT_OPU, PG_SPI_PREINIT_OPU_CONFIG, spiCs_t, csnTag, SPI_PREINIT_OPU_COUNT ),
|
||||
#endif
|
||||
#ifdef USE_RX_SPI
|
||||
DEFS( OWNER_RX_SPI_CS, PG_RX_SPI_CONFIG, rxSpiConfig_t, csnTag ),
|
||||
DEFS( OWNER_RX_SPI_BIND, PG_RX_SPI_CONFIG, rxSpiConfig_t, bindIoTag ),
|
||||
|
|
|
@ -1154,6 +1154,7 @@ const clivalue_t valueTable[] = {
|
|||
#ifdef USE_MAX7456
|
||||
{ "max7456_clock", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MAX7456_CLOCK }, PG_MAX7456_CONFIG, offsetof(max7456Config_t, clockConfig) },
|
||||
{ "max7456_spi_bus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, SPIDEV_COUNT }, PG_MAX7456_CONFIG, offsetof(max7456Config_t, spiDevice) },
|
||||
{ "max7456_preinit_opu", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MAX7456_CONFIG, offsetof(max7456Config_t, preInitOPU) },
|
||||
#endif
|
||||
|
||||
// PG_DISPLAY_PORT_MSP_CONFIG
|
||||
|
|
|
@ -62,69 +62,4 @@ void pgResetFn_spiPinConfig(spiPinConfig_t *spiPinConfig)
|
|||
spiPinConfig[defconf->device].ioTagMosi = defconf->mosi;
|
||||
}
|
||||
}
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(spiCs_t, SPI_PREINIT_IPU_COUNT, spiPreinitIPUConfig, PG_SPI_PREINIT_IPU_CONFIG, 0);
|
||||
PG_REGISTER_ARRAY(spiCs_t, SPI_PREINIT_OPU_COUNT, spiPreinitOPUConfig, PG_SPI_PREINIT_OPU_CONFIG, 0);
|
||||
|
||||
// Initialization values for input pull-up are listed here.
|
||||
// Explicit output with pull-up should handled in target dependent config.c.
|
||||
// Generic target will be specifying both values by resource commands.
|
||||
|
||||
ioTag_t preinitIPUList[SPI_PREINIT_IPU_COUNT] = {
|
||||
#ifdef GYRO_1_CS_PIN
|
||||
IO_TAG(GYRO_1_CS_PIN),
|
||||
#endif
|
||||
#ifdef GYRO_2_CS_PIN
|
||||
IO_TAG(GYRO_2_CS_PIN),
|
||||
#endif
|
||||
#ifdef L3GD20_CS_PIN
|
||||
IO_TAG(L3GD20_CS_PIN),
|
||||
#endif
|
||||
#ifdef SDCARD_SPI_CS_PIN
|
||||
IO_TAG(SDCARD_SPI_CS_PIN),
|
||||
#endif
|
||||
#ifdef BMP280_CS_PIN
|
||||
IO_TAG(BMP280_CS_PIN),
|
||||
#endif
|
||||
#ifdef MS5611_CS_PIN
|
||||
IO_TAG(MS5611_CS_PIN),
|
||||
#endif
|
||||
#ifdef LPS_CS_PIN
|
||||
IO_TAG(LPS_CS_PIN),
|
||||
#endif
|
||||
#ifdef HMC5883_CS_PIN
|
||||
IO_TAG(HMC5883_CS_PIN),
|
||||
#endif
|
||||
#ifdef AK8963_CS_PIN
|
||||
IO_TAG(AK8963_CS_PIN),
|
||||
#endif
|
||||
#if defined(RTC6705_CS_PIN) && !defined(USE_VTX_RTC6705_SOFTSPI) // RTC6705 soft SPI initialisation handled elsewhere.
|
||||
IO_TAG(RTC6705_CS_PIN),
|
||||
#endif
|
||||
#ifdef FLASH_CS_PIN
|
||||
IO_TAG(FLASH_CS_PIN),
|
||||
#endif
|
||||
#if defined(USE_RX_SPI) && !defined(USE_RX_SOFTSPI)
|
||||
IO_TAG(RX_NSS_PIN),
|
||||
#endif
|
||||
#if defined(MAX7456_SPI_CS_PIN)
|
||||
IO_TAG(MAX7456_SPI_CS_PIN),
|
||||
#endif
|
||||
IO_TAG(NONE)
|
||||
};
|
||||
|
||||
void pgResetFn_spiPreinitIPUConfig(spiCs_t *config)
|
||||
{
|
||||
int puPins = 0;
|
||||
|
||||
for (int i = 0 ; i < SPI_PREINIT_IPU_COUNT ; i++) {
|
||||
for (int j = 0 ; j < i ; j++) {
|
||||
if (config[j].csnTag == preinitIPUList[i]) {
|
||||
goto next;
|
||||
}
|
||||
}
|
||||
config[puPins++].csnTag = preinitIPUList[i];
|
||||
next:;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -32,12 +32,3 @@ typedef struct spiPinConfig_s {
|
|||
} spiPinConfig_t;
|
||||
|
||||
PG_DECLARE_ARRAY(spiPinConfig_t, SPIDEV_COUNT, spiPinConfig);
|
||||
|
||||
// Place holder for CS pins for pre-initialization
|
||||
|
||||
typedef struct spiCs_s {
|
||||
ioTag_t csnTag;
|
||||
} spiCs_t;
|
||||
|
||||
PG_DECLARE_ARRAY(spiCs_t, SPI_PREINIT_IPU_COUNT, spiPreinitIPUConfig);
|
||||
PG_DECLARE_ARRAY(spiCs_t, SPI_PREINIT_OPU_COUNT, spiPreinitOPUConfig);
|
||||
|
|
|
@ -37,5 +37,6 @@ void pgResetFn_max7456Config(max7456Config_t *config)
|
|||
config->clockConfig = MAX7456_CLOCK_CONFIG_DEFAULT;
|
||||
config->csTag = IO_TAG(MAX7456_SPI_CS_PIN);
|
||||
config->spiDevice = SPI_DEV_TO_CFG(spiDeviceByInstance(MAX7456_SPI_INSTANCE));
|
||||
config->preInitOPU = false;
|
||||
}
|
||||
#endif // USE_MAX7456
|
||||
|
|
|
@ -27,6 +27,7 @@ typedef struct max7456Config_s {
|
|||
uint8_t clockConfig; // SPI clock based on device type and overclock state (MAX7456_CLOCK_CONFIG_xxxx)
|
||||
ioTag_t csTag;
|
||||
uint8_t spiDevice;
|
||||
bool preInitOPU;
|
||||
} max7456Config_t;
|
||||
|
||||
// clockConfig values
|
||||
|
|
|
@ -146,6 +146,15 @@ static int32_t baroGroundAltitude = 0;
|
|||
static int32_t baroGroundPressure = 8*101325;
|
||||
static uint32_t baroPressureSum = 0;
|
||||
|
||||
void baroPreInit(void)
|
||||
{
|
||||
#ifdef USE_SPI
|
||||
if (barometerConfig()->baro_bustype == BUSTYPE_SPI) {
|
||||
spiPreinitRegister(barometerConfig()->baro_spi_csn, IOCFG_IPU, 1);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
||||
{
|
||||
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
|
||||
|
|
|
@ -59,6 +59,7 @@ typedef struct baro_s {
|
|||
|
||||
extern baro_t baro;
|
||||
|
||||
void baroPreInit(void);
|
||||
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse);
|
||||
bool isBaroCalibrationComplete(void);
|
||||
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
||||
|
|
|
@ -116,6 +116,15 @@ void pgResetFn_compassConfig(compassConfig_t *compassConfig)
|
|||
static int16_t magADCRaw[XYZ_AXIS_COUNT];
|
||||
static uint8_t magInit = 0;
|
||||
|
||||
void compassPreInit(void)
|
||||
{
|
||||
#ifdef USE_SPI
|
||||
if (compassConfig()->mag_bustype == BUSTYPE_SPI) {
|
||||
spiPreinitRegister(compassConfig()->mag_spi_csn, IOCFG_IPU, 1);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if !defined(SIMULATOR_BUILD)
|
||||
bool compassDetect(magDev_t *dev)
|
||||
{
|
||||
|
|
|
@ -64,3 +64,4 @@ PG_DECLARE(compassConfig_t, compassConfig);
|
|||
bool compassIsHealthy(void);
|
||||
void compassUpdate(timeUs_t currentTime);
|
||||
bool compassInit(void);
|
||||
void compassPreInit(void);
|
||||
|
|
|
@ -401,6 +401,16 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
|
|||
return gyroHardware;
|
||||
}
|
||||
|
||||
static void gyroPreInitSensor(const gyroDeviceConfig_t *config)
|
||||
{
|
||||
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) \
|
||||
|| defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689)
|
||||
mpuPreInit(config);
|
||||
#else
|
||||
UNUSED(config);
|
||||
#endif
|
||||
}
|
||||
|
||||
static bool gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
|
||||
{
|
||||
gyroSensor->gyroDev.gyro_high_fsr = gyroConfig()->gyro_high_fsr;
|
||||
|
@ -483,6 +493,18 @@ static bool gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *c
|
|||
return true;
|
||||
}
|
||||
|
||||
void gyroPreInit(void)
|
||||
{
|
||||
if (gyroToUse == GYRO_CONFIG_USE_GYRO_1 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
|
||||
gyroPreInitSensor(gyroDeviceConfig(0));
|
||||
}
|
||||
#ifdef USE_MULTI_GYRO
|
||||
if (gyroToUse == GYRO_CONFIG_USE_GYRO_2 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
|
||||
gyroPreInitSensor(gyroDeviceConfig(1));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
bool gyroInit(void)
|
||||
{
|
||||
#ifdef USE_GYRO_OVERFLOW_CHECK
|
||||
|
@ -711,7 +733,6 @@ static void gyroInitFilterDynamicNotch(gyroSensor_t *gyroSensor)
|
|||
}
|
||||
#endif
|
||||
|
||||
|
||||
static void gyroInitSensorFilters(gyroSensor_t *gyroSensor)
|
||||
{
|
||||
#if defined(USE_GYRO_SLEW_LIMITER)
|
||||
|
|
|
@ -108,6 +108,7 @@ typedef struct gyroConfig_s {
|
|||
|
||||
PG_DECLARE(gyroConfig_t, gyroConfig);
|
||||
|
||||
void gyroPreInit(void);
|
||||
bool gyroInit(void);
|
||||
|
||||
void gyroInitFilters(void);
|
||||
|
|
|
@ -46,6 +46,19 @@
|
|||
uint8_t requestedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE };
|
||||
uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE };
|
||||
|
||||
void sensorsPreInit(void)
|
||||
{
|
||||
gyroPreInit();
|
||||
|
||||
#ifdef USE_MAG
|
||||
compassPreInit();
|
||||
#endif
|
||||
|
||||
#ifdef USE_BARO
|
||||
baroPreInit();
|
||||
#endif
|
||||
}
|
||||
|
||||
bool sensorsAutodetect(void)
|
||||
{
|
||||
|
||||
|
|
|
@ -20,4 +20,5 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void sensorsPreInit(void);
|
||||
bool sensorsAutodetect(void);
|
||||
|
|
|
@ -30,13 +30,11 @@
|
|||
#include "pg/bus_i2c.h"
|
||||
#include "pg/bus_spi.h"
|
||||
|
||||
extern void spiPreInit(void);
|
||||
|
||||
void targetBusInit(void)
|
||||
{
|
||||
if (hardwareRevision == AFF3_REV_2) {
|
||||
spiPinConfigure(spiPinConfig(0));
|
||||
spiPreInit();
|
||||
spiPreinit();
|
||||
spiInit(SPIDEV_3);
|
||||
}
|
||||
i2cHardwareConfigure(i2cConfig(0));
|
||||
|
|
|
@ -29,14 +29,11 @@
|
|||
#include "pg/bus_i2c.h"
|
||||
#include "pg/bus_spi.h"
|
||||
|
||||
|
||||
extern void spiPreInit(void); // XXX In fc/init.c
|
||||
|
||||
void targetBusInit(void)
|
||||
{
|
||||
#if defined(USE_SPI) && defined(USE_SPI_DEVICE_1)
|
||||
spiPinConfigure(spiPinConfig(0));
|
||||
spiPreInit();
|
||||
spiPreinit();
|
||||
spiInit(SPIDEV_1);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -27,8 +27,7 @@
|
|||
|
||||
#include "config_helper.h"
|
||||
#include "io/serial.h"
|
||||
#include "pg/bus_spi.h"
|
||||
#include "rx/rx.h"
|
||||
#include "pg/max7456.h"
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#define TELEMETRY_UART SERIAL_PORT_USART1
|
||||
|
@ -43,22 +42,7 @@ void targetConfiguration(void)
|
|||
telemetryConfigMutable()->halfDuplex = 0;
|
||||
telemetryConfigMutable()->telemetry_inverted = true;
|
||||
|
||||
// Register MAX7456 CS pin as OPU
|
||||
|
||||
// Invalidate IPU entry first
|
||||
for (int i = 0 ; i < SPI_PREINIT_IPU_COUNT ; i++) {
|
||||
if (spiPreinitIPUConfig(i)->csnTag == IO_TAG(MAX7456_SPI_CS_PIN)) {
|
||||
spiPreinitIPUConfigMutable(i)->csnTag = IO_TAG(NONE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Add as OPU entry
|
||||
for (int i = 0 ; i < SPI_PREINIT_OPU_COUNT ; i++) {
|
||||
if (spiPreinitOPUConfig(i)->csnTag == IO_TAG(NONE)) {
|
||||
spiPreinitOPUConfigMutable(i)->csnTag = IO_TAG(MAX7456_SPI_CS_PIN);
|
||||
break;
|
||||
}
|
||||
}
|
||||
// Mark MAX7456 CS pin as OPU
|
||||
max7456ConfigMutable()->preInitOPU = true;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -30,14 +30,11 @@
|
|||
#include "pg/bus_i2c.h"
|
||||
#include "pg/bus_spi.h"
|
||||
|
||||
|
||||
extern void spiPreInit(void); // XXX In fc/init.c
|
||||
|
||||
void targetBusInit(void)
|
||||
{
|
||||
#ifdef USE_SPI
|
||||
spiPinConfigure(spiPinConfig(0));
|
||||
spiPreInit();
|
||||
spiPreinit();
|
||||
#ifdef USE_SPI_DEVICE_2
|
||||
spiInit(SPIDEV_2);
|
||||
#endif
|
||||
|
|
|
@ -33,10 +33,6 @@ resource SPI_SCK 3 C10
|
|||
resource SPI_MISO 3 C11
|
||||
resource SPI_MOSI 3 C12
|
||||
|
||||
# SPI CS pins to pre-initialize
|
||||
resource SPI_PREINIT_IPU 1 C04 // MPU6500
|
||||
resource SPI_PREINIT_IPU 2 A15 // SDCARD
|
||||
|
||||
# Acc/gyro
|
||||
resource gyro_cs 1 C4
|
||||
resource GYRO_EXTI 1 B15
|
||||
|
|
|
@ -215,3 +215,10 @@
|
|||
#define SYSTEM_HSE_VALUE (HSE_VALUE/1000000U)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Number of pins that needs pre-init
|
||||
#ifdef USE_SPI
|
||||
#ifndef SPI_PREINIT_COUNT
|
||||
#define SPI_PREINIT_COUNT 16 // 2 x 8 (GYROx2, BARO, MAG, MAX, FLASHx2, RX)
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -150,7 +150,7 @@ bool busWriteRegister(const busDevice_t*, uint8_t, uint8_t) {return true;}
|
|||
void spiSetDivisor() {
|
||||
}
|
||||
|
||||
void spiPreinitCsByIO() {
|
||||
void spiPreinitByIO() {
|
||||
}
|
||||
|
||||
void IOConfigGPIO() {
|
||||
|
|
|
@ -152,7 +152,7 @@ bool busWriteRegister(const busDevice_t*, uint8_t, uint8_t) {return true;}
|
|||
void spiSetDivisor() {
|
||||
}
|
||||
|
||||
void spiPreinitCsByIO() {
|
||||
void spiPreinitByIO() {
|
||||
}
|
||||
|
||||
void IOConfigGPIO() {
|
||||
|
|
Loading…
Reference in New Issue