mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 15:25:36 +03:00
Make SPI read and write register generic
This commit is contained in:
parent
e36ad629e4
commit
8df87bc47d
6 changed files with 74 additions and 53 deletions
|
@ -30,6 +30,7 @@
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/bus_i2c.h"
|
#include "drivers/bus_i2c.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/exti.h"
|
#include "drivers/exti.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
|
@ -233,14 +234,15 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
|
||||||
{
|
{
|
||||||
UNUSED(gyro); // since there are FCs which have gyro on I2C but other devices on SPI
|
UNUSED(gyro); // since there are FCs which have gyro on I2C but other devices on SPI
|
||||||
#ifdef USE_GYRO_SPI_MPU6000
|
#ifdef USE_GYRO_SPI_MPU6000
|
||||||
|
gyro->bus.spi.instance = MPU6000_SPI_INSTANCE;
|
||||||
#ifdef MPU6000_CS_PIN
|
#ifdef MPU6000_CS_PIN
|
||||||
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU6000_CS_PIN)) : gyro->bus.spi.csnPin;
|
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU6000_CS_PIN)) : gyro->bus.spi.csnPin;
|
||||||
#endif
|
#endif
|
||||||
if (mpu6000SpiDetect(&gyro->bus)) {
|
if (mpu6000SpiDetect(&gyro->bus)) {
|
||||||
gyro->mpuDetectionResult.sensor = MPU_60x0_SPI;
|
gyro->mpuDetectionResult.sensor = MPU_60x0_SPI;
|
||||||
gyro->mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
|
gyro->mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
|
||||||
gyro->mpuConfiguration.readFn = mpu6000SpiReadRegister;
|
gyro->mpuConfiguration.readFn = spiReadRegister;
|
||||||
gyro->mpuConfiguration.writeFn = mpu6000SpiWriteRegister;
|
gyro->mpuConfiguration.writeFn = spiWriteRegister;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -99,42 +99,19 @@ static bool mpuSpi6000InitDone = false;
|
||||||
#define MPU6000_REV_D9 0x59
|
#define MPU6000_REV_D9 0x59
|
||||||
#define MPU6000_REV_D10 0x5A
|
#define MPU6000_REV_D10 0x5A
|
||||||
|
|
||||||
#define DISABLE_MPU6000(spiCsnPin) IOHi(spiCsnPin)
|
|
||||||
#define ENABLE_MPU6000(spiCsnPin) IOLo(spiCsnPin)
|
|
||||||
|
|
||||||
bool mpu6000SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
|
|
||||||
{
|
|
||||||
ENABLE_MPU6000(bus->spi.csnPin);
|
|
||||||
spiTransferByte(MPU6000_SPI_INSTANCE, reg);
|
|
||||||
spiTransferByte(MPU6000_SPI_INSTANCE, data);
|
|
||||||
DISABLE_MPU6000(bus->spi.csnPin);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool mpu6000SpiReadRegister(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data)
|
|
||||||
{
|
|
||||||
ENABLE_MPU6000(bus->spi.csnPin);
|
|
||||||
spiTransferByte(MPU6000_SPI_INSTANCE, reg | 0x80); // read transaction
|
|
||||||
spiTransfer(MPU6000_SPI_INSTANCE, data, NULL, length);
|
|
||||||
DISABLE_MPU6000(bus->spi.csnPin);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void mpu6000SpiGyroInit(gyroDev_t *gyro)
|
void mpu6000SpiGyroInit(gyroDev_t *gyro)
|
||||||
{
|
{
|
||||||
mpuGyroInit(gyro);
|
mpuGyroInit(gyro);
|
||||||
|
|
||||||
mpu6000AccAndGyroInit(gyro);
|
mpu6000AccAndGyroInit(gyro);
|
||||||
|
|
||||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
|
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_INITIALIZATON);
|
||||||
|
|
||||||
// Accel and Gyro DLPF Setting
|
// Accel and Gyro DLPF Setting
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU6000_CONFIG, gyro->lpf);
|
spiWriteRegister(&gyro->bus, MPU6000_CONFIG, gyro->lpf);
|
||||||
delayMicroseconds(1);
|
delayMicroseconds(1);
|
||||||
|
|
||||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); // 18 MHz SPI clock
|
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_FAST); // 18 MHz SPI clock
|
||||||
|
|
||||||
mpuGyroRead(gyro);
|
mpuGyroRead(gyro);
|
||||||
|
|
||||||
|
@ -157,14 +134,14 @@ bool mpu6000SpiDetect(const busDevice_t *bus)
|
||||||
IOConfigGPIO(bus->spi.csnPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(bus->spi.csnPin, SPI_IO_CS_CFG);
|
||||||
IOHi(bus->spi.csnPin);
|
IOHi(bus->spi.csnPin);
|
||||||
|
|
||||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
|
spiSetDivisor(bus->spi.instance, SPI_CLOCK_INITIALIZATON);
|
||||||
|
|
||||||
mpu6000SpiWriteRegister(bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
|
spiWriteRegister(bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
|
||||||
|
|
||||||
do {
|
do {
|
||||||
delay(150);
|
delay(150);
|
||||||
|
|
||||||
mpu6000SpiReadRegister(bus, MPU_RA_WHO_AM_I, 1, &in);
|
spiReadRegister(bus, MPU_RA_WHO_AM_I, 1, &in);
|
||||||
if (in == MPU6000_WHO_AM_I_CONST) {
|
if (in == MPU6000_WHO_AM_I_CONST) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -173,7 +150,7 @@ bool mpu6000SpiDetect(const busDevice_t *bus)
|
||||||
}
|
}
|
||||||
} while (attemptsRemaining--);
|
} while (attemptsRemaining--);
|
||||||
|
|
||||||
mpu6000SpiReadRegister(bus, MPU_RA_PRODUCT_ID, 1, &in);
|
spiReadRegister(bus, MPU_RA_PRODUCT_ID, 1, &in);
|
||||||
|
|
||||||
/* look for a product ID we recognise */
|
/* look for a product ID we recognise */
|
||||||
|
|
||||||
|
@ -203,48 +180,48 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
|
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_INITIALIZATON);
|
||||||
|
|
||||||
// Device Reset
|
// Device Reset
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
|
spiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
|
||||||
delay(150);
|
delay(150);
|
||||||
|
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_SIGNAL_PATH_RESET, BIT_GYRO | BIT_ACC | BIT_TEMP);
|
spiWriteRegister(&gyro->bus, MPU_RA_SIGNAL_PATH_RESET, BIT_GYRO | BIT_ACC | BIT_TEMP);
|
||||||
delay(150);
|
delay(150);
|
||||||
|
|
||||||
// Clock Source PPL with Z axis gyro reference
|
// Clock Source PPL with Z axis gyro reference
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, MPU_CLK_SEL_PLLGYROZ);
|
spiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, MPU_CLK_SEL_PLLGYROZ);
|
||||||
delayMicroseconds(15);
|
delayMicroseconds(15);
|
||||||
|
|
||||||
// Disable Primary I2C Interface
|
// Disable Primary I2C Interface
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_USER_CTRL, BIT_I2C_IF_DIS);
|
spiWriteRegister(&gyro->bus, MPU_RA_USER_CTRL, BIT_I2C_IF_DIS);
|
||||||
delayMicroseconds(15);
|
delayMicroseconds(15);
|
||||||
|
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_2, 0x00);
|
spiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_2, 0x00);
|
||||||
delayMicroseconds(15);
|
delayMicroseconds(15);
|
||||||
|
|
||||||
// Accel Sample Rate 1kHz
|
// Accel Sample Rate 1kHz
|
||||||
// Gyroscope Output Rate = 1kHz when the DLPF is enabled
|
// Gyroscope Output Rate = 1kHz when the DLPF is enabled
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops(gyro));
|
spiWriteRegister(&gyro->bus, MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops(gyro));
|
||||||
delayMicroseconds(15);
|
delayMicroseconds(15);
|
||||||
|
|
||||||
// Gyro +/- 1000 DPS Full Scale
|
// Gyro +/- 1000 DPS Full Scale
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3);
|
spiWriteRegister(&gyro->bus, MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3);
|
||||||
delayMicroseconds(15);
|
delayMicroseconds(15);
|
||||||
|
|
||||||
// Accel +/- 8 G Full Scale
|
// Accel +/- 8 G Full Scale
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
spiWriteRegister(&gyro->bus, MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||||
delayMicroseconds(15);
|
delayMicroseconds(15);
|
||||||
|
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_ANYRD_2CLEAR
|
spiWriteRegister(&gyro->bus, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_ANYRD_2CLEAR
|
||||||
delayMicroseconds(15);
|
delayMicroseconds(15);
|
||||||
|
|
||||||
#ifdef USE_MPU_DATA_READY_SIGNAL
|
#ifdef USE_MPU_DATA_READY_SIGNAL
|
||||||
mpu6000SpiWriteRegister(&gyro->bus, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
|
spiWriteRegister(&gyro->bus, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
|
||||||
delayMicroseconds(15);
|
delayMicroseconds(15);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST);
|
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_FAST);
|
||||||
delayMicroseconds(1);
|
delayMicroseconds(1);
|
||||||
|
|
||||||
mpuSpi6000InitDone = true;
|
mpuSpi6000InitDone = true;
|
||||||
|
|
|
@ -21,6 +21,3 @@ bool mpu6000SpiDetect(const busDevice_t *bus);
|
||||||
|
|
||||||
bool mpu6000SpiAccDetect(accDev_t *acc);
|
bool mpu6000SpiAccDetect(accDev_t *acc);
|
||||||
bool mpu6000SpiGyroDetect(gyroDev_t *gyro);
|
bool mpu6000SpiGyroDetect(gyroDev_t *gyro);
|
||||||
|
|
||||||
bool mpu6000SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data);
|
|
||||||
bool mpu6000SpiReadRegister(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data);
|
|
||||||
|
|
|
@ -20,11 +20,12 @@
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
|
#include "drivers/bus.h"
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/exti.h"
|
#include "drivers/exti.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "io_impl.h"
|
#include "drivers/io_impl.h"
|
||||||
#include "rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
/* for F30x processors */
|
/* for F30x processors */
|
||||||
#if defined(STM32F303xC)
|
#if defined(STM32F303xC)
|
||||||
|
@ -351,3 +352,23 @@ void spiResetErrorCounter(SPI_TypeDef *instance)
|
||||||
if (device != SPIINVALID)
|
if (device != SPIINVALID)
|
||||||
spiHardwareMap[device].errorCount = 0;
|
spiHardwareMap[device].errorCount = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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);
|
||||||
|
IOHi(bus->spi.csnPin);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool spiReadRegister(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);
|
||||||
|
IOHi(bus->spi.csnPin);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
|
@ -18,7 +18,8 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/io_types.h"
|
#include "drivers/io_types.h"
|
||||||
#include "rcc_types.h"
|
#include "drivers/bus.h"
|
||||||
|
#include "drivers/rcc_types.h"
|
||||||
|
|
||||||
#if defined(STM32F4) || defined(STM32F3)
|
#if defined(STM32F4) || defined(STM32F3)
|
||||||
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
|
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
|
||||||
|
@ -101,3 +102,6 @@ SPIDevice spiDeviceByInstance(SPI_TypeDef *instance);
|
||||||
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance);
|
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance);
|
||||||
DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channel, SPI_TypeDef *Instance, uint8_t *pData, uint16_t Size);
|
DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channel, SPI_TypeDef *Instance, uint8_t *pData, uint16_t Size);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data);
|
||||||
|
bool spiReadRegister(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data);
|
||||||
|
|
|
@ -21,11 +21,11 @@
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
#include "dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "io_impl.h"
|
#include "drivers/io_impl.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
#ifndef SPI1_SCK_PIN
|
#ifndef SPI1_SCK_PIN
|
||||||
#define SPI1_NSS_PIN PA4
|
#define SPI1_NSS_PIN PA4
|
||||||
|
@ -346,6 +346,26 @@ void spiResetErrorCounter(SPI_TypeDef *instance)
|
||||||
spiHardwareMap[device].errorCount = 0;
|
spiHardwareMap[device].errorCount = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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);
|
||||||
|
IOHi(bus->spi.csnPin);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool spiReadRegister(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);
|
||||||
|
IOHi(bus->spi.csnPin);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
void dmaSPIIRQHandler(dmaChannelDescriptor_t* descriptor)
|
void dmaSPIIRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
{
|
{
|
||||||
SPIDevice device = descriptor->userParam;
|
SPIDevice device = descriptor->userParam;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue