2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
23 #include "drivers/barometer/barometer.h"
24 #include "drivers/bus.h"
26 void bmp388Calculate(int32_t *pressure
, int32_t *temperature
);
28 extern uint32_t bmp388_up
;
29 extern uint32_t bmp388_ut
;
30 extern int64_t t_lin
; // when temperature is calculated this is updated, the result is used in the pressure calculations
32 typedef struct bmp388_calib_param_s
{
47 } __attribute__((packed
)) bmp388_calib_param_t
; // packed as we read directly from the device into this structure.
49 bmp388_calib_param_t bmp388_cal
;
54 #include "unittest_macros.h"
55 #include "gtest/gtest.h"
57 void baroBmp388ConfigureZeroCalibration(void)
77 void baroBmp388ConfigureSampleCalibration(void)
97 TEST(baroBmp388Test
, TestBmp388CalculateWithZeroCalibration
)
100 int32_t pressure
, temperature
;
101 bmp388_up
= 0; // uncompensated pressure value
102 bmp388_ut
= 0; // uncompensated temperature value
106 baroBmp388ConfigureZeroCalibration();
109 bmp388Calculate(&pressure
, &temperature
);
112 EXPECT_EQ(0, temperature
);
116 EXPECT_EQ(0, pressure
);
119 TEST(baroBmp388Test
, TestBmp388CalculateWithSampleCalibration
)
122 int32_t pressure
, temperature
;
123 bmp388_up
= 7323488; // uncompensated pressure value
124 bmp388_ut
= 9937920; // uncompensated temperature value
128 baroBmp388ConfigureSampleCalibration();
131 bmp388Calculate(&pressure
, &temperature
);
134 EXPECT_EQ(4880, temperature
); // 48.80 degrees C
138 EXPECT_EQ(39535, pressure
); // 39535 Pa
147 bool busBusy(const extDevice_t
*, bool*) {return false;}
148 bool busReadRegisterBuffer(const extDevice_t
*, uint8_t, uint8_t*, uint8_t) {return true;}
149 bool busReadRegisterBufferStart(const extDevice_t
*, uint8_t, uint8_t*, uint8_t) {return true;}
150 bool busWriteRegister(const extDevice_t
*, uint8_t, uint8_t) {return true;}
151 bool busWriteRegisterStart(const extDevice_t
*, uint8_t, uint8_t) {return true;}
152 void busDeviceRegister(const extDevice_t
*) {}
154 uint16_t spiCalculateDivider()
159 void spiSetClkDivisor()
163 void spiPreinitByIO(IO_t
)
175 IO_t
IOGetByTag(ioTag_t
)
184 void EXTIHandlerInit(extiCallbackRec_t
*, extiHandlerCallback
*)
188 void EXTIConfig(IO_t
, extiCallbackRec_t
*, int, ioConfig_t
, extiTrigger_t
)
192 void EXTIEnable(IO_t
)
195 void EXTIDisable(IO_t
)