mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 22:05:17 +03:00
BMP388 - Add support for BMP388 barometer.
BMP388 - Move the static assert. BMP388 - Build faster when the baro driver is not enabled. BMP388 - Fix spi init due to changes in master. BMP388 - Add missing bmp388 unit test files. BMP388 - Remove debug code. BMP388 - Prepare EXTI/EOC handling for unified targets. BMP388 - enable on unified targets. BMP388 - Add support to NUCLEOF722. BMP388 - Add support to NUCLEOH743. BMP388 - Add BMP388 (via SPI) support to NUCLEOF7 * For some CI visibility on the conditional baro SPI code. NUCLEOH743 - Add LPS baro for more CI visibility. Remove whitespace, as requested. Move barometer `#defines` into the implementations. Cleanup style of method names in baro drivers.
This commit is contained in:
parent
aba49b39ae
commit
53167b161f
25 changed files with 842 additions and 169 deletions
|
@ -65,6 +65,15 @@ baro_bmp280_unittest_DEFINES := \
|
|||
USE_BARO_BMP280= \
|
||||
USE_BARO_SPI_BMP280=
|
||||
|
||||
baro_bmp388_unittest_SRC := \
|
||||
$(USER_DIR)/common/maths.c \
|
||||
$(USER_DIR)/drivers/barometer/barometer_bmp388.c
|
||||
|
||||
baro_bmp388_unittest_DEFINES := \
|
||||
USE_EXTI= \
|
||||
USE_BARO_BMP388= \
|
||||
USE_BARO_SPI_BMP388=
|
||||
|
||||
baro_ms5611_unittest_SRC := \
|
||||
$(USER_DIR)/drivers/barometer/barometer_ms5611.c
|
||||
|
||||
|
|
|
@ -23,7 +23,7 @@ extern "C" {
|
|||
#include "drivers/barometer/barometer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
void bmp280_calculate(int32_t *pressure, int32_t *temperature);
|
||||
void bmp280Calculate(int32_t *pressure, int32_t *temperature);
|
||||
|
||||
extern uint32_t bmp280_up;
|
||||
extern uint32_t bmp280_ut;
|
||||
|
@ -75,7 +75,7 @@ TEST(baroBmp280Test, TestBmp280Calculate)
|
|||
bmp280_cal.dig_P9 = 6000;
|
||||
|
||||
// when
|
||||
bmp280_calculate(&pressure, &temperature);
|
||||
bmp280Calculate(&pressure, &temperature);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(100653, pressure); // 100653 Pa
|
||||
|
@ -105,7 +105,7 @@ TEST(baroBmp280Test, TestBmp280CalculateHighP)
|
|||
bmp280_cal.dig_P9 = 6000;
|
||||
|
||||
// when
|
||||
bmp280_calculate(&pressure, &temperature);
|
||||
bmp280Calculate(&pressure, &temperature);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(135382, pressure); // 135385 Pa
|
||||
|
@ -135,7 +135,7 @@ TEST(baroBmp280Test, TestBmp280CalculateZeroP)
|
|||
bmp280_cal.dig_P9 = 6000;
|
||||
|
||||
// when
|
||||
bmp280_calculate(&pressure, &temperature);
|
||||
bmp280Calculate(&pressure, &temperature);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(0, pressure); // P1=0 trips pressure to 0 Pa, avoiding division by zero
|
||||
|
|
181
src/test/unit/baro_bmp388_unittest.cc
Normal file
181
src/test/unit/baro_bmp388_unittest.cc
Normal file
|
@ -0,0 +1,181 @@
|
|||
/*
|
||||
* 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 <stdint.h>
|
||||
|
||||
extern "C" {
|
||||
|
||||
#include "platform.h"
|
||||
#include "target.h"
|
||||
#include "drivers/barometer/barometer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
void bmp388Calculate(int32_t *pressure, int32_t *temperature);
|
||||
|
||||
extern uint32_t bmp388_up;
|
||||
extern uint32_t bmp388_ut;
|
||||
extern int64_t t_lin; // when temperature is calculated this is updated, the result is used in the pressure calculations
|
||||
|
||||
typedef struct bmp388_calib_param_s {
|
||||
uint16_t T1;
|
||||
uint16_t T2;
|
||||
int8_t T3;
|
||||
int16_t P1;
|
||||
int16_t P2;
|
||||
int8_t P3;
|
||||
int8_t P4;
|
||||
uint16_t P5;
|
||||
uint16_t P6;
|
||||
int8_t P7;
|
||||
int8_t P8;
|
||||
int16_t P9;
|
||||
int8_t P10;
|
||||
int8_t P11;
|
||||
} __attribute__((packed)) bmp388_calib_param_t; // packed as we read directly from the device into this structure.
|
||||
|
||||
bmp388_calib_param_t bmp388_cal;
|
||||
|
||||
} // extern "C"
|
||||
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
void baroBmp388ConfigureZeroCalibration(void)
|
||||
{
|
||||
bmp388_cal = {
|
||||
.T1 = 0,
|
||||
.T2 = 0,
|
||||
.T3 = 0,
|
||||
.P1 = 0,
|
||||
.P2 = 0,
|
||||
.P3 = 0,
|
||||
.P4 = 0,
|
||||
.P5 = 0,
|
||||
.P6 = 0,
|
||||
.P7 = 0,
|
||||
.P8 = 0,
|
||||
.P9 = 0,
|
||||
.P10 = 0,
|
||||
.P11 = 0
|
||||
};
|
||||
}
|
||||
|
||||
void baroBmp388ConfigureSampleCalibration(void)
|
||||
{
|
||||
bmp388_cal = {
|
||||
.T1 = 27772,
|
||||
.T2 = 18638,
|
||||
.T3 = -10,
|
||||
.P1 = 878,
|
||||
.P2 = -2023,
|
||||
.P3 = 35,
|
||||
.P4 = 0,
|
||||
.P5 = 24476,
|
||||
.P6 = 30501,
|
||||
.P7 = -13,
|
||||
.P8 = -10,
|
||||
.P9 = 16545,
|
||||
.P10 = 21,
|
||||
.P11 = -60
|
||||
};
|
||||
}
|
||||
|
||||
TEST(baroBmp388Test, TestBmp388CalculateWithZeroCalibration)
|
||||
{
|
||||
// given
|
||||
int32_t pressure, temperature;
|
||||
bmp388_up = 0; // uncompensated pressure value
|
||||
bmp388_ut = 0; // uncompensated temperature value
|
||||
t_lin = 0;
|
||||
|
||||
// and
|
||||
baroBmp388ConfigureZeroCalibration();
|
||||
|
||||
// when
|
||||
bmp388Calculate(&pressure, &temperature);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(0, temperature);
|
||||
EXPECT_EQ(0, t_lin);
|
||||
|
||||
// and
|
||||
EXPECT_EQ(0, pressure);
|
||||
}
|
||||
|
||||
TEST(baroBmp388Test, TestBmp388CalculateWithSampleCalibration)
|
||||
{
|
||||
// given
|
||||
int32_t pressure, temperature;
|
||||
bmp388_up = 7323488; // uncompensated pressure value
|
||||
bmp388_ut = 9937920; // uncompensated temperature value
|
||||
t_lin = 0;
|
||||
|
||||
// and
|
||||
baroBmp388ConfigureSampleCalibration();
|
||||
|
||||
// when
|
||||
bmp388Calculate(&pressure, &temperature);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(4880, temperature); // 48.80 degrees C
|
||||
EXPECT_NE(0, t_lin);
|
||||
|
||||
// and
|
||||
EXPECT_EQ(39535, pressure); // 39535 Pa
|
||||
}
|
||||
|
||||
// STUBS
|
||||
|
||||
extern "C" {
|
||||
|
||||
void delay(uint32_t) {}
|
||||
bool busReadRegisterBuffer(const busDevice_t*, uint8_t, uint8_t*, uint8_t) {return true;}
|
||||
bool busWriteRegister(const busDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
|
||||
void spiBusSetDivisor() {
|
||||
}
|
||||
|
||||
void spiBusTransactionInit() {
|
||||
}
|
||||
|
||||
void spiPreinitByIO(IO_t) {
|
||||
}
|
||||
|
||||
void IOConfigGPIO() {
|
||||
}
|
||||
|
||||
void IOHi() {
|
||||
}
|
||||
|
||||
IO_t IOGetByTag(ioTag_t) {
|
||||
return IO_NONE;
|
||||
}
|
||||
|
||||
void IOInit() {
|
||||
}
|
||||
|
||||
void EXTIHandlerInit(extiCallbackRec_t *, extiHandlerCallback *) {
|
||||
}
|
||||
|
||||
void EXTIConfig(IO_t, extiCallbackRec_t *, int, ioConfig_t, extiTrigger_t) {
|
||||
}
|
||||
|
||||
void EXTIEnable(IO_t, bool) {
|
||||
}
|
||||
|
||||
|
||||
} // extern "C"
|
|
@ -23,8 +23,8 @@ extern "C" {
|
|||
#include "drivers/barometer/barometer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
int8_t ms5611_crc(uint16_t *prom);
|
||||
void ms5611_calculate(int32_t *pressure, int32_t *temperature);
|
||||
int8_t ms5611CRC(uint16_t *prom);
|
||||
void ms5611Calculate(int32_t *pressure, int32_t *temperature);
|
||||
|
||||
extern uint16_t ms5611_c[8];
|
||||
extern uint32_t ms5611_up;
|
||||
|
@ -40,10 +40,10 @@ extern uint32_t ms5611_ut;
|
|||
TEST(baroMS5611Test, TestValidMs5611Crc)
|
||||
{
|
||||
// given
|
||||
uint16_t ms5611_prom[] = {0x3132,0x3334,0x3536,0x3738,0x3940,0x4142,0x4344,0x450B};
|
||||
uint16_t ms5611Prom[] = {0x3132,0x3334,0x3536,0x3738,0x3940,0x4142,0x4344,0x450B};
|
||||
|
||||
// when
|
||||
int8_t result = ms5611_crc(ms5611_prom);
|
||||
int8_t result = ms5611CRC(ms5611Prom);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(0, result);
|
||||
|
@ -52,10 +52,10 @@ TEST(baroMS5611Test, TestValidMs5611Crc)
|
|||
TEST(baroMS5611Test, TestInvalidMs5611Crc)
|
||||
{
|
||||
// given
|
||||
uint16_t ms5611_prom[] = {0x3132,0x3334,0x3536,0x3738,0x3940,0x4142,0x4344,0x4500};
|
||||
uint16_t ms5611Prom[] = {0x3132,0x3334,0x3536,0x3738,0x3940,0x4142,0x4344,0x4500};
|
||||
|
||||
// when
|
||||
int8_t result = ms5611_crc(ms5611_prom);
|
||||
int8_t result = ms5611CRC(ms5611Prom);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(-1, result);
|
||||
|
@ -64,10 +64,10 @@ TEST(baroMS5611Test, TestInvalidMs5611Crc)
|
|||
TEST(baroMS5611Test, TestMs5611AllZeroProm)
|
||||
{
|
||||
// given
|
||||
uint16_t ms5611_prom[] = {0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000};
|
||||
uint16_t ms5611Prom[] = {0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000,0x0000};
|
||||
|
||||
// when
|
||||
int8_t result = ms5611_crc(ms5611_prom);
|
||||
int8_t result = ms5611CRC(ms5611Prom);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(-1, result);
|
||||
|
@ -76,10 +76,10 @@ TEST(baroMS5611Test, TestMs5611AllZeroProm)
|
|||
TEST(baroMS5611Test, TestMs5611AllOnesProm)
|
||||
{
|
||||
// given
|
||||
uint16_t ms5611_prom[] = {0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF};
|
||||
uint16_t ms5611Prom[] = {0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF};
|
||||
|
||||
// when
|
||||
int8_t result = ms5611_crc(ms5611_prom);
|
||||
int8_t result = ms5611CRC(ms5611Prom);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(-1, result);
|
||||
|
@ -96,7 +96,7 @@ TEST(baroMS5611Test, TestMs5611CalculatePressureGT20Deg)
|
|||
ms5611_ut = 8569150; // Digital temperature value from MS5611 datasheet
|
||||
|
||||
// when
|
||||
ms5611_calculate(&pressure, &temperature);
|
||||
ms5611Calculate(&pressure, &temperature);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(2007, temperature); // 20.07 deg C
|
||||
|
@ -114,7 +114,7 @@ TEST(baroMS5611Test, TestMs5611CalculatePressureLT20Deg)
|
|||
ms5611_ut = 8069150; // Digital temperature value
|
||||
|
||||
// when
|
||||
ms5611_calculate(&pressure, &temperature);
|
||||
ms5611Calculate(&pressure, &temperature);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(205, temperature); // 2.05 deg C
|
||||
|
@ -132,7 +132,7 @@ TEST(baroMS5611Test, TestMs5611CalculatePressureLTMinus15Deg)
|
|||
ms5611_ut = 7369150; // Digital temperature value
|
||||
|
||||
// when
|
||||
ms5611_calculate(&pressure, &temperature);
|
||||
ms5611Calculate(&pressure, &temperature);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(-2710, temperature); // -27.10 deg C
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue