mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Merge pull request #3399 from martinbudden/bf_spi_handle_cache
Cache SPI handle to improve performance for F7 boards
This commit is contained in:
commit
43c46d3845
6 changed files with 59 additions and 27 deletions
|
@ -234,7 +234,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
|
|||
{
|
||||
UNUSED(gyro); // since there are FCs which have gyro on I2C but other devices on SPI
|
||||
#ifdef USE_GYRO_SPI_MPU6000
|
||||
gyro->bus.spi.instance = MPU6000_SPI_INSTANCE;
|
||||
spiBusSetInstance(&gyro->bus, MPU6000_SPI_INSTANCE);
|
||||
#ifdef MPU6000_CS_PIN
|
||||
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU6000_CS_PIN)) : gyro->bus.spi.csnPin;
|
||||
#endif
|
||||
|
@ -248,7 +248,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
|
|||
#endif
|
||||
|
||||
#ifdef USE_GYRO_SPI_MPU6500
|
||||
gyro->bus.spi.instance = MPU6500_SPI_INSTANCE;
|
||||
spiBusSetInstance(&gyro->bus, MPU6500_SPI_INSTANCE);
|
||||
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU6500_CS_PIN)) : gyro->bus.spi.csnPin;
|
||||
const uint8_t mpu6500Sensor = mpu6500SpiDetect(&gyro->bus);
|
||||
// some targets using MPU_9250_SPI, ICM_20608_SPI or ICM_20602_SPI state sensor is MPU_65xx_SPI
|
||||
|
@ -262,7 +262,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
|
|||
#endif
|
||||
|
||||
#ifdef USE_GYRO_SPI_MPU9250
|
||||
gyro->bus.spi.instance = MPU9250_SPI_INSTANCE;
|
||||
spiBusSetInstance(&gyro->bus, MPU9250_SPI_INSTANCE);
|
||||
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU9250_CS_PIN)) : gyro->bus.spi.csnPin;
|
||||
if (mpu9250SpiDetect(&gyro->bus)) {
|
||||
gyro->mpuDetectionResult.sensor = MPU_9250_SPI;
|
||||
|
@ -275,7 +275,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
|
|||
#endif
|
||||
|
||||
#ifdef USE_GYRO_SPI_ICM20689
|
||||
gyro->bus.spi.instance = ICM20689_SPI_INSTANCE;
|
||||
spiBusSetInstance(&gyro->bus, ICM20689_SPI_INSTANCE);
|
||||
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(ICM20689_CS_PIN)) : gyro->bus.spi.csnPin;
|
||||
if (icm20689SpiDetect(&gyro->bus)) {
|
||||
gyro->mpuDetectionResult.sensor = ICM_20689_SPI;
|
||||
|
@ -287,7 +287,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
|
|||
#endif
|
||||
|
||||
#ifdef USE_ACCGYRO_BMI160
|
||||
gyro->bus.spi.instance = BMI160_SPI_INSTANCE;
|
||||
spiBusSetInstance(&gyro->bus, BMI160_SPI_INSTANCE);
|
||||
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(BMI160_CS_PIN)) : gyro->bus.spi.csnPin;
|
||||
if (bmi160Detect(&gyro->bus)) {
|
||||
gyro->mpuDetectionResult.sensor = BMI_160_SPI;
|
||||
|
|
|
@ -25,6 +25,9 @@
|
|||
typedef union busDevice_u {
|
||||
struct deviceSpi_s {
|
||||
SPI_TypeDef *instance;
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
SPI_HandleTypeDef* handle; // cached here for efficiency
|
||||
#endif
|
||||
IO_t csnPin;
|
||||
} spi;
|
||||
struct deviceI2C_s {
|
||||
|
|
|
@ -383,3 +383,8 @@ uint8_t spiReadRegister(const busDevice_t *bus, uint8_t reg)
|
|||
|
||||
return data;
|
||||
}
|
||||
|
||||
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance)
|
||||
{
|
||||
bus->spi.instance = instance;
|
||||
}
|
||||
|
|
|
@ -106,3 +106,4 @@ DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channe
|
|||
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);
|
||||
uint8_t spiReadRegister(const busDevice_t *bus, uint8_t reg);
|
||||
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance);
|
||||
|
|
|
@ -68,6 +68,8 @@
|
|||
#define SPI4_NSS_PIN NONE
|
||||
#endif
|
||||
|
||||
#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 },
|
||||
|
@ -239,13 +241,6 @@ uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance)
|
|||
return spiHardwareMap[device].errorCount;
|
||||
}
|
||||
|
||||
// return uint8_t value or -1 when failure
|
||||
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in)
|
||||
{
|
||||
spiTransfer(instance, &in, &in, 1);
|
||||
return in;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return true if the bus is currently in the middle of a transmission.
|
||||
*/
|
||||
|
@ -263,8 +258,6 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
|||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
HAL_StatusTypeDef status;
|
||||
|
||||
#define SPI_DEFAULT_TIMEOUT 10
|
||||
|
||||
if(!out) // Tx only
|
||||
{
|
||||
status = HAL_SPI_Transmit(&spiHardwareMap[device].hspi, (uint8_t *)in, len, SPI_DEFAULT_TIMEOUT);
|
||||
|
@ -284,6 +277,31 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
|||
return true;
|
||||
}
|
||||
|
||||
static bool spiBusReadBuffer(const busDevice_t *bus, uint8_t *out, int len)
|
||||
{
|
||||
const HAL_StatusTypeDef status = HAL_SPI_Receive(bus->spi.handle, out, len, SPI_DEFAULT_TIMEOUT);
|
||||
if (status != HAL_OK) {
|
||||
spiTimeoutUserCallback(bus->spi.instance);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
// return uint8_t value or -1 when failure
|
||||
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in)
|
||||
{
|
||||
spiTransfer(instance, &in, &in, 1);
|
||||
return in;
|
||||
}
|
||||
|
||||
// return uint8_t value or -1 when failure
|
||||
static uint8_t spiBusTransferByte(const busDevice_t *bus, uint8_t in)
|
||||
{
|
||||
const HAL_StatusTypeDef status = HAL_SPI_TransmitReceive(bus->spi.handle, &in, &in, 1, SPI_DEFAULT_TIMEOUT);
|
||||
if (status != HAL_OK) {
|
||||
spiTimeoutUserCallback(bus->spi.instance);
|
||||
}
|
||||
return in;
|
||||
}
|
||||
|
||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
||||
{
|
||||
|
@ -349,8 +367,8 @@ void spiResetErrorCounter(SPI_TypeDef *instance)
|
|||
bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
|
||||
{
|
||||
IOLo(bus->spi.csnPin);
|
||||
spiTransferByte(bus->spi.instance, reg);
|
||||
spiTransferByte(bus->spi.instance, data);
|
||||
spiBusTransferByte(bus, reg);
|
||||
spiBusTransferByte(bus, data);
|
||||
IOHi(bus->spi.csnPin);
|
||||
|
||||
return true;
|
||||
|
@ -359,8 +377,8 @@ 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)
|
||||
{
|
||||
IOLo(bus->spi.csnPin);
|
||||
spiTransferByte(bus->spi.instance, reg | 0x80); // read transaction
|
||||
spiTransfer(bus->spi.instance, data, NULL, length);
|
||||
spiBusTransferByte(bus, reg | 0x80); // read transaction
|
||||
spiBusReadBuffer(bus, data, length);
|
||||
IOHi(bus->spi.csnPin);
|
||||
|
||||
return true;
|
||||
|
@ -370,13 +388,19 @@ uint8_t spiReadRegister(const busDevice_t *bus, uint8_t reg)
|
|||
{
|
||||
uint8_t data;
|
||||
IOLo(bus->spi.csnPin);
|
||||
spiTransferByte(bus->spi.instance, reg | 0x80); // read transaction
|
||||
spiTransfer(bus->spi.instance, &data, NULL, 1);
|
||||
spiBusTransferByte(bus, reg | 0x80); // read transaction
|
||||
spiBusReadBuffer(bus, &data, 1);
|
||||
IOHi(bus->spi.csnPin);
|
||||
|
||||
return data;
|
||||
}
|
||||
|
||||
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance)
|
||||
{
|
||||
bus->spi.instance = instance;
|
||||
bus->spi.handle = spiHandleByInstance(instance);
|
||||
}
|
||||
|
||||
void dmaSPIIRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||
{
|
||||
SPIDevice device = descriptor->userParam;
|
||||
|
|
|
@ -84,7 +84,9 @@
|
|||
|
||||
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
||||
|
||||
#if defined(USE_SPI)
|
||||
static busDevice_t *bus = NULL; // HACK
|
||||
#endif
|
||||
|
||||
// FIXME pretend we have real MPU9250 support
|
||||
// Is an separate MPU9250 driver really needed? The GYRO/ACC part between MPU6500 and MPU9250 is exactly the same.
|
||||
|
@ -325,21 +327,18 @@ bool ak8963Detect(magDev_t *mag)
|
|||
{
|
||||
uint8_t sig = 0;
|
||||
|
||||
bus = &mag->bus;
|
||||
|
||||
#if defined(USE_SPI)
|
||||
bus = &mag->bus;
|
||||
#if defined(MPU6500_SPI_INSTANCE)
|
||||
bus->spi.instance = MPU6500_SPI_INSTANCE;
|
||||
spiBusSetInstance(&mag->bus, MPU6500_SPI_INSTANCE);
|
||||
#elif defined(MPU9250_SPI_INSTANCE)
|
||||
bus->spi.instance = MPU9250_SPI_INSTANCE;
|
||||
// initialze I2C master via SPI bus (MPU9250)
|
||||
spiBusSetInstance(&mag->bus, MPU9250_SPI_INSTANCE);
|
||||
|
||||
// initialze I2C master via SPI bus (MPU9250)
|
||||
mpu9250SpiWriteRegisterVerify(&mag->bus, MPU_RA_INT_PIN_CFG, MPU6500_BIT_INT_ANYRD_2CLEAR | MPU6500_BIT_BYPASS_EN);
|
||||
delay(10);
|
||||
|
||||
mpu9250SpiWriteRegisterVerify(&mag->bus, MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
|
||||
delay(10);
|
||||
|
||||
mpu9250SpiWriteRegisterVerify(&mag->bus, MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
|
||||
delay(10);
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue