Don't handle non-MSP characters on VTX MSP port (#14091)
[betaflight.git] / src / main / drivers / barometer / barometer_bmp388.c
blobc7dfbb8dd78746e03da8ed83564c5ffa9cbffd74
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
20 * BMP388 Driver author: Dominic Clifton
23 #include <math.h>
24 #include <stdbool.h>
25 #include <stdint.h>
26 #include <string.h>
28 #include "platform.h"
30 #if defined(USE_BARO) && (defined(USE_BARO_BMP388) || defined(USE_BARO_SPI_BMP388))
32 #include "build/build_config.h"
34 #include "build/debug.h"
36 #include "drivers/barometer/barometer.h"
37 #include "drivers/bus.h"
38 #include "drivers/bus_i2c.h"
39 #include "drivers/bus_i2c_busdev.h"
40 #include "drivers/bus_spi.h"
41 #include "drivers/io.h"
42 #include "drivers/nvic.h"
43 #include "drivers/time.h"
45 #include "barometer_bmp388.h"
47 // 10 MHz max SPI frequency
48 #define BMP388_MAX_SPI_CLK_HZ 10000000
50 #define BMP388_I2C_ADDR (0x76) // same as BMP280/BMP180
51 #define BMP388_CHIP_ID_BMP3 (0x50) // from https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h#L130
52 #define BMP388_CHIP_ID_BMP390 (0x60) // from https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h#L133
54 #define BMP388_CMD_REG (0x7E)
55 #define BMP388_RESERVED_UPPER_REG (0x7D)
56 // everything between BMP388_RESERVED_UPPER_REG and BMP388_RESERVED_LOWER_REG is reserved.
57 #define BMP388_RESERVED_LOWER_REG (0x20)
58 #define BMP388_CONFIG_REG (0x1F)
59 #define BMP388_RESERVED_0x1E_REG (0x1E)
60 #define BMP388_ODR_REG (0x1D)
61 #define BMP388_OSR_REG (0x1C)
62 #define BMP388_PWR_CTRL_REG (0x1B)
63 #define BMP388_IF_CONFIG_REG (0x1A)
64 #define BMP388_INT_CTRL_REG (0x19)
65 #define BMP388_FIFO_CONFIG_2_REG (0x18)
66 #define BMP388_FIFO_CONFIG_1_REG (0x17)
67 #define BMP388_FIFO_WTM_1_REG (0x16)
68 #define BMP388_FIFO_WTM_0_REG (0x15)
69 #define BMP388_FIFO_DATA_REG (0x14)
70 #define BMP388_FIFO_LENGTH_1_REG (0x13)
71 #define BMP388_FIFO_LENGTH_0_REG (0x12)
72 #define BMP388_INT_STATUS_REG (0x11)
73 #define BMP388_EVENT_REG (0x10)
74 #define BMP388_SENSORTIME_3_REG (0x0F) // BME780 only
75 #define BMP388_SENSORTIME_2_REG (0x0E)
76 #define BMP388_SENSORTIME_1_REG (0x0D)
77 #define BMP388_SENSORTIME_0_REG (0x0C)
78 #define BMP388_RESERVED_0x0B_REG (0x0B)
79 #define BMP388_RESERVED_0x0A_REG (0x0A)
81 // see friendly register names below
82 #define BMP388_DATA_5_REG (0x09)
83 #define BMP388_DATA_4_REG (0x08)
84 #define BMP388_DATA_3_REG (0x07)
85 #define BMP388_DATA_2_REG (0x06)
86 #define BMP388_DATA_1_REG (0x05)
87 #define BMP388_DATA_0_REG (0x04)
89 #define BMP388_STATUS_REG (0x03)
90 #define BMP388_ERR_REG (0x02)
91 #define BMP388_RESERVED_0x01_REG (0x01)
92 #define BMP388_CHIP_ID_REG (0x00)
94 // friendly register names, from datasheet 4.3.4
95 #define BMP388_PRESS_MSB_23_16_REG BMP388_DATA_2_REG
96 #define BMP388_PRESS_LSB_15_8_REG BMP388_DATA_1_REG
97 #define BMP388_PRESS_XLSB_7_0_REG BMP388_DATA_0_REG
99 // friendly register names, from datasheet 4.3.5
100 #define BMP388_TEMP_MSB_23_16_REG BMP388_DATA_5_REG
101 #define BMP388_TEMP_LSB_15_8_REG BMP388_DATA_4_REG
102 #define BMP388_TEMP_XLSB_7_0_REG BMP388_DATA_3_REG
104 #define BMP388_DATA_FRAME_SIZE ((BMP388_DATA_5_REG - BMP388_DATA_0_REG) + 1) // +1 for inclusive
106 // from Datasheet 3.3
107 #define BMP388_MODE_SLEEP (0x00)
108 #define BMP388_MODE_FORCED (0x01)
109 #define BMP388_MODE_NORMAL (0x02)
111 #define BMP388_CALIRATION_LOWER_REG (0x30) // See datasheet 4.3.19, "calibration data"
112 #define BMP388_TRIMMING_NVM_PAR_T1_LSB_REG (0x31) // See datasheet 3.11.1 "Memory map trimming coefficients"
113 #define BMP388_TRIMMING_NVM_PAR_P11_REG (0x45) // See datasheet 3.11.1 "Memory map trimming coefficients"
114 #define BMP388_CALIRATION_UPPER_REG (0x57)
116 #define BMP388_TRIMMING_DATA_LENGTH ((BMP388_TRIMMING_NVM_PAR_P11_REG - BMP388_TRIMMING_NVM_PAR_T1_LSB_REG) + 1) // +1 for inclusive
118 #define BMP388_OVERSAMP_1X (0x00)
119 #define BMP388_OVERSAMP_2X (0x01)
120 #define BMP388_OVERSAMP_4X (0x02)
121 #define BMP388_OVERSAMP_8X (0x03)
122 #define BMP388_OVERSAMP_16X (0x04)
123 #define BMP388_OVERSAMP_32X (0x05)
125 // INT_CTRL register
126 #define BMP388_INT_OD_BIT 0
127 #define BMP388_INT_LEVEL_BIT 1
128 #define BMP388_INT_LATCH_BIT 2
129 #define BMP388_INT_FWTM_EN_BIT 3
130 #define BMP388_INT_FFULL_EN_BIT 4
131 #define BMP388_INT_RESERVED_5_BIT 5
132 #define BMP388_INT_DRDY_EN_BIT 6
133 #define BMP388_INT_RESERVED_7_BIT 7
135 // OSR register
136 #define BMP388_OSR_P_BIT 0 // to 2
137 #define BMP388_OSR4_T_BIT 3 // to 5
138 #define BMP388_OSR_P_MASK (0x03) // -----111
139 #define BMP388_OSR4_T_MASK (0x38) // --111---
141 // configure pressure and temperature oversampling, forced sampling mode
142 #define BMP388_PRESSURE_OSR (BMP388_OVERSAMP_8X)
143 #define BMP388_TEMPERATURE_OSR (BMP388_OVERSAMP_1X)
145 // see Datasheet 3.11.1 Memory Map Trimming Coefficients
146 typedef struct bmp388_calib_param_s {
147 uint16_t T1;
148 uint16_t T2;
149 int8_t T3;
150 int16_t P1;
151 int16_t P2;
152 int8_t P3;
153 int8_t P4;
154 uint16_t P5;
155 uint16_t P6;
156 int8_t P7;
157 int8_t P8;
158 int16_t P9;
159 int8_t P10;
160 int8_t P11;
161 } __attribute__((packed)) bmp388_calib_param_t;
163 STATIC_ASSERT(sizeof(bmp388_calib_param_t) == BMP388_TRIMMING_DATA_LENGTH, bmp388_calibration_structure_incorrectly_packed);
165 static uint8_t bmp388_chip_id = 0;
166 STATIC_UNIT_TESTED bmp388_calib_param_t bmp388_cal;
167 // uncompensated pressure and temperature
168 uint32_t bmp388_up = 0;
169 uint32_t bmp388_ut = 0;
171 // make space for dummy SPI byte
172 static DMA_DATA_ZERO_INIT uint8_t sensor_data_buffer[BMP388_DATA_FRAME_SIZE + 1];
173 static uint8_t * sensor_data = sensor_data_buffer;
175 STATIC_UNIT_TESTED int64_t t_lin = 0;
177 static bool bmp388StartUT(baroDev_t *baro);
178 static bool bmp388GetUT(baroDev_t *baro);
179 static bool bmp388ReadUT(baroDev_t *baro);
180 static bool bmp388StartUP(baroDev_t *baro);
181 static bool bmp388GetUP(baroDev_t *baro);
182 static bool bmp388ReadUP(baroDev_t *baro);
184 STATIC_UNIT_TESTED void bmp388Calculate(int32_t *pressure, int32_t *temperature);
186 static bool bmp388ReadRegisterBuffer(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t length)
188 if (dev->bus->busType == BUS_TYPE_SPI) {
189 // dummy byte is returned first on BMP3xx read
190 uint8_t buf[length + 1];
191 bool ret = busReadRegisterBuffer(dev, reg, buf, length + 1);
192 if (ret) {
193 memcpy(data, buf + 1, length);
195 return ret;
196 } else {
197 return busReadRegisterBuffer(dev, reg, data, length);
201 void bmp388_extiHandler(extiCallbackRec_t* cb)
203 #ifdef DEBUG
204 static uint32_t bmp388ExtiCallbackCounter = 0;
206 bmp388ExtiCallbackCounter++;
207 #endif
209 baroDev_t *baro = container_of(cb, baroDev_t, exti);
211 uint8_t intStatus = 0;
212 bmp388ReadRegisterBuffer(&baro->dev, BMP388_INT_STATUS_REG, &intStatus, 1);
215 void bmp388BusInit(const extDevice_t *dev)
217 #ifdef USE_BARO_SPI_BMP388
218 if (dev->bus->busType == BUS_TYPE_SPI) {
219 IOHi(dev->busType_u.spi.csnPin); // Disable
220 IOInit(dev->busType_u.spi.csnPin, OWNER_BARO_CS, 0);
221 IOConfigGPIO(dev->busType_u.spi.csnPin, IOCFG_OUT_PP);
222 spiSetClkDivisor(dev, spiCalculateDivider(BMP388_MAX_SPI_CLK_HZ));
224 #else
225 UNUSED(dev);
226 #endif
229 void bmp388BusDeinit(const extDevice_t *dev)
231 #ifdef USE_BARO_SPI_BMP388
232 if (dev->bus->busType == BUS_TYPE_SPI) {
233 spiPreinitByIO(dev->busType_u.spi.csnPin);
235 #else
236 UNUSED(dev);
237 #endif
240 bool bmp388BeginForcedMeasurement(const extDevice_t *dev)
242 // enable pressure measurement, temperature measurement, set power mode and start sampling
243 uint8_t mode = BMP388_MODE_FORCED << 4 | 1 << 1 | 1 << 0;
244 return busWriteRegisterStart(dev, BMP388_PWR_CTRL_REG, mode);
247 bool bmp388Detect(const bmp388Config_t *config, baroDev_t *baro)
249 delay(20);
251 IO_t baroIntIO = IOGetByTag(config->eocTag);
252 if (baroIntIO) {
253 IOInit(baroIntIO, OWNER_BARO_EOC, 0);
254 EXTIHandlerInit(&baro->exti, bmp388_extiHandler);
255 EXTIConfig(baroIntIO, &baro->exti, NVIC_PRIO_BARO_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
256 EXTIEnable(baroIntIO);
259 extDevice_t *dev = &baro->dev;
260 bool defaultAddressApplied = false;
262 bmp388BusInit(dev);
264 if ((dev->bus->busType == BUS_TYPE_I2C) && (dev->busType_u.i2c.address == 0)) {
265 // Default address for BMP388
266 dev->busType_u.i2c.address = BMP388_I2C_ADDR;
267 defaultAddressApplied = true;
269 if (dev->bus->busType == BUS_TYPE_SPI) {
270 // dummy byte is returned first on BMP3xx read
271 sensor_data = sensor_data_buffer + 1;
274 bmp388ReadRegisterBuffer(dev, BMP388_CHIP_ID_REG, &bmp388_chip_id, 1);
276 if (bmp388_chip_id != BMP388_CHIP_ID_BMP3 && bmp388_chip_id != BMP388_CHIP_ID_BMP390) {
277 bmp388BusDeinit(dev);
278 if (defaultAddressApplied) {
279 dev->busType_u.i2c.address = 0;
281 return false;
284 busDeviceRegister(dev);
286 if (baroIntIO) {
287 uint8_t intCtrlValue = 1 << BMP388_INT_DRDY_EN_BIT |
288 0 << BMP388_INT_FFULL_EN_BIT |
289 0 << BMP388_INT_FWTM_EN_BIT |
290 0 << BMP388_INT_LATCH_BIT |
291 1 << BMP388_INT_LEVEL_BIT |
292 0 << BMP388_INT_OD_BIT;
293 busWriteRegister(dev, BMP388_INT_CTRL_REG, intCtrlValue);
296 // read calibration
297 bmp388ReadRegisterBuffer(dev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, (uint8_t *)&bmp388_cal, sizeof(bmp388_calib_param_t));
299 // set oversampling
300 busWriteRegister(dev, BMP388_OSR_REG,
301 ((BMP388_PRESSURE_OSR << BMP388_OSR_P_BIT) & BMP388_OSR_P_MASK) |
302 ((BMP388_TEMPERATURE_OSR << BMP388_OSR4_T_BIT) & BMP388_OSR4_T_MASK)
305 bmp388BeginForcedMeasurement(dev);
307 // these are dummy as temperature is measured as part of pressure
308 baro->ut_delay = 0;
309 baro->start_ut = bmp388StartUT;
310 baro->get_ut = bmp388GetUT;
311 baro->read_ut = bmp388ReadUT;
312 // only _up part is executed, and gets both temperature and pressure
313 baro->start_up = bmp388StartUP;
314 baro->get_up = bmp388GetUP;
315 baro->read_up = bmp388ReadUP;
317 // See datasheet 3.9.2 "Measurement rate in forced mode and normal mode"
318 baro->up_delay = 234 +
319 (392 + (powf(2, BMP388_PRESSURE_OSR + 1) * 2000)) +
320 (313 + (powf(2, BMP388_TEMPERATURE_OSR + 1) * 2000));
322 baro->calculate = bmp388Calculate;
324 while (busBusy(&baro->dev, NULL));
326 return true;
329 static bool bmp388StartUT(baroDev_t *baro)
331 UNUSED(baro);
332 // dummy
334 return true;
337 static bool bmp388ReadUT(baroDev_t *baro)
339 UNUSED(baro);
340 // dummy
341 return true;
344 static bool bmp388GetUT(baroDev_t *baro)
346 UNUSED(baro);
347 // dummy
348 return true;
351 static bool bmp388StartUP(baroDev_t *baro)
353 // start measurement
354 return bmp388BeginForcedMeasurement(&baro->dev);
357 static bool bmp388ReadUP(baroDev_t *baro)
359 if (busBusy(&baro->dev, NULL)) {
360 return false;
363 // read data from sensor
364 return busReadRegisterBufferStart(&baro->dev, BMP388_DATA_0_REG, sensor_data_buffer, BMP388_DATA_FRAME_SIZE + (sensor_data - sensor_data_buffer));
367 static bool bmp388GetUP(baroDev_t *baro)
369 if (busBusy(&baro->dev, NULL)) {
370 return false;
373 bmp388_up = sensor_data[0] << 0 | sensor_data[1] << 8 | sensor_data[2] << 16;
374 bmp388_ut = sensor_data[3] << 0 | sensor_data[4] << 8 | sensor_data[5] << 16;
375 return true;
378 // Returns temperature in DegC, resolution is 0.01 DegC. Output value of "5123" equals 51.23 DegC
379 static int64_t bmp388CompensateTemperature(uint32_t uncomp_temperature)
381 uint64_t partial_data1;
382 uint64_t partial_data2;
383 uint64_t partial_data3;
384 int64_t partial_data4;
385 int64_t partial_data5;
386 int64_t partial_data6;
387 int64_t comp_temp;
389 partial_data1 = uncomp_temperature - (256 * bmp388_cal.T1);
390 partial_data2 = bmp388_cal.T2 * partial_data1;
391 partial_data3 = partial_data1 * partial_data1;
392 partial_data4 = (int64_t)partial_data3 * bmp388_cal.T3;
393 partial_data5 = ((int64_t)(partial_data2 * 262144) + partial_data4);
394 partial_data6 = partial_data5 / 4294967296;
395 /* Update t_lin, needed for pressure calculation */
396 t_lin = partial_data6;
397 comp_temp = (int64_t)((partial_data6 * 25) / 16384);
399 return comp_temp;
402 static uint64_t bmp388CompensatePressure(uint32_t uncomp_pressure)
404 int64_t partial_data1;
405 int64_t partial_data2;
406 int64_t partial_data3;
407 int64_t partial_data4;
408 int64_t partial_data5;
409 int64_t partial_data6;
410 int64_t offset;
411 int64_t sensitivity;
412 uint64_t comp_press;
414 partial_data1 = t_lin * t_lin;
415 partial_data2 = partial_data1 / 64;
416 partial_data3 = (partial_data2 * t_lin) / 256;
417 partial_data4 = (bmp388_cal.P8 * partial_data3) / 32;
418 partial_data5 = (bmp388_cal.P7 * partial_data1) * 16;
419 partial_data6 = (bmp388_cal.P6 * t_lin) * 4194304;
420 offset = (bmp388_cal.P5 * 140737488355328) + partial_data4 + partial_data5 + partial_data6;
422 partial_data2 = (bmp388_cal.P4 * partial_data3) / 32;
423 partial_data4 = (bmp388_cal.P3 * partial_data1) * 4;
424 partial_data5 = (bmp388_cal.P2 - 16384) * t_lin * 2097152;
425 sensitivity = ((bmp388_cal.P1 - 16384) * 70368744177664) + partial_data2 + partial_data4
426 + partial_data5;
428 partial_data1 = (sensitivity / 16777216) * uncomp_pressure;
429 partial_data2 = bmp388_cal.P10 * t_lin;
430 partial_data3 = partial_data2 + (65536 * bmp388_cal.P9);
431 partial_data4 = (partial_data3 * uncomp_pressure) / 8192;
432 partial_data5 = (partial_data4 * uncomp_pressure) / 512;
433 partial_data6 = (int64_t)((uint64_t)uncomp_pressure * (uint64_t)uncomp_pressure);
434 partial_data2 = (bmp388_cal.P11 * partial_data6) / 65536;
435 partial_data3 = (partial_data2 * uncomp_pressure) / 128;
436 partial_data4 = (offset / 4) + partial_data1 + partial_data5 + partial_data3;
437 comp_press = (((uint64_t)partial_data4 * 25) / (uint64_t)1099511627776);
439 #ifdef DEBUG_BARO_BMP388
440 debug[1] = ((comp_press & 0xFFFF0000) >> 32);
441 debug[2] = ((comp_press & 0x0000FFFF) >> 0);
442 #endif
443 return comp_press;
446 STATIC_UNIT_TESTED void bmp388Calculate(int32_t *pressure, int32_t *temperature)
448 // calculate
449 int64_t t;
450 int64_t p;
452 t = bmp388CompensateTemperature(bmp388_ut);
453 p = bmp388CompensatePressure(bmp388_up);
455 if (pressure)
456 *pressure = (int32_t)(p / 256);
457 if (temperature)
458 *temperature = t;
461 #endif