1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-13 03:20:00 +03:00

Fix bmp388 spi (and add BMP390) (#13458)

* Fix BMP388-SPI

SPI read returns dummy byte first when reading. Discard this byte on
SPI reads

* BMP388 - add supprot for BMP390

* fixup! Fix BMP388-SPI

---------

Co-authored-by: Petr Ledvina <ledvinap@hp124.ekotip.cz>
This commit is contained in:
Petr Ledvina 2024-03-19 11:11:53 +01:00 committed by GitHub
parent 84d54051f1
commit 0f109c8d0b
No known key found for this signature in database
GPG key ID: B5690EEEBB952194

View file

@ -23,6 +23,7 @@
#include <math.h>
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
@ -47,7 +48,8 @@
#define BMP388_MAX_SPI_CLK_HZ 10000000
#define BMP388_I2C_ADDR (0x76) // same as BMP280/BMP180
#define BMP388_DEFAULT_CHIP_ID (0x50) // from https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h#L130
#define BMP388_CHIP_ID_BMP3 (0x50) // from https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h#L130
#define BMP388_CHIP_ID_BMP390 (0x60) // from https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h#L133
#define BMP388_CMD_REG (0x7E)
#define BMP388_RESERVED_UPPER_REG (0x7D)
@ -165,7 +167,10 @@ STATIC_UNIT_TESTED bmp388_calib_param_t bmp388_cal;
// uncompensated pressure and temperature
uint32_t bmp388_up = 0;
uint32_t bmp388_ut = 0;
static DMA_DATA_ZERO_INIT uint8_t sensor_data[BMP388_DATA_FRAME_SIZE];
// make space for dummy SPI byte
static DMA_DATA_ZERO_INIT uint8_t sensor_data_buffer[BMP388_DATA_FRAME_SIZE + 1];
static uint8_t * sensor_data = sensor_data_buffer;
STATIC_UNIT_TESTED int64_t t_lin = 0;
@ -178,6 +183,22 @@ static bool bmp388ReadUP(baroDev_t *baro);
STATIC_UNIT_TESTED void bmp388Calculate(int32_t *pressure, int32_t *temperature);
static bool bmp388ReadRegisterBuffer(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t length)
{
if (dev->bus->busType == BUS_TYPE_SPI) {
// dummy byte is returned first on BMP3xx read
uint8_t buf[length + 1];
bool ret = busReadRegisterBuffer(dev, reg, buf, length + 1);
if (ret) {
memcpy(data, buf + 1, length);
}
return ret;
} else {
return busReadRegisterBuffer(dev, reg, data, length);
}
}
void bmp388_extiHandler(extiCallbackRec_t* cb)
{
#ifdef DEBUG
@ -189,7 +210,7 @@ void bmp388_extiHandler(extiCallbackRec_t* cb)
baroDev_t *baro = container_of(cb, baroDev_t, exti);
uint8_t intStatus = 0;
busReadRegisterBuffer(&baro->dev, BMP388_INT_STATUS_REG, &intStatus, 1);
bmp388ReadRegisterBuffer(&baro->dev, BMP388_INT_STATUS_REG, &intStatus, 1);
}
void bmp388BusInit(const extDevice_t *dev)
@ -246,10 +267,14 @@ bool bmp388Detect(const bmp388Config_t *config, baroDev_t *baro)
dev->busType_u.i2c.address = BMP388_I2C_ADDR;
defaultAddressApplied = true;
}
if (dev->bus->busType == BUS_TYPE_SPI) {
// dummy byte is returned first on BMP3xx read
sensor_data = sensor_data_buffer + 1;
}
busReadRegisterBuffer(dev, BMP388_CHIP_ID_REG, &bmp388_chip_id, 1);
bmp388ReadRegisterBuffer(dev, BMP388_CHIP_ID_REG, &bmp388_chip_id, 1);
if (bmp388_chip_id != BMP388_DEFAULT_CHIP_ID) {
if (bmp388_chip_id != BMP388_CHIP_ID_BMP3 && bmp388_chip_id != BMP388_CHIP_ID_BMP390) {
bmp388BusDeinit(dev);
if (defaultAddressApplied) {
dev->busType_u.i2c.address = 0;
@ -270,7 +295,7 @@ bool bmp388Detect(const bmp388Config_t *config, baroDev_t *baro)
}
// read calibration
busReadRegisterBuffer(dev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, (uint8_t *)&bmp388_cal, sizeof(bmp388_calib_param_t));
bmp388ReadRegisterBuffer(dev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, (uint8_t *)&bmp388_cal, sizeof(bmp388_calib_param_t));
// set oversampling
@ -336,8 +361,7 @@ static bool bmp388ReadUP(baroDev_t *baro)
}
// read data from sensor
busReadRegisterBufferStart(&baro->dev, BMP388_DATA_0_REG, sensor_data, BMP388_DATA_FRAME_SIZE);
busReadRegisterBufferStart(&baro->dev, BMP388_DATA_0_REG, sensor_data_buffer, BMP388_DATA_FRAME_SIZE + (sensor_data - sensor_data_buffer));
return true;
}