1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 15:25:36 +03:00

Merge pull request #3530 from jflyper/bfdev-configurable-baro

Configurable baro
This commit is contained in:
jflyper 2017-07-19 20:16:21 +09:00 committed by GitHub
commit ba4f423019
50 changed files with 644 additions and 490 deletions

View file

@ -682,6 +682,7 @@ COMMON_SRC = \
config/config_streamer.c \ config/config_streamer.c \
drivers/adc.c \ drivers/adc.c \
drivers/buf_writer.c \ drivers/buf_writer.c \
drivers/bus_i2c_busdev.c \
drivers/bus_i2c_config.c \ drivers/bus_i2c_config.c \
drivers/bus_i2c_soft.c \ drivers/bus_i2c_soft.c \
drivers/bus_spi.c \ drivers/bus_spi.c \
@ -847,6 +848,7 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
common/typeconversion.c \ common/typeconversion.c \
drivers/adc.c \ drivers/adc.c \
drivers/buf_writer.c \ drivers/buf_writer.c \
drivers/bus_i2c_busdev.c \
drivers/bus_spi.c \ drivers/bus_spi.c \
drivers/exti.c \ drivers/exti.c \
drivers/gyro_sync.c \ drivers/gyro_sync.c \

View file

@ -29,7 +29,7 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/utils.h" #include "common/utils.h"
#include "drivers/bus_spi.h" #include "drivers/bus.h"
#include "drivers/bus_i2c.h" #include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
#include "drivers/exti.h" #include "drivers/exti.h"
@ -248,7 +248,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
spiBusSetInstance(&gyro->bus, MPU6000_SPI_INSTANCE); spiBusSetInstance(&gyro->bus, MPU6000_SPI_INSTANCE);
#endif #endif
#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.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU6000_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
#endif #endif
sensor = mpu6000SpiDetect(&gyro->bus); sensor = mpu6000SpiDetect(&gyro->bus);
if (sensor != MPU_NONE) { if (sensor != MPU_NONE) {
@ -264,7 +264,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
spiBusSetInstance(&gyro->bus, MPU6500_SPI_INSTANCE); spiBusSetInstance(&gyro->bus, MPU6500_SPI_INSTANCE);
#endif #endif
#ifdef MPU6500_CS_PIN #ifdef MPU6500_CS_PIN
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU6500_CS_PIN)) : gyro->bus.spi.csnPin; gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU6500_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
#endif #endif
sensor = mpu6500SpiDetect(&gyro->bus); sensor = mpu6500SpiDetect(&gyro->bus);
// some targets using MPU_9250_SPI, ICM_20608_SPI or ICM_20602_SPI state sensor is MPU_65xx_SPI // some targets using MPU_9250_SPI, ICM_20608_SPI or ICM_20602_SPI state sensor is MPU_65xx_SPI
@ -281,7 +281,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
spiBusSetInstance(&gyro->bus, MPU9250_SPI_INSTANCE); spiBusSetInstance(&gyro->bus, MPU9250_SPI_INSTANCE);
#endif #endif
#ifdef MPU9250_CS_PIN #ifdef MPU9250_CS_PIN
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU9250_CS_PIN)) : gyro->bus.spi.csnPin; gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(MPU9250_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
#endif #endif
sensor = mpu9250SpiDetect(&gyro->bus); sensor = mpu9250SpiDetect(&gyro->bus);
if (sensor != MPU_NONE) { if (sensor != MPU_NONE) {
@ -298,7 +298,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
spiBusSetInstance(&gyro->bus, ICM20689_SPI_INSTANCE); spiBusSetInstance(&gyro->bus, ICM20689_SPI_INSTANCE);
#endif #endif
#ifdef ICM20689_CS_PIN #ifdef ICM20689_CS_PIN
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(ICM20689_CS_PIN)) : gyro->bus.spi.csnPin; gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(ICM20689_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
#endif #endif
sensor = icm20689SpiDetect(&gyro->bus); sensor = icm20689SpiDetect(&gyro->bus);
if (sensor != MPU_NONE) { if (sensor != MPU_NONE) {
@ -314,7 +314,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
spiBusSetInstance(&gyro->bus, BMI160_SPI_INSTANCE); spiBusSetInstance(&gyro->bus, BMI160_SPI_INSTANCE);
#endif #endif
#ifdef BMI160_CS_PIN #ifdef BMI160_CS_PIN
gyro->bus.spi.csnPin = gyro->bus.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(BMI160_CS_PIN)) : gyro->bus.spi.csnPin; gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(BMI160_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin;
#endif #endif
sensor = bmi160Detect(&gyro->bus); sensor = bmi160Detect(&gyro->bus);
if (sensor != MPU_NONE) { if (sensor != MPU_NONE) {

View file

@ -92,18 +92,17 @@ static int32_t BMI160_Config(const busDevice_t *bus);
static int32_t BMI160_do_foc(const busDevice_t *bus); static int32_t BMI160_do_foc(const busDevice_t *bus);
static int32_t BMI160_WriteReg(const busDevice_t *bus, uint8_t reg, uint8_t data); static int32_t BMI160_WriteReg(const busDevice_t *bus, uint8_t reg, uint8_t data);
uint8_t bmi160Detect(const busDevice_t *bus) uint8_t bmi160Detect(const busDevice_t *bus)
{ {
if (BMI160Detected) { if (BMI160Detected) {
return BMI_160_SPI; return BMI_160_SPI;
} }
IOInit(bus->spi.csnPin, OWNER_MPU_CS, 0); IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
IOConfigGPIO(bus->spi.csnPin, SPI_IO_CS_CFG); IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
spiSetDivisor(bus->spi.instance, BMI160_SPI_DIVISOR); spiSetDivisor(bus->busdev_u.spi.instance, BMI160_SPI_DIVISOR);
/* Read this address to acticate SPI (see p. 84) */ /* Read this address to acticate SPI (see p. 84) */
spiReadRegister(bus, 0x7F); spiReadRegister(bus, 0x7F);
@ -270,12 +269,12 @@ static int32_t BMI160_do_foc(const busDevice_t *bus)
static int32_t BMI160_WriteReg(const busDevice_t *bus, uint8_t reg, uint8_t data) static int32_t BMI160_WriteReg(const busDevice_t *bus, uint8_t reg, uint8_t data)
{ {
ENABLE_BMI160(bus->spi.csnPin); IOLo(busdev->busdev_u.spi.csnPin); // Enable
spiTransferByte(BMI160_SPI_INSTANCE, 0x7f & reg); spiTransferByte(BMI160_SPI_INSTANCE, 0x7f & reg);
spiTransferByte(BMI160_SPI_INSTANCE, data); spiTransferByte(BMI160_SPI_INSTANCE, data);
DISABLE_BMI160(bus->spi.csnPin); IOHi(busdev->busdev_u.spi.csnPin); // Disable
return 0; return 0;
} }
@ -325,9 +324,9 @@ bool bmi160AccRead(accDev_t *acc)
uint8_t bmi160_rec_buf[BUFFER_SIZE]; uint8_t bmi160_rec_buf[BUFFER_SIZE];
uint8_t bmi160_tx_buf[BUFFER_SIZE] = {BMI160_REG_ACC_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0}; uint8_t bmi160_tx_buf[BUFFER_SIZE] = {BMI160_REG_ACC_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0};
IOLo(acc->bus.spi.csnPin); IOLo(acc->bus.busdev_u.spi.csnPin);
spiTransfer(acc->bus.spi.instance, bmi160_rec_buf, bmi160_tx_buf, BUFFER_SIZE); // receive response spiTransfer(acc->bus.busdev_u.spi.instance, bmi160_rec_buf, bmi160_tx_buf, BUFFER_SIZE); // receive response
IOHi(acc->bus.spi.csnPin); IOHi(acc->bus.busdev_u.spi.csnPin);
acc->ADCRaw[X] = (int16_t)((bmi160_rec_buf[IDX_ACCEL_XOUT_H] << 8) | bmi160_rec_buf[IDX_ACCEL_XOUT_L]); acc->ADCRaw[X] = (int16_t)((bmi160_rec_buf[IDX_ACCEL_XOUT_H] << 8) | bmi160_rec_buf[IDX_ACCEL_XOUT_L]);
acc->ADCRaw[Y] = (int16_t)((bmi160_rec_buf[IDX_ACCEL_YOUT_H] << 8) | bmi160_rec_buf[IDX_ACCEL_YOUT_L]); acc->ADCRaw[Y] = (int16_t)((bmi160_rec_buf[IDX_ACCEL_YOUT_H] << 8) | bmi160_rec_buf[IDX_ACCEL_YOUT_L]);
@ -353,9 +352,9 @@ bool bmi160GyroRead(gyroDev_t *gyro)
uint8_t bmi160_rec_buf[BUFFER_SIZE]; uint8_t bmi160_rec_buf[BUFFER_SIZE];
static const uint8_t bmi160_tx_buf[BUFFER_SIZE] = {BMI160_REG_GYR_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0}; static const uint8_t bmi160_tx_buf[BUFFER_SIZE] = {BMI160_REG_GYR_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0};
IOLo(gyro->bus.spi.csnPin); IOLo(gyro->bus.busdev_u.spi.csnPin);
spiTransfer(gyro->bus.spi.instance, bmi160_rec_buf, bmi160_tx_buf, BUFFER_SIZE); // receive response spiTransfer(gyro->bus.busdev_u.spi.instance, bmi160_rec_buf, bmi160_tx_buf, BUFFER_SIZE); // receive response
IOHi(gyro->bus.spi.csnPin); IOHi(gyro->bus.busdev_u.spi.csnPin);
gyro->gyroADCRaw[X] = (int16_t)((bmi160_rec_buf[IDX_GYRO_XOUT_H] << 8) | bmi160_rec_buf[IDX_GYRO_XOUT_L]); gyro->gyroADCRaw[X] = (int16_t)((bmi160_rec_buf[IDX_GYRO_XOUT_H] << 8) | bmi160_rec_buf[IDX_GYRO_XOUT_L]);
gyro->gyroADCRaw[Y] = (int16_t)((bmi160_rec_buf[IDX_GYRO_YOUT_H] << 8) | bmi160_rec_buf[IDX_GYRO_YOUT_L]); gyro->gyroADCRaw[Y] = (int16_t)((bmi160_rec_buf[IDX_GYRO_YOUT_H] << 8) | bmi160_rec_buf[IDX_GYRO_YOUT_L]);
@ -367,13 +366,13 @@ bool bmi160GyroRead(gyroDev_t *gyro)
void bmi160SpiGyroInit(gyroDev_t *gyro) void bmi160SpiGyroInit(gyroDev_t *gyro)
{ {
BMI160_Init(gyro->bus.spi.csnPin); BMI160_Init(gyro->bus.busdev_u.spi.csnPin);
bmi160IntExtiInit(gyro); bmi160IntExtiInit(gyro);
} }
void bmi160SpiAccInit(accDev_t *acc) void bmi160SpiAccInit(accDev_t *acc)
{ {
BMI160_Init(acc->bus.spi.csnPin); BMI160_Init(acc->bus.busdev_u.spi.csnPin);
acc->acc_1G = 512 * 8; acc->acc_1G = 512 * 8;
} }
@ -381,7 +380,7 @@ void bmi160SpiAccInit(accDev_t *acc)
bool bmi160SpiAccDetect(accDev_t *acc) bool bmi160SpiAccDetect(accDev_t *acc)
{ {
if (bmi160Detect(acc->bus.spi.csnPin) == MPU_NONE) { if (bmi160Detect(acc->bus.busdev_u.spi.csnPin) == MPU_NONE) {
return false; return false;
} }
@ -394,7 +393,7 @@ bool bmi160SpiAccDetect(accDev_t *acc)
bool bmi160SpiGyroDetect(gyroDev_t *gyro) bool bmi160SpiGyroDetect(gyroDev_t *gyro)
{ {
if (bmi160Detect(gyro->bus.spi.csnPin) == MPU_NONE) { if (bmi160Detect(gyro->bus.busdev_u.spi.csnPin) == MPU_NONE) {
return false; return false;
} }

View file

@ -44,11 +44,11 @@ static void icm20689SpiInit(const busDevice_t *bus)
return; return;
} }
IOInit(bus->spi.csnPin, OWNER_MPU_CS, 0); IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
IOConfigGPIO(bus->spi.csnPin, SPI_IO_CS_CFG); IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
spiSetDivisor(bus->spi.instance, SPI_CLOCK_STANDARD); spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_STANDARD);
hardwareInitialised = true; hardwareInitialised = true;
} }
@ -57,7 +57,7 @@ uint8_t icm20689SpiDetect(const busDevice_t *bus)
{ {
icm20689SpiInit(bus); icm20689SpiInit(bus);
spiSetDivisor(bus->spi.instance, SPI_CLOCK_INITIALIZATON); //low speed spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON); //low speed
spiWriteRegister(bus, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET); spiWriteRegister(bus, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET);
@ -73,7 +73,7 @@ uint8_t icm20689SpiDetect(const busDevice_t *bus)
} }
} while (attemptsRemaining--); } while (attemptsRemaining--);
spiSetDivisor(bus->spi.instance, SPI_CLOCK_STANDARD); spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_STANDARD);
return ICM_20689_SPI; return ICM_20689_SPI;
@ -100,7 +100,7 @@ void icm20689GyroInit(gyroDev_t *gyro)
{ {
mpuGyroInit(gyro); mpuGyroInit(gyro);
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_INITIALIZATON); spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON);
gyro->mpuConfiguration.writeFn(&gyro->bus, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET); gyro->mpuConfiguration.writeFn(&gyro->bus, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET);
delay(100); delay(100);
@ -130,7 +130,7 @@ void icm20689GyroInit(gyroDev_t *gyro)
gyro->mpuConfiguration.writeFn(&gyro->bus, MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable gyro->mpuConfiguration.writeFn(&gyro->bus, MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable
#endif #endif
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_STANDARD); spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_STANDARD);
} }
bool icm20689SpiGyroDetect(gyroDev_t *gyro) bool icm20689SpiGyroDetect(gyroDev_t *gyro)

View file

@ -105,13 +105,13 @@ void mpu6000SpiGyroInit(gyroDev_t *gyro)
mpu6000AccAndGyroInit(gyro); mpu6000AccAndGyroInit(gyro);
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_INITIALIZATON); spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON);
// Accel and Gyro DLPF Setting // Accel and Gyro DLPF Setting
spiWriteRegister(&gyro->bus, MPU6000_CONFIG, gyro->lpf); spiWriteRegister(&gyro->bus, MPU6000_CONFIG, gyro->lpf);
delayMicroseconds(1); delayMicroseconds(1);
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_FAST); // 18 MHz SPI clock spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_FAST); // 18 MHz SPI clock
mpuGyroRead(gyro); mpuGyroRead(gyro);
@ -127,11 +127,11 @@ void mpu6000SpiAccInit(accDev_t *acc)
uint8_t mpu6000SpiDetect(const busDevice_t *bus) uint8_t mpu6000SpiDetect(const busDevice_t *bus)
{ {
IOInit(bus->spi.csnPin, OWNER_MPU_CS, 0); IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
IOConfigGPIO(bus->spi.csnPin, SPI_IO_CS_CFG); IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
spiSetDivisor(bus->spi.instance, SPI_CLOCK_INITIALIZATON); spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON);
spiWriteRegister(bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET); spiWriteRegister(bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
@ -178,7 +178,7 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
return; return;
} }
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_INITIALIZATON); spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON);
// Device Reset // Device Reset
spiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET); spiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
@ -219,7 +219,7 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
delayMicroseconds(15); delayMicroseconds(15);
#endif #endif
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_FAST); spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_FAST);
delayMicroseconds(1); delayMicroseconds(1);
mpuSpi6000InitDone = true; mpuSpi6000InitDone = true;

View file

@ -44,11 +44,11 @@ static void mpu6500SpiInit(const busDevice_t *bus)
return; return;
} }
IOInit(bus->spi.csnPin, OWNER_MPU_CS, 0); IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
IOConfigGPIO(bus->spi.csnPin, SPI_IO_CS_CFG); IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
spiSetDivisor(bus->spi.instance, SPI_CLOCK_FAST); spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_FAST);
hardwareInitialised = true; hardwareInitialised = true;
} }
@ -90,7 +90,7 @@ void mpu6500SpiAccInit(accDev_t *acc)
void mpu6500SpiGyroInit(gyroDev_t *gyro) void mpu6500SpiGyroInit(gyroDev_t *gyro)
{ {
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_SLOW); spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_SLOW);
delayMicroseconds(1); delayMicroseconds(1);
mpu6500GyroInit(gyro); mpu6500GyroInit(gyro);
@ -99,7 +99,7 @@ void mpu6500SpiGyroInit(gyroDev_t *gyro)
spiWriteRegister(&gyro->bus, MPU_RA_USER_CTRL, MPU6500_BIT_I2C_IF_DIS); spiWriteRegister(&gyro->bus, MPU_RA_USER_CTRL, MPU6500_BIT_I2C_IF_DIS);
delay(100); delay(100);
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_FAST); spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_FAST);
delayMicroseconds(1); delayMicroseconds(1);
} }

View file

@ -52,11 +52,11 @@ static bool mpuSpi9250InitDone = false;
bool mpu9250SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data) bool mpu9250SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
{ {
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
delayMicroseconds(1); delayMicroseconds(1);
spiTransferByte(bus->spi.instance, reg); spiTransferByte(bus->busdev_u.spi.instance, reg);
spiTransferByte(bus->spi.instance, data); spiTransferByte(bus->busdev_u.spi.instance, data);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
delayMicroseconds(1); delayMicroseconds(1);
return true; return true;
@ -64,11 +64,11 @@ bool mpu9250SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
static bool mpu9250SpiSlowReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data) static bool mpu9250SpiSlowReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data)
{ {
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
delayMicroseconds(1); delayMicroseconds(1);
spiTransferByte(bus->spi.instance, reg | 0x80); // read transaction spiTransferByte(bus->busdev_u.spi.instance, reg | 0x80); // read transaction
spiTransfer(bus->spi.instance, data, NULL, length); spiTransfer(bus->busdev_u.spi.instance, data, NULL, length);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
delayMicroseconds(1); delayMicroseconds(1);
return true; return true;
@ -76,12 +76,15 @@ static bool mpu9250SpiSlowReadRegisterBuffer(const busDevice_t *bus, uint8_t reg
void mpu9250SpiResetGyro(void) void mpu9250SpiResetGyro(void)
{ {
#if 0
// XXX This doesn't work. Need a proper busDevice_t.
// Device Reset // Device Reset
#ifdef MPU9250_CS_PIN #ifdef MPU9250_CS_PIN
busDevice_t bus = { .spi = { .csnPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN)) } }; busDevice_t bus = { .spi = { .csnPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN)) } };
mpu9250SpiWriteRegister(&bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); mpu9250SpiWriteRegister(&bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
delay(150); delay(150);
#endif #endif
#endif
} }
void mpu9250SpiGyroInit(gyroDev_t *gyro) void mpu9250SpiGyroInit(gyroDev_t *gyro)
@ -90,14 +93,14 @@ void mpu9250SpiGyroInit(gyroDev_t *gyro)
mpu9250AccAndGyroInit(gyro); mpu9250AccAndGyroInit(gyro);
spiResetErrorCounter(gyro->bus.spi.instance); spiResetErrorCounter(gyro->bus.busdev_u.spi.instance);
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_FAST); //high speed now that we don't need to write to the slow registers spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_FAST); //high speed now that we don't need to write to the slow registers
mpuGyroRead(gyro); mpuGyroRead(gyro);
if ((((int8_t)gyro->gyroADCRaw[1]) == -1 && ((int8_t)gyro->gyroADCRaw[0]) == -1) || spiGetErrorCounter(gyro->bus.spi.instance) != 0) { if ((((int8_t)gyro->gyroADCRaw[1]) == -1 && ((int8_t)gyro->gyroADCRaw[0]) == -1) || spiGetErrorCounter(gyro->bus.busdev_u.spi.instance) != 0) {
spiResetErrorCounter(gyro->bus.spi.instance); spiResetErrorCounter(gyro->bus.busdev_u.spi.instance);
failureMode(FAILURE_GYRO_INIT_FAILED); failureMode(FAILURE_GYRO_INIT_FAILED);
} }
} }
@ -133,7 +136,7 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro) {
return; return;
} }
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_INITIALIZATON); //low speed for writing to slow registers spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON); //low speed for writing to slow registers
mpu9250SpiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); mpu9250SpiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
delay(50); delay(50);
@ -161,17 +164,17 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro) {
mpu9250SpiWriteRegisterVerify(&gyro->bus, MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly. mpu9250SpiWriteRegisterVerify(&gyro->bus, MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly.
#endif #endif
spiSetDivisor(gyro->bus.spi.instance, SPI_CLOCK_FAST); spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_FAST);
mpuSpi9250InitDone = true; //init done mpuSpi9250InitDone = true; //init done
} }
uint8_t mpu9250SpiDetect(const busDevice_t *bus) uint8_t mpu9250SpiDetect(const busDevice_t *bus)
{ {
IOInit(bus->spi.csnPin, OWNER_MPU_CS, 0); IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0);
IOConfigGPIO(bus->spi.csnPin, SPI_IO_CS_CFG); IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
spiSetDivisor(bus->spi.instance, SPI_CLOCK_INITIALIZATON); //low speed spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON); //low speed
mpu9250SpiWriteRegister(bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); mpu9250SpiWriteRegister(bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
uint8_t attemptsRemaining = 20; uint8_t attemptsRemaining = 20;
@ -186,7 +189,7 @@ uint8_t mpu9250SpiDetect(const busDevice_t *bus)
} }
} while (attemptsRemaining--); } while (attemptsRemaining--);
spiSetDivisor(bus->spi.instance, SPI_CLOCK_FAST); spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_FAST);
return MPU_9250_SPI; return MPU_9250_SPI;
} }

View file

@ -17,10 +17,15 @@
#pragma once #pragma once
typedef void (*baroOpFuncPtr)(void); // baro start operation #include "drivers/bus.h" // XXX
struct baroDev_s;
typedef void (*baroOpFuncPtr)(struct baroDev_s *baro); // baro start operation
typedef void (*baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature) typedef void (*baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature)
typedef struct baroDev_s { typedef struct baroDev_s {
busDevice_t busdev;
uint16_t ut_delay; uint16_t ut_delay;
uint16_t up_delay; uint16_t up_delay;
baroOpFuncPtr start_ut; baroOpFuncPtr start_ut;

View file

@ -24,7 +24,9 @@
#include "barometer.h" #include "barometer.h"
#include "drivers/bus.h"
#include "drivers/bus_i2c.h" #include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_busdev.h"
#include "drivers/exti.h" #include "drivers/exti.h"
#include "drivers/gpio.h" #include "drivers/gpio.h"
#include "drivers/io.h" #include "drivers/io.h"
@ -119,11 +121,11 @@ static bool bmp085InitDone = false;
STATIC_UNIT_TESTED uint16_t bmp085_ut; // static result of temperature measurement STATIC_UNIT_TESTED uint16_t bmp085_ut; // static result of temperature measurement
STATIC_UNIT_TESTED uint32_t bmp085_up; // static result of pressure measurement STATIC_UNIT_TESTED uint32_t bmp085_up; // static result of pressure measurement
static void bmp085_get_cal_param(void); static void bmp085_get_cal_param(busDevice_t *busdev);
static void bmp085_start_ut(void); static void bmp085_start_ut(baroDev_t *baro);
static void bmp085_get_ut(void); static void bmp085_get_ut(baroDev_t *baro);
static void bmp085_start_up(void); static void bmp085_start_up(baroDev_t *baro);
static void bmp085_get_up(void); static void bmp085_get_up(baroDev_t *baro);
static int32_t bmp085_get_temperature(uint32_t ut); static int32_t bmp085_get_temperature(uint32_t ut);
static int32_t bmp085_get_pressure(uint32_t up); static int32_t bmp085_get_pressure(uint32_t up);
STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature); STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature);
@ -154,6 +156,16 @@ void bmp085Disable(const bmp085Config_t *config)
BMP085_OFF; BMP085_OFF;
} }
bool bmp085ReadRegister(busDevice_t *busdev, uint8_t cmd, uint8_t len, uint8_t *data)
{
return i2cReadRegisterBuffer(busdev, cmd, len, data);
}
bool bmp085WriteRegister(busDevice_t *busdev, uint8_t cmd, uint8_t byte)
{
return i2cWriteRegister(busdev, cmd, byte);
}
bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro) bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
{ {
uint8_t data; uint8_t data;
@ -184,16 +196,18 @@ bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
delay(20); // datasheet says 10ms, we'll be careful and do 20. delay(20); // datasheet says 10ms, we'll be careful and do 20.
ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ busDevice_t *busdev = &baro->busdev;
ack = bmp085ReadRegister(busdev, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
if (ack) { if (ack) {
bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID); bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID);
bmp085.oversampling_setting = 3; bmp085.oversampling_setting = 3;
if (bmp085.chip_id == BMP085_CHIP_ID) { /* get bitslice */ if (bmp085.chip_id == BMP085_CHIP_ID) { /* get bitslice */
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_VERSION_REG, 1, &data); /* read Version reg */ bmp085ReadRegister(busdev, BMP085_VERSION_REG, 1, &data); /* read Version reg */
bmp085.ml_version = BMP085_GET_BITSLICE(data, BMP085_ML_VERSION); /* get ML Version */ bmp085.ml_version = BMP085_GET_BITSLICE(data, BMP085_ML_VERSION); /* get ML Version */
bmp085.al_version = BMP085_GET_BITSLICE(data, BMP085_AL_VERSION); /* get AL Version */ bmp085.al_version = BMP085_GET_BITSLICE(data, BMP085_AL_VERSION); /* get AL Version */
bmp085_get_cal_param(); /* readout bmp085 calibparam structure */ bmp085_get_cal_param(busdev); /* readout bmp085 calibparam structure */
baro->ut_delay = UT_DELAY; baro->ut_delay = UT_DELAY;
baro->up_delay = UP_DELAY; baro->up_delay = UP_DELAY;
baro->start_ut = bmp085_start_ut; baro->start_ut = bmp085_start_ut;
@ -272,15 +286,15 @@ static int32_t bmp085_get_pressure(uint32_t up)
return pressure; return pressure;
} }
static void bmp085_start_ut(void) static void bmp085_start_ut(baroDev_t *baro)
{ {
#if defined(BARO_EOC_GPIO) #if defined(BARO_EOC_GPIO)
isConversionComplete = false; isConversionComplete = false;
#endif #endif
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE); bmp085WriteRegister(&baro->busdev, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
} }
static void bmp085_get_ut(void) static void bmp085_get_ut(baroDev_t *baro)
{ {
uint8_t data[2]; uint8_t data[2];
@ -291,11 +305,11 @@ static void bmp085_get_ut(void)
} }
#endif #endif
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data); bmp085ReadRegister(&baro->busdev, BMP085_ADC_OUT_MSB_REG, 2, data);
bmp085_ut = (data[0] << 8) | data[1]; bmp085_ut = (data[0] << 8) | data[1];
} }
static void bmp085_start_up(void) static void bmp085_start_up(baroDev_t *baro)
{ {
uint8_t ctrl_reg_data; uint8_t ctrl_reg_data;
@ -305,14 +319,14 @@ static void bmp085_start_up(void)
isConversionComplete = false; isConversionComplete = false;
#endif #endif
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data); bmp085WriteRegister(&baro->busdev, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
} }
/** read out up for pressure conversion /** read out up for pressure conversion
depending on the oversampling ratio setting up can be 16 to 19 bit depending on the oversampling ratio setting up can be 16 to 19 bit
\return up parameter that represents the uncompensated pressure value \return up parameter that represents the uncompensated pressure value
*/ */
static void bmp085_get_up(void) static void bmp085_get_up(baroDev_t *baro)
{ {
uint8_t data[3]; uint8_t data[3];
@ -323,7 +337,7 @@ static void bmp085_get_up(void)
} }
#endif #endif
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data); bmp085ReadRegister(&baro->busdev, BMP085_ADC_OUT_MSB_REG, 3, data);
bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2]) bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2])
>> (8 - bmp085.oversampling_setting); >> (8 - bmp085.oversampling_setting);
} }
@ -340,10 +354,10 @@ STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature
*temperature = temp; *temperature = temp;
} }
static void bmp085_get_cal_param(void) static void bmp085_get_cal_param(busDevice_t *busdev)
{ {
uint8_t data[22]; uint8_t data[22];
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data); bmp085ReadRegister(busdev, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data);
/*parameters AC1-AC6*/ /*parameters AC1-AC6*/
bmp085.cal_param.ac1 = (data[0] << 8) | data[1]; bmp085.cal_param.ac1 = (data[0] << 8) | data[1];

View file

@ -19,6 +19,8 @@
#include "drivers/io_types.h" #include "drivers/io_types.h"
#define BMP085_I2C_ADDR 0x77
typedef struct bmp085Config_s { typedef struct bmp085Config_s {
ioTag_t xclrIO; ioTag_t xclrIO;
ioTag_t eocIO; ioTag_t eocIO;

View file

@ -21,18 +21,20 @@
#include <platform.h> #include <platform.h>
#include "build/build_config.h" #include "build/build_config.h"
#include "build/debug.h"
#include "barometer.h" #include "barometer.h"
#include "drivers/bus.h"
#include "drivers/bus_i2c.h" #include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_busdev.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "barometer_bmp280.h" #include "barometer_bmp280.h"
#include "barometer_spi_bmp280.h"
#ifdef BARO #if defined(BARO) && (defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280))
// BMP280, address 0x76
typedef struct bmp280_calib_param_s { typedef struct bmp280_calib_param_s {
uint16_t dig_T1; /* calibration T1 data */ uint16_t dig_T1; /* calibration T1 data */
@ -51,97 +53,137 @@ typedef struct bmp280_calib_param_s {
} bmp280_calib_param_t; } bmp280_calib_param_t;
static uint8_t bmp280_chip_id = 0; static uint8_t bmp280_chip_id = 0;
static bool bmp280InitDone = false;
STATIC_UNIT_TESTED bmp280_calib_param_t bmp280_cal; STATIC_UNIT_TESTED bmp280_calib_param_t bmp280_cal;
// uncompensated pressure and temperature // uncompensated pressure and temperature
int32_t bmp280_up = 0; int32_t bmp280_up = 0;
int32_t bmp280_ut = 0; int32_t bmp280_ut = 0;
static void bmp280_start_ut(void); static void bmp280_start_ut(baroDev_t *baro);
static void bmp280_get_ut(void); static void bmp280_get_ut(baroDev_t *baro);
#ifndef USE_BARO_SPI_BMP280 static void bmp280_start_up(baroDev_t *baro);
static void bmp280_start_up(void); static void bmp280_get_up(baroDev_t *baro);
static void bmp280_get_up(void);
#endif
STATIC_UNIT_TESTED void bmp280_calculate(int32_t *pressure, int32_t *temperature); STATIC_UNIT_TESTED void bmp280_calculate(int32_t *pressure, int32_t *temperature);
bool bmp280ReadRegister(busDevice_t *busdev, uint8_t reg, uint8_t length, uint8_t *data)
{
switch (busdev->bustype) {
#ifdef USE_BARO_SPI_BMP280
case BUSTYPE_SPI:
return spiReadRegisterBuffer(busdev, reg | 0x80, length, data);
#endif
#ifdef USE_BARO_BMP280
case BUSTYPE_I2C:
return i2cReadRegisterBuffer(busdev, reg, length, data);
#endif
}
return false;
}
bool bmp280WriteRegister(busDevice_t *busdev, uint8_t reg, uint8_t data)
{
switch (busdev->bustype) {
#ifdef USE_BARO_SPI_BMP280
case BUSTYPE_SPI:
return spiWriteRegister(busdev, reg & 0x7f, data);
#endif
#ifdef USE_BARO_BMP280
case BUSTYPE_I2C:
return i2cWriteRegister(busdev, reg, data);
#endif
}
return false;
}
void bmp280BusInit(busDevice_t *busdev)
{
#ifdef USE_BARO_SPI_BMP280
if (busdev->bustype == BUSTYPE_SPI) {
IOInit(busdev->busdev_u.spi.csnPin, OWNER_BARO_CS, 0);
IOConfigGPIO(busdev->busdev_u.spi.csnPin, IOCFG_OUT_PP);
IOHi(busdev->busdev_u.spi.csnPin); // Disable
spiSetDivisor(busdev->busdev_u.spi.instance, SPI_CLOCK_STANDARD); // XXX
}
#else
UNUSED(busdev);
#endif
}
void bmp280BusDeinit(busDevice_t *busdev)
{
#ifdef USE_BARO_SPI_BMP280
if (busdev->bustype == BUSTYPE_SPI) {
IOConfigGPIO(busdev->busdev_u.spi.csnPin, IOCFG_IPU);
IORelease(busdev->busdev_u.spi.csnPin);
IOInit(busdev->busdev_u.spi.csnPin, OWNER_SPI_PREINIT, 0);
}
#else
UNUSED(busdev);
#endif
}
bool bmp280Detect(baroDev_t *baro) bool bmp280Detect(baroDev_t *baro)
{ {
if (bmp280InitDone)
return true;
delay(20); delay(20);
#ifdef USE_BARO_SPI_BMP280 busDevice_t *busdev = &baro->busdev;
bmp280SpiInit();
bmp280ReadRegister(BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); bmp280BusInit(busdev);
if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID)
bmp280ReadRegister(busdev, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID) {
bmp280BusDeinit(busdev);
return false; return false;
}
// read calibration // read calibration
bmp280ReadRegister(BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal); bmp280ReadRegister(busdev, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
// set oversampling + power mode (forced), and start sampling
bmp280WriteRegister(BMP280_CTRL_MEAS_REG, BMP280_MODE);
#else
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID)
return false;
// read calibration
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
// set oversampling + power mode (forced), and start sampling // set oversampling + power mode (forced), and start sampling
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE); bmp280WriteRegister(busdev, BMP280_CTRL_MEAS_REG, BMP280_MODE);
#endif
bmp280InitDone = true;
// these are dummy as temperature is measured as part of pressure // these are dummy as temperature is measured as part of pressure
baro->ut_delay = 0; baro->ut_delay = 0;
baro->get_ut = bmp280_get_ut; baro->get_ut = bmp280_get_ut;
baro->start_ut = bmp280_start_ut; baro->start_ut = bmp280_start_ut;
// only _up part is executed, and gets both temperature and pressure // only _up part is executed, and gets both temperature and pressure
baro->up_delay = ((T_INIT_MAX + T_MEASURE_PER_OSRS_MAX * (((1 << BMP280_TEMPERATURE_OSR) >> 1) + ((1 << BMP280_PRESSURE_OSR) >> 1)) + (BMP280_PRESSURE_OSR ? T_SETUP_PRESSURE_MAX : 0) + 15) / 16) * 1000;
#ifdef USE_BARO_SPI_BMP280
baro->start_up = bmp280_spi_start_up;
baro->get_up = bmp280_spi_get_up;
#else
baro->start_up = bmp280_start_up; baro->start_up = bmp280_start_up;
baro->get_up = bmp280_get_up; baro->get_up = bmp280_get_up;
#endif baro->up_delay = ((T_INIT_MAX + T_MEASURE_PER_OSRS_MAX * (((1 << BMP280_TEMPERATURE_OSR) >> 1) + ((1 << BMP280_PRESSURE_OSR) >> 1)) + (BMP280_PRESSURE_OSR ? T_SETUP_PRESSURE_MAX : 0) + 15) / 16) * 1000;
baro->calculate = bmp280_calculate; baro->calculate = bmp280_calculate;
return true; return true;
} }
static void bmp280_start_ut(void) static void bmp280_start_ut(baroDev_t *baro)
{ {
UNUSED(baro);
// dummy // dummy
} }
static void bmp280_get_ut(void) static void bmp280_get_ut(baroDev_t *baro)
{ {
UNUSED(baro);
// dummy // dummy
} }
#ifndef USE_BARO_SPI_BMP280 static void bmp280_start_up(baroDev_t *baro)
static void bmp280_start_up(void)
{ {
// start measurement // start measurement
// set oversampling + power mode (forced), and start sampling // set oversampling + power mode (forced), and start sampling
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE); bmp280WriteRegister(&baro->busdev, BMP280_CTRL_MEAS_REG, BMP280_MODE);
} }
static void bmp280_get_up(void) static void bmp280_get_up(baroDev_t *baro)
{ {
uint8_t data[BMP280_DATA_FRAME_SIZE]; uint8_t data[BMP280_DATA_FRAME_SIZE];
// read data from sensor // read data from sensor
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data); bmp280ReadRegister(&baro->busdev, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4)); bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4));
bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4)); bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4));
} }
#endif
// Returns temperature in DegC, resolution is 0.01 DegC. Output value of "5123" equals 51.23 DegC // Returns temperature in DegC, resolution is 0.01 DegC. Output value of "5123" equals 51.23 DegC
// t_fine carries fine temperature as global value // t_fine carries fine temperature as global value

View file

@ -17,7 +17,8 @@
#pragma once #pragma once
#define BMP280_I2C_ADDR (0x76) //#define BMP280_I2C_ADDR (0x76)
#define BMP280_I2C_ADDR (0x77) // Adafruit 2651
#define BMP280_DEFAULT_CHIP_ID (0x58) #define BMP280_DEFAULT_CHIP_ID (0x58)
#define BMP280_CHIP_ID_REG (0xD0) /* Chip ID Register */ #define BMP280_CHIP_ID_REG (0xD0) /* Chip ID Register */

View file

@ -22,6 +22,8 @@
#ifdef USE_FAKE_BARO #ifdef USE_FAKE_BARO
#include "common/utils.h"
#include "barometer.h" #include "barometer.h"
#include "barometer_fake.h" #include "barometer_fake.h"
@ -30,8 +32,9 @@ static int32_t fakePressure;
static int32_t fakeTemperature; static int32_t fakeTemperature;
static void fakeBaroStartGet(void) static void fakeBaroStartGet(baroDev_t *baro)
{ {
UNUSED(baro);
} }
static void fakeBaroCalculate(int32_t *pressure, int32_t *temperature) static void fakeBaroCalculate(int32_t *pressure, int32_t *temperature)

View file

@ -20,18 +20,19 @@
#include <platform.h> #include <platform.h>
#if defined(BARO) && (defined(USE_BARO_MS5611) || defined(USE_BARO_SPI_MS5611))
#include "build/build_config.h" #include "build/build_config.h"
#include "barometer.h" #include "barometer.h"
#include "barometer_spi_ms5611.h" #include "barometer_ms5611.h"
#include "drivers/bus_i2c.h" #include "drivers/bus_i2c.h"
#include "drivers/gpio.h" #include "drivers/bus_i2c_busdev.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/time.h" #include "drivers/time.h"
// MS5611, Standard address 0x77
#define MS5611_ADDR 0x77
#define CMD_RESET 0x1E // ADC reset command #define CMD_RESET 0x1E // ADC reset command
#define CMD_ADC_READ 0x00 // ADC read command #define CMD_ADC_READ 0x00 // ADC read command
#define CMD_ADC_CONV 0x40 // ADC conversion command #define CMD_ADC_CONV 0x40 // ADC conversion command
@ -45,14 +46,14 @@
#define CMD_PROM_RD 0xA0 // Prom read command #define CMD_PROM_RD 0xA0 // Prom read command
#define PROM_NB 8 #define PROM_NB 8
static void ms5611_reset(void); static void ms5611_reset(busDevice_t *busdev);
static uint16_t ms5611_prom(int8_t coef_num); static uint16_t ms5611_prom(busDevice_t *busdev, int8_t coef_num);
STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom); STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom);
static uint32_t ms5611_read_adc(void); static uint32_t ms5611_read_adc(busDevice_t *busdev);
static void ms5611_start_ut(void); static void ms5611_start_ut(baroDev_t *baro);
static void ms5611_get_ut(void); static void ms5611_get_ut(baroDev_t *baro);
static void ms5611_start_up(void); static void ms5611_start_up(baroDev_t *baro);
static void ms5611_get_up(void); static void ms5611_get_up(baroDev_t *baro);
STATIC_UNIT_TESTED void ms5611_calculate(int32_t *pressure, int32_t *temperature); STATIC_UNIT_TESTED void ms5611_calculate(int32_t *pressure, int32_t *temperature);
STATIC_UNIT_TESTED uint32_t ms5611_ut; // static result of temperature measurement STATIC_UNIT_TESTED uint32_t ms5611_ut; // static result of temperature measurement
@ -60,6 +61,63 @@ STATIC_UNIT_TESTED uint32_t ms5611_up; // static result of pressure measurement
STATIC_UNIT_TESTED uint16_t ms5611_c[PROM_NB]; // on-chip ROM STATIC_UNIT_TESTED uint16_t ms5611_c[PROM_NB]; // on-chip ROM
static uint8_t ms5611_osr = CMD_ADC_4096; static uint8_t ms5611_osr = CMD_ADC_4096;
bool ms5611ReadCommand(busDevice_t *busdev, uint8_t cmd, uint8_t len, uint8_t *data)
{
switch (busdev->bustype) {
#ifdef USE_BARO_SPI_MS5611
case BUSTYPE_SPI:
return spiReadRegisterBuffer(busdev, cmd | 0x80, len, data);
#endif
#ifdef USE_BARO_MS5611
case BUSTYPE_I2C:
return i2cReadRegisterBuffer(busdev, cmd, len, data);
#endif
}
return false;
}
bool ms5611WriteCommand(busDevice_t *busdev, uint8_t cmd, uint8_t byte)
{
switch (busdev->bustype) {
#ifdef USE_BARO_SPI_MS5611
case BUSTYPE_SPI:
return spiWriteRegister(busdev, cmd & 0x7f, byte);
#endif
#ifdef USE_BARO_MS5611
case BUSTYPE_I2C:
return i2cWriteRegister(busdev, cmd, byte);
#endif
}
return false;
}
void ms5611BusInit(busDevice_t *busdev)
{
#ifdef USE_BARO_SPI_MS5611
if (busdev->bustype == BUSTYPE_SPI) {
IOInit(busdev->busdev_u.spi.csnPin, OWNER_BARO_CS, 0);
IOConfigGPIO(busdev->busdev_u.spi.csnPin, IOCFG_OUT_PP);
IOHi(busdev->busdev_u.spi.csnPin); // Disable
spiSetDivisor(busdev->busdev_u.spi.csnPin, SPI_CLOCK_STANDARD);
}
#else
UNUSED(busdev);
#endif
}
void ms5611BusDeinit(busDevice_t *busdev)
{
#ifdef USE_BARO_SPI_MS5611
if (busdev->bustype == BUSTYPE_SPI) {
IOConfigGPIO(busdev->busdev_u.spi.csnPin, IOCFG_IPU);
IORelease(busdev->busdev_u.spi.csnPin);
IOInit(busdev->busdev_u.spi.csnPin, OWNER_SPI_PREINIT, 0);
}
#else
UNUSED(busdev);
#endif
}
bool ms5611Detect(baroDev_t *baro) bool ms5611Detect(baroDev_t *baro)
{ {
uint8_t sig; uint8_t sig;
@ -67,23 +125,26 @@ bool ms5611Detect(baroDev_t *baro)
delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms
#ifdef USE_BARO_SPI_MS5611 busDevice_t *busdev = &baro->busdev;
ms5611SpiInit();
ms5611SpiReadCommand(CMD_PROM_RD, 1, &sig); ms5611BusInit(busdev);
if (sig == 0xFF)
return false; if (!ms5611ReadCommand(busdev, CMD_PROM_RD, 1, &sig) || sig == 0xFF) {
#else ms5611BusDeinit(busdev);
if (!i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig)) return false;
return false; }
#endif
ms5611_reset(busdev);
ms5611_reset();
// read all coefficients // read all coefficients
for (i = 0; i < PROM_NB; i++) for (i = 0; i < PROM_NB; i++)
ms5611_c[i] = ms5611_prom(i); ms5611_c[i] = ms5611_prom(busdev, i);
// check crc, bail out if wrong - we are probably talking to BMP085 w/o XCLR line! // check crc, bail out if wrong - we are probably talking to BMP085 w/o XCLR line!
if (ms5611_crc(ms5611_c) != 0) if (ms5611_crc(ms5611_c) != 0) {
ms5611BusDeinit(busdev);
return false; return false;
}
// TODO prom + CRC // TODO prom + CRC
baro->ut_delay = 10000; baro->ut_delay = 10000;
@ -97,24 +158,19 @@ bool ms5611Detect(baroDev_t *baro)
return true; return true;
} }
static void ms5611_reset(void) static void ms5611_reset(busDevice_t *busdev)
{ {
#ifdef USE_BARO_SPI_MS5611 ms5611WriteCommand(busdev, CMD_RESET, 1);
ms5611SpiWriteCommand(CMD_RESET, 1);
#else
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_RESET, 1);
#endif
delayMicroseconds(2800); delayMicroseconds(2800);
} }
static uint16_t ms5611_prom(int8_t coef_num) static uint16_t ms5611_prom(busDevice_t *busdev, int8_t coef_num)
{ {
uint8_t rxbuf[2] = { 0, 0 }; uint8_t rxbuf[2] = { 0, 0 };
#ifdef USE_BARO_SPI_MS5611
ms5611SpiReadCommand(CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command ms5611ReadCommand(busdev, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
#else
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
#endif
return rxbuf[0] << 8 | rxbuf[1]; return rxbuf[0] << 8 | rxbuf[1];
} }
@ -148,43 +204,33 @@ STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom)
return -1; return -1;
} }
static uint32_t ms5611_read_adc(void) static uint32_t ms5611_read_adc(busDevice_t *busdev)
{ {
uint8_t rxbuf[3]; uint8_t rxbuf[3];
#ifdef USE_BARO_SPI_MS5611
ms5611SpiReadCommand(CMD_ADC_READ, 3, rxbuf); // read ADC ms5611ReadCommand(busdev, CMD_ADC_READ, 3, rxbuf); // read ADC
#else
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC
#endif
return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2]; return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2];
} }
static void ms5611_start_ut(void) static void ms5611_start_ut(baroDev_t *baro)
{ {
#ifdef USE_BARO_SPI_MS5611 ms5611WriteCommand(&baro->busdev, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
ms5611SpiWriteCommand(CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
#else
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
#endif
} }
static void ms5611_get_ut(void) static void ms5611_get_ut(baroDev_t *baro)
{ {
ms5611_ut = ms5611_read_adc(); ms5611_ut = ms5611_read_adc(&baro->busdev);
} }
static void ms5611_start_up(void) static void ms5611_start_up(baroDev_t *baro)
{ {
#ifdef USE_BARO_SPI_MS5611 ms5611WriteCommand(&baro->busdev, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start!
ms5611SpiWriteCommand(CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
#else
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start!
#endif
} }
static void ms5611_get_up(void) static void ms5611_get_up(baroDev_t *baro)
{ {
ms5611_up = ms5611_read_adc(); ms5611_up = ms5611_read_adc(&baro->busdev);
} }
STATIC_UNIT_TESTED void ms5611_calculate(int32_t *pressure, int32_t *temperature) STATIC_UNIT_TESTED void ms5611_calculate(int32_t *pressure, int32_t *temperature)
@ -218,3 +264,4 @@ STATIC_UNIT_TESTED void ms5611_calculate(int32_t *pressure, int32_t *temperature
if (temperature) if (temperature)
*temperature = temp; *temperature = temp;
} }
#endif

View file

@ -17,4 +17,7 @@
#pragma once #pragma once
// MS5611, Standard address 0x77
#define MS5611_I2C_ADDR 0x77
bool ms5611Detect(baroDev_t *baro); bool ms5611Detect(baroDev_t *baro);

View file

@ -1,94 +0,0 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stddef.h>
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/bus_spi.h"
#include "barometer.h"
#include "barometer_bmp280.h"
#include "drivers/io.h"
#ifdef USE_BARO_SPI_BMP280
#define DISABLE_BMP280 IOHi(bmp280CsPin)
#define ENABLE_BMP280 IOLo(bmp280CsPin)
extern int32_t bmp280_up;
extern int32_t bmp280_ut;
static IO_t bmp280CsPin = IO_NONE;
bool bmp280WriteRegister(uint8_t reg, uint8_t data)
{
ENABLE_BMP280;
spiTransferByte(BMP280_SPI_INSTANCE, reg & 0x7F);
spiTransferByte(BMP280_SPI_INSTANCE, data);
DISABLE_BMP280;
return true;
}
bool bmp280ReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
{
ENABLE_BMP280;
spiTransferByte(BMP280_SPI_INSTANCE, reg | 0x80); // read transaction
spiTransfer(BMP280_SPI_INSTANCE, data, NULL, length);
DISABLE_BMP280;
return true;
}
void bmp280SpiInit(void)
{
static bool hardwareInitialised = false;
if (hardwareInitialised) {
return;
}
bmp280CsPin = IOGetByTag(IO_TAG(BMP280_CS_PIN));
IOInit(bmp280CsPin, OWNER_BARO_CS, 0);
IOConfigGPIO(bmp280CsPin, IOCFG_OUT_PP);
DISABLE_BMP280;
spiSetDivisor(BMP280_SPI_INSTANCE, SPI_CLOCK_STANDARD);
hardwareInitialised = true;
}
void bmp280_spi_start_up(void)
{
// start measurement
// set oversampling + power mode (forced), and start sampling
bmp280WriteRegister(BMP280_CTRL_MEAS_REG, BMP280_MODE);
}
void bmp280_spi_get_up(void)
{
uint8_t data[BMP280_DATA_FRAME_SIZE];
// read data from sensor
bmp280ReadRegister(BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4));
bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4));
}
#endif

View file

@ -1,24 +0,0 @@
/*
* This file is part of Betaflight.
*
* Betaflight 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.
*
* 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 Betaflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
void bmp280SpiInit(void);
bool bmp280ReadRegister(uint8_t reg, uint8_t length, uint8_t *data);
bool bmp280WriteRegister(uint8_t reg, uint8_t data);
void bmp280_spi_start_up(void);
void bmp280_spi_get_up(void);

View file

@ -1,74 +0,0 @@
/*
* This file is part of INAV.
*
* INAV 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.
*
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/bus_spi.h"
#include "barometer.h"
#include "barometer_ms5611.h"
#ifdef USE_BARO_SPI_MS5611
#define DISABLE_MS5611 IOHi(ms5611CsPin)
#define ENABLE_MS5611 IOLo(ms5611CsPin)
static IO_t ms5611CsPin = IO_NONE;
bool ms5611SpiWriteCommand(uint8_t reg, uint8_t data)
{
ENABLE_MS5611;
spiTransferByte(MS5611_SPI_INSTANCE, reg & 0x7F);
spiTransferByte(MS5611_SPI_INSTANCE, data);
DISABLE_MS5611;
return true;
}
bool ms5611SpiReadCommand(uint8_t reg, uint8_t length, uint8_t *data)
{
ENABLE_MS5611;
spiTransferByte(MS5611_SPI_INSTANCE, reg | 0x80);
spiTransfer(MS5611_SPI_INSTANCE, data, NULL, length);
DISABLE_MS5611;
return true;
}
void ms5611SpiInit(void)
{
static bool hardwareInitialised = false;
if (hardwareInitialised) {
return;
}
ms5611CsPin = IOGetByTag(IO_TAG(MS5611_CS_PIN));
IOInit(ms5611CsPin, OWNER_BARO_CS, 0);
IOConfigGPIO(ms5611CsPin, IOCFG_OUT_PP);
DISABLE_MS5611;
spiSetDivisor(MS5611_SPI_INSTANCE, SPI_CLOCK_STANDARD);
hardwareInitialised = true;
}
#endif

View file

@ -22,20 +22,26 @@
#include "drivers/bus_i2c.h" #include "drivers/bus_i2c.h"
#include "drivers/io_types.h" #include "drivers/io_types.h"
typedef union busDevice_u { typedef struct busDevice_s {
struct deviceSpi_s { uint8_t bustype;
SPI_TypeDef *instance; union {
struct deviceSpi_s {
SPI_TypeDef *instance;
#if defined(USE_HAL_DRIVER) #if defined(USE_HAL_DRIVER)
SPI_HandleTypeDef* handle; // cached here for efficiency SPI_HandleTypeDef* handle; // cached here for efficiency
#endif #endif
IO_t csnPin; IO_t csnPin;
} spi; } spi;
struct deviceI2C_s { struct deviceI2C_s {
I2CDevice device; I2CDevice device;
uint8_t address; uint8_t address;
} i2c; } i2c;
} busdev_u;
} busDevice_t; } busDevice_t;
#define BUSTYPE_NONE 0
#define BUSTYPE_I2C 1
#define BUSTYPE_SPI 2
#ifdef TARGET_BUS_INIT #ifdef TARGET_BUS_INIT
void targetBusInit(void); void targetBusInit(void);

View file

@ -49,9 +49,9 @@ typedef enum I2CDevice {
#define I2C_CFG_TO_DEV(x) ((x) - 1) #define I2C_CFG_TO_DEV(x) ((x) - 1)
#define I2C_DEV_TO_CFG(x) ((x) + 1) #define I2C_DEV_TO_CFG(x) ((x) + 1)
// I2C device address range in 8-bit address mode // I2C device address range in 7-bit address mode
#define I2C_ADDR8_MIN 8 #define I2C_ADDR7_MIN 8
#define I2C_ADDR8_MAX 119 #define I2C_ADDR7_MAX 119
typedef struct i2cConfig_s { typedef struct i2cConfig_s {
ioTag_t ioTagScl[I2CDEV_COUNT]; ioTag_t ioTagScl[I2CDEV_COUNT];

View file

@ -0,0 +1,39 @@
/*
* 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>
#if defined(USE_I2C)
#include "drivers/bus_i2c.h"
#include "drivers/bus.h"
bool i2cReadRegisterBuffer(busDevice_t *busdev, uint8_t reg, uint8_t len, uint8_t *buffer)
{
return i2cRead(busdev->busdev_u.i2c.device, busdev->busdev_u.i2c.address, reg, len, buffer);
}
bool i2cWriteRegister(busDevice_t *busdev, uint8_t reg, uint8_t data)
{
return i2cWrite(busdev->busdev_u.i2c.device, busdev->busdev_u.i2c.address, reg, data);
}
#endif

View file

@ -1,22 +1,21 @@
/* /*
* This file is part of INAV. * This file is part of Cleanflight.
* *
* INAV is free software: you can redistribute it and/or modify * Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* INAV is distributed in the hope that it will be useful, * Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#pragma once #pragma once
void ms5611SpiInit(void); bool i2cReadRegisterBuffer(busDevice_t *busdev, uint8_t reg, uint8_t len, uint8_t *buffer);
bool ms5611SpiReadCommand(uint8_t reg, uint8_t length, uint8_t *data); bool i2cWriteRegister(busDevice_t *busdev, uint8_t reg, uint8_t data);
bool ms5611SpiWriteCommand(uint8_t reg, uint8_t data);

View file

@ -57,6 +57,15 @@ SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
return SPIINVALID; return SPIINVALID;
} }
SPI_TypeDef *spiInstanceByDevice(SPIDevice device)
{
if (device >= SPIDEV_COUNT) {
return NULL;
}
return spiDevice[device].dev;
}
void spiInitDevice(SPIDevice device) void spiInitDevice(SPIDevice device)
{ {
spiDevice_t *spi = &(spiDevice[device]); spiDevice_t *spi = &(spiDevice[device]);
@ -242,9 +251,9 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *rxData, const uint8_t *txData,
bool spiBusTransfer(const busDevice_t *bus, uint8_t *rxData, const uint8_t *txData, int length) bool spiBusTransfer(const busDevice_t *bus, uint8_t *rxData, const uint8_t *txData, int length)
{ {
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
spiTransfer(bus->spi.instance, rxData, txData, length); spiTransfer(bus->busdev_u.spi.instance, rxData, txData, length);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
return true; return true;
} }
@ -278,20 +287,20 @@ void spiResetErrorCounter(SPI_TypeDef *instance)
bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data) bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
{ {
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
spiTransferByte(bus->spi.instance, reg); spiTransferByte(bus->busdev_u.spi.instance, reg);
spiTransferByte(bus->spi.instance, data); spiTransferByte(bus->busdev_u.spi.instance, data);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
return true; return true;
} }
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)
{ {
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
spiTransferByte(bus->spi.instance, reg | 0x80); // read transaction spiTransferByte(bus->busdev_u.spi.instance, reg | 0x80); // read transaction
spiTransfer(bus->spi.instance, data, NULL, length); spiTransfer(bus->busdev_u.spi.instance, data, NULL, length);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
return true; return true;
} }
@ -299,16 +308,16 @@ bool spiReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t length,
uint8_t spiReadRegister(const busDevice_t *bus, uint8_t reg) uint8_t spiReadRegister(const busDevice_t *bus, uint8_t reg)
{ {
uint8_t data; uint8_t data;
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
spiTransferByte(bus->spi.instance, reg | 0x80); // read transaction spiTransferByte(bus->busdev_u.spi.instance, reg | 0x80); // read transaction
spiTransfer(bus->spi.instance, &data, NULL, 1); spiTransfer(bus->busdev_u.spi.instance, &data, NULL, 1);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
return data; return data;
} }
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance) void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance)
{ {
bus->spi.instance = instance; bus->busdev_u.spi.instance = instance;
} }
#endif #endif

View file

@ -82,6 +82,10 @@ typedef enum SPIDevice {
#endif #endif
// Macros to convert between CLI bus number and SPIDevice.
#define SPI_CFG_TO_DEV(x) ((x) - 1)
#define SPI_DEV_TO_CFG(x) ((x) + 1)
void spiPreInitCs(ioTag_t iotag); void spiPreInitCs(ioTag_t iotag);
bool spiInit(SPIDevice device); bool spiInit(SPIDevice device);
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor); void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor);
@ -93,6 +97,7 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *rxData, const uint8_t *txData,
uint16_t spiGetErrorCounter(SPI_TypeDef *instance); uint16_t spiGetErrorCounter(SPI_TypeDef *instance);
void spiResetErrorCounter(SPI_TypeDef *instance); void spiResetErrorCounter(SPI_TypeDef *instance);
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance); SPIDevice spiDeviceByInstance(SPI_TypeDef *instance);
SPI_TypeDef *spiInstanceByDevice(SPIDevice device);
bool spiBusTransfer(const busDevice_t *bus, uint8_t *rxData, const uint8_t *txData, int length); bool spiBusTransfer(const busDevice_t *bus, uint8_t *rxData, const uint8_t *txData, int length);

View file

@ -99,6 +99,15 @@ SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance)
return &spiDevice[spiDeviceByInstance(instance)].hspi; return &spiDevice[spiDeviceByInstance(instance)].hspi;
} }
SPI_TypeDef *spiInstanceByDevice(SPIDevice device)
{
if (device >= SPIDEV_COUNT) {
return NULL;
}
return spiDevice[device].dev;
}
DMA_HandleTypeDef* dmaHandleByInstance(SPI_TypeDef *instance) DMA_HandleTypeDef* dmaHandleByInstance(SPI_TypeDef *instance)
{ {
return &spiDevice[spiDeviceByInstance(instance)].hdma; return &spiDevice[spiDeviceByInstance(instance)].hdma;
@ -287,9 +296,9 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *rxData, const uint8_t *txData,
static bool spiBusReadBuffer(const busDevice_t *bus, uint8_t *out, int len) 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); const HAL_StatusTypeDef status = HAL_SPI_Receive(bus->busdev_u.spi.handle, out, len, SPI_DEFAULT_TIMEOUT);
if (status != HAL_OK) { if (status != HAL_OK) {
spiTimeoutUserCallback(bus->spi.instance); spiTimeoutUserCallback(bus->busdev_u.spi.instance);
} }
return true; return true;
} }
@ -306,20 +315,20 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t txByte)
// return uint8_t value or -1 when failure // return uint8_t value or -1 when failure
static uint8_t spiBusTransferByte(const busDevice_t *bus, uint8_t in) 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); const HAL_StatusTypeDef status = HAL_SPI_TransmitReceive(bus->busdev_u.spi.handle, &in, &in, 1, SPI_DEFAULT_TIMEOUT);
if (status != HAL_OK) { if (status != HAL_OK) {
spiTimeoutUserCallback(bus->spi.instance); spiTimeoutUserCallback(bus->busdev_u.spi.instance);
} }
return in; return in;
} }
bool spiBusTransfer(const busDevice_t *bus, uint8_t *rxData, const uint8_t *txData, int len) bool spiBusTransfer(const busDevice_t *bus, uint8_t *rxData, const uint8_t *txData, int len)
{ {
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
const HAL_StatusTypeDef status = HAL_SPI_TransmitReceive(bus->spi.handle, txData, rxData, len, SPI_DEFAULT_TIMEOUT); const HAL_StatusTypeDef status = HAL_SPI_TransmitReceive(bus->busdev_u.spi.handle, txData, rxData, len, SPI_DEFAULT_TIMEOUT);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
if (status != HAL_OK) { if (status != HAL_OK) {
spiTimeoutUserCallback(bus->spi.instance); spiTimeoutUserCallback(bus->busdev_u.spi.instance);
} }
return true; return true;
} }
@ -361,20 +370,20 @@ void spiResetErrorCounter(SPI_TypeDef *instance)
bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data) bool spiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
{ {
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
spiBusTransferByte(bus, reg); spiBusTransferByte(bus, reg);
spiBusTransferByte(bus, data); spiBusTransferByte(bus, data);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
return true; return true;
} }
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)
{ {
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
spiBusTransferByte(bus, reg | 0x80); // read transaction spiBusTransferByte(bus, reg | 0x80); // read transaction
spiBusReadBuffer(bus, data, length); spiBusReadBuffer(bus, data, length);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
return true; return true;
} }
@ -382,18 +391,18 @@ bool spiReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t length,
uint8_t spiReadRegister(const busDevice_t *bus, uint8_t reg) uint8_t spiReadRegister(const busDevice_t *bus, uint8_t reg)
{ {
uint8_t data; uint8_t data;
IOLo(bus->spi.csnPin); IOLo(bus->busdev_u.spi.csnPin);
spiBusTransferByte(bus, reg | 0x80); // read transaction spiBusTransferByte(bus, reg | 0x80); // read transaction
spiBusReadBuffer(bus, &data, 1); spiBusReadBuffer(bus, &data, 1);
IOHi(bus->spi.csnPin); IOHi(bus->busdev_u.spi.csnPin);
return data; return data;
} }
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance) void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance)
{ {
bus->spi.instance = instance; bus->busdev_u.spi.instance = instance;
bus->spi.handle = spiHandleByInstance(instance); bus->busdev_u.spi.handle = spiHandleByInstance(instance);
} }
void dmaSPIIRQHandler(dmaChannelDescriptor_t* descriptor) void dmaSPIIRQHandler(dmaChannelDescriptor_t* descriptor)

View file

@ -180,7 +180,7 @@ static const uint8_t multiWiiFont[][5] = { // Refer to "Times New Roman" Font Da
static bool i2c_OLED_send_cmd(busDevice_t *bus, uint8_t command) static bool i2c_OLED_send_cmd(busDevice_t *bus, uint8_t command)
{ {
return i2cWrite(bus->i2c.device, bus->i2c.address, 0x80, command); return i2cWrite(bus->busdev_u.i2c.device, bus->busdev_u.i2c.address, 0x80, command);
} }
static bool i2c_OLED_send_cmdarray(busDevice_t *bus, const uint8_t *commands, size_t len) static bool i2c_OLED_send_cmdarray(busDevice_t *bus, const uint8_t *commands, size_t len)
@ -196,7 +196,7 @@ static bool i2c_OLED_send_cmdarray(busDevice_t *bus, const uint8_t *commands, si
static bool i2c_OLED_send_byte(busDevice_t *bus, uint8_t val) static bool i2c_OLED_send_byte(busDevice_t *bus, uint8_t val)
{ {
return i2cWrite(bus->i2c.device, bus->i2c.address, 0x40, val); return i2cWrite(bus->busdev_u.i2c.device, bus->busdev_u.i2c.address, 0x40, val);
} }
void i2c_OLED_clear_display_quick(busDevice_t *bus) void i2c_OLED_clear_display_quick(busDevice_t *bus)

View file

@ -3041,6 +3041,9 @@ const cliResourceValue_t resourceTable[] = {
{ OWNER_ADC_CURR, PG_ADC_CONFIG, offsetof(adcConfig_t, current.ioTag), 0 }, { OWNER_ADC_CURR, PG_ADC_CONFIG, offsetof(adcConfig_t, current.ioTag), 0 },
{ OWNER_ADC_EXT, PG_ADC_CONFIG, offsetof(adcConfig_t, external1.ioTag), 0 }, { OWNER_ADC_EXT, PG_ADC_CONFIG, offsetof(adcConfig_t, external1.ioTag), 0 },
#endif #endif
#ifdef BARO
{ OWNER_BARO_CS, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_spi_csn), 0 },
#endif
}; };
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index) static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)

View file

@ -239,6 +239,10 @@ static const char * const lookupTableFailsafe[] = {
"AUTO-LAND", "DROP" "AUTO-LAND", "DROP"
}; };
static const char * const lookupTableBusType[] = {
"NONE", "I2C", "SPI"
};
const lookupTableEntry_t lookupTables[] = { const lookupTableEntry_t lookupTables[] = {
{ lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) }, { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
{ lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) }, { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
@ -284,6 +288,7 @@ const lookupTableEntry_t lookupTables[] = {
#ifdef USE_CAMERA_CONTROL #ifdef USE_CAMERA_CONTROL
{ lookupTableCameraControlMode, sizeof(lookupTableCameraControlMode) / sizeof(char *) }, { lookupTableCameraControlMode, sizeof(lookupTableCameraControlMode) / sizeof(char *) },
#endif #endif
{ lookupTableBusType, sizeof(lookupTableBusType) / sizeof(char *) },
}; };
const clivalue_t valueTable[] = { const clivalue_t valueTable[] = {
@ -329,6 +334,11 @@ const clivalue_t valueTable[] = {
// PG_BAROMETER_CONFIG // PG_BAROMETER_CONFIG
#ifdef BARO #ifdef BARO
{ "baro_bustype", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BUS_TYPE }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_bustype) },
{ "baro_spi_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 5 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_spi_device) },
{ "baro_i2c_device", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 5 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_i2c_device) },
{ "baro_i2c_address", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2C_ADDR7_MAX }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_i2c_address) },
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BARO_HARDWARE }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_hardware) }, { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BARO_HARDWARE }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_hardware) },
{ "baro_tab_size", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_sample_count) }, { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_sample_count) },
{ "baro_noise_lpf", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 1000 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_noise_lpf) }, { "baro_noise_lpf", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 1000 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_noise_lpf) },
@ -721,7 +731,7 @@ const clivalue_t valueTable[] = {
{ "led_inversion", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) }, { "led_inversion", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) },
#ifdef USE_DASHBOARD #ifdef USE_DASHBOARD
{ "dashboard_i2c_bus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2CDEV_COUNT }, PG_DASHBOARD_CONFIG, offsetof(dashboardConfig_t, device) }, { "dashboard_i2c_bus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, I2CDEV_COUNT }, PG_DASHBOARD_CONFIG, offsetof(dashboardConfig_t, device) },
{ "dashboard_i2c_addr", VAR_UINT8 | MASTER_VALUE, .config.minmax = { I2C_ADDR8_MIN, I2C_ADDR8_MAX }, PG_DASHBOARD_CONFIG, offsetof(dashboardConfig_t, address) }, { "dashboard_i2c_addr", VAR_UINT8 | MASTER_VALUE, .config.minmax = { I2C_ADDR7_MIN, I2C_ADDR7_MAX }, PG_DASHBOARD_CONFIG, offsetof(dashboardConfig_t, address) },
#endif #endif
// PG_CAMERA_CONTROL_CONFIG // PG_CAMERA_CONTROL_CONFIG

View file

@ -63,6 +63,7 @@ typedef enum {
#ifdef USE_CAMERA_CONTROL #ifdef USE_CAMERA_CONTROL
TABLE_CAMERA_CONTROL_MODE, TABLE_CAMERA_CONTROL_MODE,
#endif #endif
TABLE_BUS_TYPE,
LOOKUP_TABLE_COUNT LOOKUP_TABLE_COUNT
} lookupTableIndex_e; } lookupTableIndex_e;

View file

@ -677,8 +677,8 @@ void dashboardUpdate(timeUs_t currentTimeUs)
void dashboardInit(void) void dashboardInit(void)
{ {
static busDevice_t dashBoardBus; static busDevice_t dashBoardBus;
dashBoardBus.i2c.device = I2C_CFG_TO_DEV(dashboardConfig()->device); dashBoardBus.busdev_u.i2c.device = I2C_CFG_TO_DEV(dashboardConfig()->device);
dashBoardBus.i2c.address = dashboardConfig()->address; dashBoardBus.busdev_u.i2c.address = dashboardConfig()->address;
bus = &dashBoardBus; bus = &dashBoardBus;
delay(200); delay(200);

View file

@ -60,7 +60,7 @@
#include "flight/altitude.h" #include "flight/altitude.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "sensors/barometer.h" //#include "sensors/barometer.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "telemetry/jetiexbus.h" #include "telemetry/jetiexbus.h"
#endif //TELEMETRY #endif //TELEMETRY

View file

@ -26,6 +26,10 @@
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "config/parameter_group_ids.h" #include "config/parameter_group_ids.h"
#include "drivers/bus.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/barometer/barometer.h" #include "drivers/barometer/barometer.h"
#include "drivers/barometer/barometer_bmp085.h" #include "drivers/barometer/barometer_bmp085.h"
#include "drivers/barometer/barometer_bmp280.h" #include "drivers/barometer/barometer_bmp280.h"
@ -43,15 +47,61 @@
baro_t baro; // barometer access functions baro_t baro; // barometer access functions
PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 0); PG_REGISTER_WITH_RESET_FN(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 0);
PG_RESET_TEMPLATE(barometerConfig_t, barometerConfig, void pgResetFn_barometerConfig(barometerConfig_t *barometerConfig)
.baro_hardware = 1, {
.baro_sample_count = 21, barometerConfig->baro_sample_count = 21;
.baro_noise_lpf = 600, barometerConfig->baro_noise_lpf = 600;
.baro_cf_vel = 985, barometerConfig->baro_cf_vel = 985;
.baro_cf_alt = 965 barometerConfig->baro_cf_alt = 965;
); barometerConfig->baro_hardware = BARO_DEFAULT;
// For backward compatibility; ceate a valid default value for bus parameters
#ifdef USE_BARO_BMP085
barometerConfig->baro_bustype = BUSTYPE_I2C;
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(BARO_I2C_INSTANCE);
barometerConfig->baro_i2c_address = BMP085_I2C_ADDR;
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
barometerConfig->baro_spi_csn = IO_TAG_NONE;
#elif defined(USE_BARO_MS5611) || defined(USE_BARO_SPI_MS5611)
#if defined(USE_BARO_SPI_MS5611)
barometerConfig->baro_bustype = BUSTYPE_SPI;
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(spiDeviceByInstance(MS5611_SPI_INSTANCE));
barometerConfig->baro_spi_csn = IO_TAG(MS5611_CS_PIN);
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(I2CINVALID);
barometerConfig->baro_i2c_address = 0;
#else
barometerConfig->baro_bustype = BUSTYPE_I2C;
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(BARO_I2C_INSTANCE);
barometerConfig->baro_i2c_address = MS5611_I2C_ADDR;
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
barometerConfig->baro_spi_csn = IO_TAG_NONE;
#endif
#elif defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)
#if defined(USE_BARO_SPI_BMP280)
barometerConfig->baro_bustype = BUSTYPE_SPI;
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(spiDeviceByInstance(BMP280_SPI_INSTANCE));
barometerConfig->baro_spi_csn = IO_TAG(BMP280_CS_PIN);
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(I2CINVALID);
barometerConfig->baro_i2c_address = 0;
#else
barometerConfig->baro_bustype = BUSTYPE_I2C;
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(BARO_I2C_INSTANCE);
barometerConfig->baro_i2c_address = BMP280_I2C_ADDR;
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
barometerConfig->baro_spi_csn = IO_TAG_NONE;
#endif
#else
barometerConfig->baro_hardware = BARO_NONE;
barometerConfig->baro_bustype = BUSTYPE_NONE;
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(I2CINVALID);
barometerConfig->baro_i2c_address = 0;
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
barometerConfig->baro_spi_csn = IO_TAG_NONE;
#endif
}
#ifdef BARO #ifdef BARO
@ -69,42 +119,65 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
baroSensor_e baroHardware = baroHardwareToUse; baroSensor_e baroHardware = baroHardwareToUse;
#if !defined(USE_BARO_BMP085) && !defined(USE_BARO_MS5611) && !defined(USE_BARO_BMP280) && !defined(USE_BARO_SPI_BMP280) #if !defined(USE_BARO_BMP085) && !defined(USE_BARO_MS5611) && !defined(USE_BARO_SPI_MS5611) && !defined(USE_BARO_BMP280) && !defined(USE_BARO_SPI_BMP280)
UNUSED(dev); UNUSED(dev);
#endif #endif
#ifdef USE_BARO_BMP085 switch (barometerConfig()->baro_bustype) {
const bmp085Config_t *bmp085Config = NULL; case BUSTYPE_I2C:
#ifdef USE_I2C
#if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO) dev->busdev.bustype = BUSTYPE_I2C;
static const bmp085Config_t defaultBMP085Config = { dev->busdev.busdev_u.i2c.device = I2C_CFG_TO_DEV(barometerConfig()->baro_i2c_device);
.xclrIO = IO_TAG(BARO_XCLR_PIN), dev->busdev.busdev_u.i2c.address = barometerConfig()->baro_i2c_address;
.eocIO = IO_TAG(BARO_EOC_PIN),
};
bmp085Config = &defaultBMP085Config;
#endif #endif
break;
case BUSTYPE_SPI:
#ifdef USE_SPI
dev->busdev.bustype = BUSTYPE_SPI;
spiBusSetInstance(&dev->busdev, spiInstanceByDevice(SPI_CFG_TO_DEV(barometerConfig()->baro_spi_device)));
dev->busdev.busdev_u.spi.csnPin = IOGetByTag(barometerConfig()->baro_spi_csn);
#endif #endif
break;
default:
return false;
}
switch (baroHardware) { switch (baroHardware) {
case BARO_DEFAULT: case BARO_DEFAULT:
; // fallthough ; // fallthough
case BARO_BMP085: case BARO_BMP085:
#ifdef USE_BARO_BMP085 #ifdef USE_BARO_BMP085
if (bmp085Detect(bmp085Config, dev)) { {
baroHardware = BARO_BMP085; const bmp085Config_t *bmp085Config = NULL;
break;
#if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO)
static const bmp085Config_t defaultBMP085Config = {
.xclrIO = IO_TAG(BARO_XCLR_PIN),
.eocIO = IO_TAG(BARO_EOC_PIN),
};
bmp085Config = &defaultBMP085Config;
#endif
if (bmp085Detect(bmp085Config, dev)) {
baroHardware = BARO_BMP085;
break;
}
} }
#endif #endif
; // fallthough ; // fallthough
case BARO_MS5611: case BARO_MS5611:
#ifdef USE_BARO_MS5611 #if defined(USE_BARO_MS5611) || defined(USE_BARO_SPI_MS5611)
if (ms5611Detect(dev)) { if (ms5611Detect(dev)) {
baroHardware = BARO_MS5611; baroHardware = BARO_MS5611;
break; break;
} }
#endif #endif
; // fallthough ; // fallthough
case BARO_BMP280: case BARO_BMP280:
#if defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280) #if defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)
if (bmp280Detect(dev)) { if (bmp280Detect(dev)) {
@ -113,6 +186,7 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
} }
#endif #endif
; // fallthough ; // fallthough
case BARO_NONE: case BARO_NONE:
baroHardware = BARO_NONE; baroHardware = BARO_NONE;
break; break;
@ -206,15 +280,15 @@ uint32_t baroUpdate(void)
switch (state) { switch (state) {
default: default:
case BAROMETER_NEEDS_SAMPLES: case BAROMETER_NEEDS_SAMPLES:
baro.dev.get_ut(); baro.dev.get_ut(&baro.dev);
baro.dev.start_up(); baro.dev.start_up(&baro.dev);
state = BAROMETER_NEEDS_CALCULATION; state = BAROMETER_NEEDS_CALCULATION;
return baro.dev.up_delay; return baro.dev.up_delay;
break; break;
case BAROMETER_NEEDS_CALCULATION: case BAROMETER_NEEDS_CALCULATION:
baro.dev.get_up(); baro.dev.get_up(&baro.dev);
baro.dev.start_ut(); baro.dev.start_ut(&baro.dev);
baro.dev.calculate(&baroPressure, &baroTemperature); baro.dev.calculate(&baroPressure, &baroTemperature);
baroPressureSum = recalculateBarometerTotal(barometerConfig()->baro_sample_count, baroPressureSum, baroPressure); baroPressureSum = recalculateBarometerTotal(barometerConfig()->baro_sample_count, baroPressureSum, baroPressure);
state = BAROMETER_NEEDS_SAMPLES; state = BAROMETER_NEEDS_SAMPLES;

View file

@ -31,6 +31,11 @@ typedef enum {
#define BARO_SAMPLE_COUNT_MAX 48 #define BARO_SAMPLE_COUNT_MAX 48
typedef struct barometerConfig_s { typedef struct barometerConfig_s {
uint8_t baro_bustype;
uint8_t baro_spi_device;
ioTag_t baro_spi_csn; // Also used as XCLR (positive logic) for BMP085
uint8_t baro_i2c_device;
uint8_t baro_i2c_address;
uint8_t baro_hardware; // Barometer hardware to use uint8_t baro_hardware; // Barometer hardware to use
uint8_t baro_sample_count; // size of baro filter array uint8_t baro_sample_count; // size of baro filter array
uint16_t baro_noise_lpf; // additional LPF to reduce baro noise uint16_t baro_noise_lpf; // additional LPF to reduce baro noise

View file

@ -314,9 +314,9 @@ static bool gyroInitSensor(gyroSensor_t *gyroSensor)
#ifdef USE_DUAL_GYRO #ifdef USE_DUAL_GYRO
// set cnsPin using GYRO_n_CS_PIN defined in target.h // set cnsPin using GYRO_n_CS_PIN defined in target.h
gyroSensor->gyroDev.bus.spi.csnPin = gyroConfig()->gyro_to_use == 0 ? IOGetByTag(IO_TAG(GYRO_0_CS_PIN)) : IOGetByTag(IO_TAG(GYRO_1_CS_PIN)); gyroSensor->gyroDev.bus.busdev_u.spi.csnPin = gyroConfig()->gyro_to_use == 0 ? IOGetByTag(IO_TAG(GYRO_0_CS_PIN)) : IOGetByTag(IO_TAG(GYRO_1_CS_PIN));
#else #else
gyroSensor->gyroDev.bus.spi.csnPin = IO_NONE; // set cnsPin to IO_NONE so mpuDetect will set it according to value defined in target.h gyroSensor->gyroDev.bus.busdev_u.spi.csnPin = IO_NONE; // set cnsPin to IO_NONE so mpuDetect will set it according to value defined in target.h
#endif // USE_DUAL_GYRO #endif // USE_DUAL_GYRO
mpuDetect(&gyroSensor->gyroDev); mpuDetect(&gyroSensor->gyroDev);
mpuResetFn = gyroSensor->gyroDev.mpuConfiguration.resetFn; // must be set after mpuDetect mpuResetFn = gyroSensor->gyroDev.mpuConfiguration.resetFn; // must be set after mpuDetect

View file

@ -5,5 +5,4 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c
drivers/barometer/barometer_spi_bmp280.c

View file

@ -5,9 +5,7 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \
drivers/barometer/barometer_ms5611.c \ drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_spi_ms5611.c \
drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8963.c \
drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_spi_hmc5883l.c drivers/compass/compass_spi_hmc5883l.c

View file

@ -21,5 +21,4 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \
drivers/compass/compass_ak8963.c drivers/compass/compass_ak8963.c

View file

@ -6,5 +6,4 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \ drivers/max7456.c
drivers/max7456.c

View file

@ -6,6 +6,4 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c
drivers/barometer/barometer_spi_bmp280.c

View file

@ -17,6 +17,8 @@
#pragma once #pragma once
#undef TELEMETRY_JETIEXBUS // no space left
#define TARGET_BOARD_IDENTIFIER "FRF3" #define TARGET_BOARD_IDENTIFIER "FRF3"
#define TARGET_CONFIG #define TARGET_CONFIG
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE

View file

@ -5,7 +5,6 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \
drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8963.c \
drivers/compass/compass_ak8975.c \ drivers/compass/compass_ak8975.c \
drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_hmc5883l.c \

View file

@ -6,6 +6,5 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_ms5611.c \ drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \
drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_hmc5883l.c \
drivers/max7456.c drivers/max7456.c

View file

@ -5,7 +5,6 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \
drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8963.c \
drivers/compass/compass_ak8975.c \ drivers/compass/compass_ak8975.c \
drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_hmc5883l.c \

View file

@ -70,6 +70,11 @@
#define ACC_MPU6000_ALIGN CW180_DEG #define ACC_MPU6000_ALIGN CW180_DEG
#endif #endif
// XXX Temporary turn this off while bus code manipulation
#undef USE_DASHBOARD
#undef USE_I2C_OLED_DISPLAY
#if 0
// Support for iFlight OMNIBUS F4 V3 // Support for iFlight OMNIBUS F4 V3
// Has ICM20608 instead of MPU6000 // Has ICM20608 instead of MPU6000
// OMNIBUSF4SD is linked with both MPU6000 and MPU6500 drivers // OMNIBUSF4SD is linked with both MPU6000 and MPU6500 drivers
@ -81,6 +86,7 @@
#define GYRO_MPU6500_ALIGN GYRO_MPU6000_ALIGN #define GYRO_MPU6500_ALIGN GYRO_MPU6000_ALIGN
#define ACC_MPU6500_ALIGN ACC_MPU6000_ALIGN #define ACC_MPU6500_ALIGN ACC_MPU6000_ALIGN
#endif #endif
#endif
#define MAG #define MAG
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
@ -90,13 +96,15 @@
//#define MAG_NAZA_ALIGN CW180_DEG_FLIP // Ditto //#define MAG_NAZA_ALIGN CW180_DEG_FLIP // Ditto
#define BARO #define BARO
#define USE_BARO_MS5611
#if defined(OMNIBUSF4SD) #if defined(OMNIBUSF4SD)
#define USE_BARO_BMP280 #define USE_BARO_BMP280
#define USE_BARO_SPI_BMP280 #define USE_BARO_SPI_BMP280
#define BMP280_SPI_INSTANCE SPI3 #define BMP280_SPI_INSTANCE SPI3
#define BMP280_CS_PIN PB3 // v1 #define BMP280_CS_PIN PB3 // v1
#endif #endif
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define BARO_I2C_INSTANCE (I2CDEV_2)
#define OSD #define OSD
#define USE_MAX7456 #define USE_MAX7456
@ -186,15 +194,15 @@
#define USE_I2C #define USE_I2C
#define USE_I2C_DEVICE_2 #define USE_I2C_DEVICE_2
#define I2C2_SCL NONE // PB10, shared with UART3TX #define I2C2_SCL PB10 // PB10, shared with UART3TX
#define I2C2_SDA NONE // PB11, shared with UART3RX #define I2C2_SDA PB11 // PB11, shared with UART3RX
#if defined(OMNIBUSF4) || defined(OMNIBUSF4SD) #if defined(OMNIBUSF4) || defined(OMNIBUSF4SD)
#define USE_I2C_DEVICE_3 #define USE_I2C_DEVICE_3
#define I2C3_SCL NONE // PA8, PWM6 #define I2C3_SCL NONE // PA8, PWM6
#define I2C3_SDA NONE // PC9, CH6 #define I2C3_SDA NONE // PC9, CH6
#endif #endif
#define I2C_DEVICE (I2CDEV_2) #define I2C_DEVICE (I2CDEV_2)
#define OLED_I2C_INSTANCE (I2CDEV_3) #define OLED_I2C_INSTANCE (I2CDEV_2)
#define USE_ADC #define USE_ADC
#define CURRENT_METER_ADC_PIN PC1 // Direct from CRNT pad (part of onboard sensor for Pro) #define CURRENT_METER_ADC_PIN PC1 // Direct from CRNT pad (part of onboard sensor for Pro)

View file

@ -4,8 +4,8 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \ drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_hmc5883l.c \
drivers/max7456.c drivers/max7456.c

View file

@ -7,7 +7,6 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_spi_bmp280.c \
drivers/light_ws2811strip.c \ drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c \ drivers/light_ws2811strip_hal.c \
drivers/max7456.c drivers/max7456.c

View file

@ -39,3 +39,14 @@
#define USE_I2C_OLED_DISPLAY #define USE_I2C_OLED_DISPLAY
#endif #endif
#endif #endif
// XXX Remove USE_BARO_BMP280 and USE_BARO_MS5611 if USE_I2C is not defined.
// XXX This should go away buy editing relevant target.h files
#if !defined(USE_I2C)
#if defined(USE_BARO_BMP280)
#undef USE_BARO_BMP280
#endif
#if defined(USE_BARO_MS5611)
#undef USE_BARO_MS5611
#endif
#endif

View file

@ -36,10 +36,18 @@ baro_bmp085_unittest_SRC := \
baro_bmp280_unittest_SRC := \ baro_bmp280_unittest_SRC := \
$(USER_DIR)/drivers/barometer/barometer_bmp280.c $(USER_DIR)/drivers/barometer/barometer_bmp280.c
baro_bmp280_unittest_DEFINES := \
USE_BARO \
USE_BARO_BMP280 \
USE_BARO_SPI_BMP280
baro_ms5611_unittest_SRC := \ baro_ms5611_unittest_SRC := \
$(USER_DIR)/drivers/barometer/barometer_ms5611.c $(USER_DIR)/drivers/barometer/barometer_ms5611.c
baro_ms5611_unittest_DEFINES := \
USE_BARO \
USE_BARO_MS5611 \
USE_BARO_SPI_MS5611
battery_unittest_SRC := \ battery_unittest_SRC := \
$(USER_DIR)/sensors/battery.c \ $(USER_DIR)/sensors/battery.c \

View file

@ -140,12 +140,36 @@ extern "C" {
void delay(uint32_t) {} void delay(uint32_t) {}
bool i2cWrite(uint8_t, uint8_t, uint8_t) { bool i2cWriteRegister(uint8_t, uint8_t, uint8_t) {
return true; return true;
} }
bool i2cRead(uint8_t, uint8_t, uint8_t, uint8_t) { bool i2cReadRegisterBuffer(uint8_t, uint8_t, uint8_t, uint8_t) {
return true; return true;
} }
bool spiWriteRegister(uint8_t, uint8_t, uint8_t) {
return true;
}
bool spiReadRegisterBuffer(uint8_t, uint8_t, uint8_t, uint8_t) {
return true;
}
void spiSetDivisor() {
}
void IOConfigGPIO() {
}
void IOHi() {
}
void IOInit() {
}
void IORelease() {
}
} }

View file

@ -141,12 +141,35 @@ extern "C" {
void delay(uint32_t) {} void delay(uint32_t) {}
void delayMicroseconds(uint32_t) {} void delayMicroseconds(uint32_t) {}
bool i2cWrite(uint8_t, uint8_t, uint8_t) { bool i2cWriteRegister(uint8_t, uint8_t, uint8_t) {
return true; return true;
} }
bool i2cRead(uint8_t, uint8_t, uint8_t, uint8_t) { bool i2cReadRegisterBuffer(uint8_t, uint8_t, uint8_t, uint8_t) {
return true; return true;
} }
bool spiWriteRegister(uint8_t, uint8_t, uint8_t) {
return true;
}
bool spiReadRegisterBuffer(uint8_t, uint8_t, uint8_t, uint8_t) {
return true;
}
void spiSetDivisor() {
}
void IOConfigGPIO() {
}
void IOHi() {
}
void IOInit() {
}
void IORelease() {
}
} }