Skip to content

Commit

Permalink
Introduce BMP390 support
Browse files Browse the repository at this point in the history
No need to discern between them besides the printouts.
  • Loading branch information
gemenerik committed Apr 3, 2024
1 parent 3d5129f commit 81decdf
Show file tree
Hide file tree
Showing 16 changed files with 152 additions and 126 deletions.
22 changes: 11 additions & 11 deletions Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -66,21 +66,21 @@ choice

config PLATFORM_CF2
bool "Build for CF2"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
select SENSORS_MPU9250_LPS25H

config PLATFORM_BOLT
bool "Build for Bolt"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
select SENSORS_BMI088_SPI

config PLATFORM_TAG
bool "Build for the roadrunner"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX

config PLATFORM_FLAPPER
bool "Build for Flapper Nimble+"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
select SENSORS_BMI088_SPI

endchoice
Expand Down Expand Up @@ -125,15 +125,15 @@ config SENSORS_MPU9250_LPS25H
bool "Support for mpu9250 and lps25h sensors"
default n
help
Include support for the Bosch bmi088 inertial and bmp388
Include support for the Bosch bmi088 inertial and bmp3xx
barometric sensors

config SENSORS_BMI088_BMP388
bool "Support for bmi088 and bmp388 sensors"
config SENSORS_BMI088_BMP3XX
bool "Support for bmi088 and bmp3xx sensors"
default n
select SENSORS_BMI088_I2C
help
Include support for the Bosch bmi088 inertial and bmp388
Include support for the Bosch bmi088 inertial and bmp3xx
barometric sensors

config SENSORS_BOSCH
Expand All @@ -142,19 +142,19 @@ config SENSORS_BOSCH

config SENSORS_IGNORE_BAROMETER_FAIL
bool "Ignore failure from barometer"
depends on SENSORS_BMI088_BMP388
depends on SENSORS_BMI088_BMP3XX
default n

config SENSORS_BMI088_SPI
bool "Support for SPI communincation with the bmi088 sensor"
depends on SENSORS_BMI088_BMP388
depends on SENSORS_BMI088_BMP3XX
default n
help
Include support using SPI with the Bosch bmi088 inertial sensor

config SENSORS_BMI088_I2C
bool "Support for I2C communincation with the bmi088 sensor"
depends on SENSORS_BMI088_BMP388
depends on SENSORS_BMI088_BMP3XX
default n
help
Include support using I2C with the Bosch bmi088 inertial sensor
Expand Down
16 changes: 8 additions & 8 deletions docs/development/create_platform.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,17 +27,17 @@ choice
config PLATFORM_CF2
bool "Build for CF2"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
select SENSORS_MPU9250_LPS25H
config PLATFORM_BOLT
bool "Build for Bolt"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
select SENSORS_BMI088_SPI
config PLATFORM_TAG
bool "Build for the roadrunner"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
endchoice
```
Expand All @@ -53,21 +53,21 @@ choice
config PLATFORM_CF2
bool "Build for CF2"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
select SENSORS_MPU9250_LPS25H
config PLATFORM_BOLT
bool "Build for Bolt"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
select SENSORS_BMI088_SPI
config PLATFORM_TAG
bool "Build for the roadrunner"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
config PLATFORM_RINCEWIND
bool "Build for the Rincewind platform"
select SENSORS_BMI088_BMP388
select SENSORS_BMI088_BMP3XX
select SENSORS_BMI088_SPI
endchoice
Expand Down Expand Up @@ -116,7 +116,7 @@ static platformConfig_t configs[] = {
{
.deviceType = "CB10",
.deviceTypeName = "Rincewind",
.sensorImplementation = SensorImplementation_bmi088_spi_bmp388,
.sensorImplementation = SensorImplementation_bmi088_spi_bmp3xx,
.physicalLayoutAntennasAreClose = false,
.motorMap = motorMapBoltBrushless,
}
Expand Down
2 changes: 1 addition & 1 deletion docs/development/kbuild.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ CONFIG_PLATFORM_CF2=y
# Sensor configuration
#
CONFIG_SENSORS_MPU9250_LPS25H=y
CONFIG_SENSORS_BMI088_BMP388=y
CONFIG_SENSORS_BMI088_BMP3XX=y
[...]
```

Expand Down
1 change: 1 addition & 0 deletions src/drivers/bosch/interface/bmp3.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@
/* Header includes */
#include "bmp3_defs.h"

extern uint8_t bmp3_chip_id;

/*!
* @brief This API is the entry point.
Expand Down
3 changes: 2 additions & 1 deletion src/drivers/bosch/interface/bmp3_defs.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,8 @@
#define BMP3_I2C_ADDR_SEC UINT8_C(0x77)

/**\name BMP3 chip identifier */
#define BMP3_CHIP_ID UINT8_C(0x50)
#define BMP388_CHIP_ID UINT8_C(0x50)
#define BMP390_CHIP_ID UINT8_C(0x60)
/**\name BMP3 pressure settling time (micro secs)*/
#define BMP3_PRESS_SETTLE_TIME UINT16_C(392)
/**\name BMP3 temperature settling time (micro secs) */
Expand Down
11 changes: 10 additions & 1 deletion src/drivers/bosch/src/bmp3.c
Original file line number Diff line number Diff line change
Expand Up @@ -694,6 +694,8 @@ static int8_t get_err_status(struct bmp3_dev *dev);
*/
static int8_t convert_frames_to_bytes(uint16_t *watermark_len, const struct bmp3_dev *dev);

uint8_t bmp3_chip_id = 0;

/****************** Global Function Definitions *******************************/
/*!
* @brief This API is the entry point.
Expand Down Expand Up @@ -723,7 +725,14 @@ int8_t bmp3_init(struct bmp3_dev *dev)
/* Proceed if everything is fine until now */
if (rslt == BMP3_OK) {
/* Check for chip id validity */
if (chip_id == BMP3_CHIP_ID) {
if (chip_id == BMP388_CHIP_ID) {
bmp3_chip_id = BMP388_CHIP_ID;
}
else if (chip_id == BMP390_CHIP_ID) {
bmp3_chip_id = BMP390_CHIP_ID;
}

if (bmp3_chip_id){
dev->chip_id = chip_id;
/* Reset the sensor */
rslt = bmp3_soft_reset(dev);
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/src/uart1.c
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include "nvicconf.h"
#include "static_mem.h"

/** This uart is conflicting with SPI2 DMA used in sensors_bmi088_spi_bmp388.c
/** This uart is conflicting with SPI2 DMA used in sensors_bmi088_spi_bmp3xx.c
* which is used in CF-Bolt. So for other products this can be enabled.
*/
//#define ENABLE_UART1_DMA
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,23 +23,23 @@
*
*/

#ifndef __SENSORS_BMI088_BMP388_H__
#define __SENSORS_BMI088_BMP388_H__
#ifndef __SENSORS_BMI088_BMP3XX_H__
#define __SENSORS_BMI088_BMP3XX_H__

#include "sensors.h"

void sensorsBmi088Bmp388Init_I2C(void);
void sensorsBmi088Bmp388Init_SPI(void);
bool sensorsBmi088Bmp388Test(void);
bool sensorsBmi088Bmp388AreCalibrated(void);
bool sensorsBmi088Bmp388ManufacturingTest(void);
void sensorsBmi088Bmp388Acquire(sensorData_t *sensors);
void sensorsBmi088Bmp388WaitDataReady(void);
bool sensorsBmi088Bmp388ReadGyro(Axis3f *gyro);
bool sensorsBmi088Bmp388ReadAcc(Axis3f *acc);
bool sensorsBmi088Bmp388ReadMag(Axis3f *mag);
bool sensorsBmi088Bmp388ReadBaro(baro_t *baro);
void sensorsBmi088Bmp388SetAccMode(accModes accMode);
void sensorsBmi088Bmp388DataAvailableCallback(void);
void sensorsBmi088Bmp3xxInit_I2C(void);
void sensorsBmi088Bmp3xxInit_SPI(void);
bool sensorsBmi088Bmp3xxTest(void);
bool sensorsBmi088Bmp3xxAreCalibrated(void);
bool sensorsBmi088Bmp3xxManufacturingTest(void);
void sensorsBmi088Bmp3xxAcquire(sensorData_t *sensors);
void sensorsBmi088Bmp3xxWaitDataReady(void);
bool sensorsBmi088Bmp3xxReadGyro(Axis3f *gyro);
bool sensorsBmi088Bmp3xxReadAcc(Axis3f *acc);
bool sensorsBmi088Bmp3xxReadMag(Axis3f *mag);
bool sensorsBmi088Bmp3xxReadBaro(baro_t *baro);
void sensorsBmi088Bmp3xxSetAccMode(accModes accMode);
void sensorsBmi088Bmp3xxDataAvailableCallback(void);

#endif // __SENSORS_BMI088_BMP388_H__
#endif // __SENSORS_BMI088_BMP3XX_H__
2 changes: 1 addition & 1 deletion src/hal/src/Kbuild
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ obj-y += pca95x4.o
obj-y += pm_stm32f4.o
obj-y += proximity.o
obj-y += radiolink.o
obj-$(CONFIG_SENSORS_BMI088_BMP388) += sensors_bmi088_bmp388.o
obj-$(CONFIG_SENSORS_BMI088_BMP3XX) += sensors_bmi088_bmp3xx.o
obj-$(CONFIG_SENSORS_BMI088_I2C) += sensors_bmi088_i2c.o
obj-$(CONFIG_SENSORS_BMI088_SPI) += sensors_bmi088_spi.o
obj-$(CONFIG_SENSORS_BOSCH) += sensors_bosch.o
Expand Down
58 changes: 29 additions & 29 deletions src/hal/src/sensors.c
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#define xstr(s) str(s)
#define str(s) #s

#if defined(CONFIG_SENSORS_BMI088_BMP388) || defined(CONFIG_SENSORS_BMI088_SPI)
#include "sensors_bmi088_bmp388.h"
#if defined(CONFIG_SENSORS_BMI088_BMP3XX) || defined(CONFIG_SENSORS_BMI088_SPI)
#include "sensors_bmi088_bmp3xx.h"
#endif

#ifdef CONFIG_SENSORS_MPU9250_LPS25H
Expand Down Expand Up @@ -72,38 +72,38 @@ static void nullFunction(void) {}
#pragma GCC diagnostic pop

static const sensorsImplementation_t sensorImplementations[SensorImplementation_COUNT] = {
#ifdef CONFIG_SENSORS_BMI088_BMP388
#ifdef CONFIG_SENSORS_BMI088_BMP3XX
{
.implements = SensorImplementation_bmi088_bmp388,
.init = sensorsBmi088Bmp388Init_I2C,
.test = sensorsBmi088Bmp388Test,
.areCalibrated = sensorsBmi088Bmp388AreCalibrated,
.manufacturingTest = sensorsBmi088Bmp388ManufacturingTest,
.acquire = sensorsBmi088Bmp388Acquire,
.waitDataReady = sensorsBmi088Bmp388WaitDataReady,
.readGyro = sensorsBmi088Bmp388ReadGyro,
.readAcc = sensorsBmi088Bmp388ReadAcc,
.readMag = sensorsBmi088Bmp388ReadMag,
.readBaro = sensorsBmi088Bmp388ReadBaro,
.setAccMode = sensorsBmi088Bmp388SetAccMode,
.dataAvailableCallback = sensorsBmi088Bmp388DataAvailableCallback,
.implements = SensorImplementation_bmi088_bmp3xx,
.init = sensorsBmi088Bmp3xxInit_I2C,
.test = sensorsBmi088Bmp3xxTest,
.areCalibrated = sensorsBmi088Bmp3xxAreCalibrated,
.manufacturingTest = sensorsBmi088Bmp3xxManufacturingTest,
.acquire = sensorsBmi088Bmp3xxAcquire,
.waitDataReady = sensorsBmi088Bmp3xxWaitDataReady,
.readGyro = sensorsBmi088Bmp3xxReadGyro,
.readAcc = sensorsBmi088Bmp3xxReadAcc,
.readMag = sensorsBmi088Bmp3xxReadMag,
.readBaro = sensorsBmi088Bmp3xxReadBaro,
.setAccMode = sensorsBmi088Bmp3xxSetAccMode,
.dataAvailableCallback = sensorsBmi088Bmp3xxDataAvailableCallback,
},
#endif
#ifdef CONFIG_SENSORS_BMI088_SPI
{
.implements = SensorImplementation_bmi088_spi_bmp388,
.init = sensorsBmi088Bmp388Init_SPI,
.test = sensorsBmi088Bmp388Test,
.areCalibrated = sensorsBmi088Bmp388AreCalibrated,
.manufacturingTest = sensorsBmi088Bmp388ManufacturingTest,
.acquire = sensorsBmi088Bmp388Acquire,
.waitDataReady = sensorsBmi088Bmp388WaitDataReady,
.readGyro = sensorsBmi088Bmp388ReadGyro,
.readAcc = sensorsBmi088Bmp388ReadAcc,
.readMag = sensorsBmi088Bmp388ReadMag,
.readBaro = sensorsBmi088Bmp388ReadBaro,
.setAccMode = sensorsBmi088Bmp388SetAccMode,
.dataAvailableCallback = sensorsBmi088Bmp388DataAvailableCallback,
.implements = SensorImplementation_bmi088_spi_bmp3xx,
.init = sensorsBmi088Bmp3xxInit_SPI,
.test = sensorsBmi088Bmp3xxTest,
.areCalibrated = sensorsBmi088Bmp3xxAreCalibrated,
.manufacturingTest = sensorsBmi088Bmp3xxManufacturingTest,
.acquire = sensorsBmi088Bmp3xxAcquire,
.waitDataReady = sensorsBmi088Bmp3xxWaitDataReady,
.readGyro = sensorsBmi088Bmp3xxReadGyro,
.readAcc = sensorsBmi088Bmp3xxReadAcc,
.readMag = sensorsBmi088Bmp3xxReadMag,
.readBaro = sensorsBmi088Bmp3xxReadBaro,
.setAccMode = sensorsBmi088Bmp3xxSetAccMode,
.dataAvailableCallback = sensorsBmi088Bmp3xxDataAvailableCallback,
},
#endif
#ifdef CONFIG_SENSORS_MPU9250_LPS25H
Expand Down
Loading

0 comments on commit 81decdf

Please sign in to comment.