PX4 Firmware
PX4 Autopilot Software http://px4.io
bmp388.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2019 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file bmp388.cpp
36  *
37  * Driver for the BMP388 barometric pressure sensor connected via I2C
38  * (SPI still TODO/test).
39  *
40  * Refer to: https://github.com/BoschSensortec/BMP3-Sensor-API
41  */
42 
43 #include "bmp388.h"
44 
45 BMP388::BMP388(IBMP388 *interface) :
46  ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id())),
47  _px4_baro(interface->get_device_id()),
48  _interface(interface),
49  _sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
50  _measure_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": measure")),
51  _comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms errors"))
52 {
54 }
55 
57 {
58  /* make sure we are truly inactive */
59  stop();
60 
61  /* free perf counters */
65 
66  delete _interface;
67 }
68 
69 int
71 {
72  if (!soft_reset()) {
73  PX4_WARN("failed to reset baro during init");
74  return -EIO;
75  }
76 
78  PX4_WARN("id of your baro is not: 0x%02x", BMP3_CHIP_ID);
79  return -EIO;
80  }
81 
83 
84  if (!_cal) {
85  PX4_WARN("failed to get baro cal init");
86  return -EIO;
87  }
88 
89  if (!validate_trimming_param()) {
90  PX4_WARN("failed to validate trim param");
91  return -EIO;
92  }
93 
94  if (!set_sensor_settings()) {
95  PX4_WARN("failed to set sensor settings");
96  return -EIO;
97  }
98 
99  /* do a first measurement cycle to populate reports with valid data */
100  if (measure()) {
101  PX4_WARN("measure failed");
102  return -EIO;
103  }
104 
105  /* sleep this first time around */
106  px4_usleep(_measure_interval);
107 
108  if (collect()) {
109  PX4_WARN("collect failed");
110  return -EIO;
111  }
112 
113  start();
114 
115  return OK;
116 }
117 
118 void
120 {
124  printf("measurement interval: %u us \n", _measure_interval);
125 
127 }
128 
129 void
131 {
132  _collect_phase = false;
133 
134  /* make sure we are stopped first */
135  stop();
136 
137  ScheduleOnInterval(_measure_interval, 1000);
138 }
139 
140 void
142 {
143  ScheduleClear();
144 }
145 
146 /*
147  * ScheduledWorkItem override
148  */
149 void
151 {
152  if (_collect_phase) {
153  collect();
154  }
155 
156  measure();
157 }
158 
159 int
161 {
162  _collect_phase = true;
163 
165 
166  /* start measurement */
168  PX4_WARN("failed to set operating mode");
171  return -EIO;
172  }
173 
175 
176  return OK;
177 }
178 
179 int
181 {
182  _collect_phase = false;
183 
184  /* enable pressure and temperature */
185  uint8_t sensor_comp = BMP3_PRESS | BMP3_TEMP;
186  bmp3_data data{};
187 
189 
190  /* this should be fairly close to the end of the conversion, so the best approximation of the time */
191  const hrt_abstime timestamp_sample = hrt_absolute_time();
192 
193  if (!get_sensor_data(sensor_comp, &data)) {
196  return -EIO;
197  }
198 
200 
201  float temperature = (float)(data.temperature / 100.0f);
202  float pressure = (float)(data.pressure / 100.0f); // to hecto Pascal
203  pressure = pressure / 100.0f; // to mbar
204 
205  _px4_baro.set_temperature(temperature);
206  _px4_baro.update(timestamp_sample, pressure); // to mbar
207 
209 
210  return OK;
211 }
212 
213 /*!
214  * @brief This API performs the soft reset of the sensor.
215  *
216  * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
217  */
218 bool
220 {
221  bool result = false;
222  uint8_t status;
223  int ret;
224 
226 
227  if (status & BMP3_CMD_RDY) {
229 
230  if (ret == OK) {
233 
234  if ((status & BMP3_CMD_ERR) == 0) {
235  result = true;
236  }
237  }
238  }
239 
240  return result;
241 }
242 
243 /*
244  * @brief function to calculate CRC for the trimming parameters
245  *
246  * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/self-test/bmp3_selftest.c
247  * */
248 static int8_t cal_crc(uint8_t seed, uint8_t data)
249 {
250  int8_t poly = 0x1D;
251  int8_t var2;
252  uint8_t i;
253 
254  for (i = 0; i < 8; i++) {
255  if ((seed & 0x80) ^ (data & 0x80)) {
256  var2 = 1;
257 
258  } else {
259  var2 = 0;
260  }
261 
262  seed = (seed & 0x7F) << 1;
263  data = (data & 0x7F) << 1;
264  seed = seed ^ (uint8_t)(poly * var2);
265  }
266 
267  return (int8_t)seed;
268 }
269 
270 /*
271  * @brief Function to verify the trimming parameters
272  *
273  * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/self-test/bmp3_selftest.c
274  * */
275 bool
277 {
278  bool result = false;
279  uint8_t crc = 0xFF;
280  uint8_t stored_crc;
281  uint8_t trim_param[BMP3_CALIB_DATA_LEN];
282  uint8_t i;
283 
284  memcpy(&trim_param, _cal, BMP3_CALIB_DATA_LEN);
285 
286  for (i = 0; i < BMP3_CALIB_DATA_LEN; i++) {
287  crc = (uint8_t)cal_crc(crc, trim_param[i]);
288  }
289 
290  crc = (crc ^ 0xFF);
291 
293 
294  if (stored_crc == crc) {
295  result = true;
296  }
297 
298  return result;
299 }
300 
301 uint32_t
302 BMP388::get_measurement_time(uint8_t osr_t, uint8_t osr_p)
303 {
304  /*
305  From BST-BMP388-DS001.pdf, page 25, table 21
306 
307  Pressure Temperature Measurement Max Time
308  Oversample Oversample Time (Forced)
309  x1 1x 4.9 ms 5.7 ms
310  x2 1x 6.9 ms 8.7 ms
311  x4 1x 10.9 ms 13.3 ms
312  x8 1x 18.9 ms 22.5 ms
313  x16 2x 36.9 ms 43.3 ms
314  x32 2x 68.9 ms (not documented)
315  */
316 
317  uint32_t meas_time_us = 0; // unsupported value by default
318 
319  if (osr_t == BMP3_NO_OVERSAMPLING) {
320  switch (osr_p) {
322  meas_time_us = 5700;
323  break;
324 
326  meas_time_us = 8700;
327  break;
328 
330  meas_time_us = 13300;
331  break;
332 
334  meas_time_us = 22500;
335  break;
336  }
337 
338  } else if (osr_t == BMP3_OVERSAMPLING_2X) {
339  switch (osr_p) {
341  meas_time_us = 43300;
342  break;
343 
345  meas_time_us = 68900;
346  break;
347  }
348  }
349 
350  return meas_time_us;
351 }
352 
353 /*!
354  * @brief This API sets the power control(pressure enable and
355  * temperature enable), over sampling, odr and filter
356  * settings in the sensor.
357  *
358  * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
359  */
360 bool
362 {
364 
365  if (_measure_interval == 0) {
366  PX4_WARN("unsupported oversampling selected");
367  return false;
368  }
369 
370  /* Select the pressure and temperature sensor to be enabled */
371  uint8_t pwc_ctl_reg = 0;
372  pwc_ctl_reg = BMP3_SET_BITS_POS_0(pwc_ctl_reg, BMP3_PRESS_EN, BMP3_ENABLE);
373  pwc_ctl_reg = BMP3_SET_BITS(pwc_ctl_reg, BMP3_TEMP_EN, BMP3_ENABLE);
374 
375  int ret = _interface->set_reg(pwc_ctl_reg, BMP3_PWR_CTRL_ADDR);
376 
377  if (ret != OK) {
378  PX4_WARN("failed to set settings BMP3_PWR_CTRL_ADDR");
379  return false;
380  }
381 
382  /* Select the and over sampling settings for pressure and temperature */
383  uint8_t osr_ctl_reg = 0;
384  osr_ctl_reg = BMP3_SET_BITS_POS_0(osr_ctl_reg, BMP3_PRESS_OS, _osr_p);
385  osr_ctl_reg = BMP3_SET_BITS(osr_ctl_reg, BMP3_TEMP_OS, _osr_t);
386 
387  ret = _interface->set_reg(osr_ctl_reg, BMP3_OSR_ADDR);
388 
389  if (ret != OK) {
390  PX4_WARN("failed to set settings BMP3_OSR_ADDR");
391  return false;
392  }
393 
394  /* Using 'forced mode' so this is not required but here for future use possibly */
395  uint8_t odr_ctl_reg = 0;
396  odr_ctl_reg = BMP3_SET_BITS_POS_0(odr_ctl_reg, BMP3_ODR, _odr);
397 
398  ret = _interface->set_reg(odr_ctl_reg, BMP3_ODR_ADDR);
399 
400  if (ret != OK) {
401  PX4_WARN("failed to set output data rate register");
402  return false;
403  }
404 
405  uint8_t iir_ctl_reg = 0;
406  iir_ctl_reg = BMP3_SET_BITS(iir_ctl_reg, BMP3_IIR_FILTER, _iir_coef);
407  ret = _interface->set_reg(iir_ctl_reg, BMP3_IIR_ADDR);
408 
409  if (ret != OK) {
410  PX4_WARN("failed to set IIR settings");
411  return false;
412  }
413 
414  return true;
415 }
416 
417 
418 /*!
419  * @brief This API sets the power mode of the sensor.
420  *
421  * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
422  */
423 bool
424 BMP388::set_op_mode(uint8_t op_mode)
425 {
426  bool result = false;
427  uint8_t last_set_mode;
428  uint8_t op_mode_reg_val;
429  int ret = OK;
430 
431  op_mode_reg_val = _interface->get_reg(BMP3_PWR_CTRL_ADDR);
432  last_set_mode = BMP3_GET_BITS(op_mode_reg_val, BMP3_OP_MODE);
433 
434  /* Device needs to be put in sleep mode to transition */
435  if (last_set_mode != BMP3_SLEEP_MODE) {
436  op_mode_reg_val = op_mode_reg_val & (~(BMP3_OP_MODE_MSK));
437  ret = _interface->set_reg(op_mode_reg_val, BMP3_PWR_CTRL_ADDR);
438 
439  if (ret != OK) {
440  return false;
441  }
442 
443  px4_usleep(BMP3_POST_SLEEP_WAIT_TIME);
444  }
445 
446  if (ret == OK) {
447  op_mode_reg_val = _interface->get_reg(BMP3_PWR_CTRL_ADDR);
448  op_mode_reg_val = BMP3_SET_BITS(op_mode_reg_val, BMP3_OP_MODE, op_mode);
449  ret = _interface->set_reg(op_mode_reg_val, BMP3_PWR_CTRL_ADDR);
450 
451  if (ret != OK) {
452  return false;
453  }
454 
455  result = true;
456  }
457 
458  return result;
459 }
460 
461 /*!
462  * @brief This internal API is used to parse the pressure or temperature or
463  * both the data and store it in the bmp3_uncomp_data structure instance.
464  *
465  * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
466  */
467 static void parse_sensor_data(const uint8_t *reg_data, struct bmp3_uncomp_data *uncomp_data)
468 {
469  uint32_t data_xlsb;
470  uint32_t data_lsb;
471  uint32_t data_msb;
472 
473  data_xlsb = (uint32_t)reg_data[0];
474  data_lsb = (uint32_t)reg_data[1] << 8;
475  data_msb = (uint32_t)reg_data[2] << 16;
476  uncomp_data->pressure = data_msb | data_lsb | data_xlsb;
477 
478  data_xlsb = (uint32_t)reg_data[3];
479  data_lsb = (uint32_t)reg_data[4] << 8;
480  data_msb = (uint32_t)reg_data[5] << 16;
481  uncomp_data->temperature = data_msb | data_lsb | data_xlsb;
482 }
483 
484 
485 /*!
486  * @brief This internal API is used to compensate the raw temperature data and
487  * return the compensated temperature data in integer data type.
488  * For eg if returned temperature is 2426 then it is 2426/100 = 24.26 deg Celsius
489  *
490  * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
491  */
492 static int64_t compensate_temperature(const struct bmp3_uncomp_data *uncomp_data, struct bmp3_calib_data *calib_data)
493 {
494  int64_t partial_data1;
495  int64_t partial_data2;
496  int64_t partial_data3;
497  int64_t partial_data4;
498  int64_t partial_data5;
499  int64_t partial_data6;
500  int64_t comp_temp;
501 
502  partial_data1 = ((int64_t)uncomp_data->temperature - (256 * calib_data->reg_calib_data.par_t1));
503  partial_data2 = calib_data->reg_calib_data.par_t2 * partial_data1;
504  partial_data3 = (partial_data1 * partial_data1);
505  partial_data4 = (int64_t)partial_data3 * calib_data->reg_calib_data.par_t3;
506  partial_data5 = ((int64_t)(partial_data2 * 262144) + partial_data4);
507  partial_data6 = partial_data5 / 4294967296;
508 
509  /* Store t_lin in dev. structure for pressure calculation */
510  calib_data->reg_calib_data.t_lin = partial_data6;
511  comp_temp = (int64_t)((partial_data6 * 25) / 16384);
512 
513  return comp_temp;
514 }
515 
516 /*!
517  * @brief This internal API is used to compensate the raw pressure data and
518  * return the compensated pressure data in integer data type.
519  * for eg return if pressure is 9528709 which is 9528709/100 = 95287.09 Pascal or 952.8709 hecto Pascal
520  *
521  * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
522  */
523 static uint64_t compensate_pressure(const struct bmp3_uncomp_data *uncomp_data,
524  const struct bmp3_calib_data *calib_data)
525 {
526  const struct bmp3_reg_calib_data *reg_calib_data = &calib_data->reg_calib_data;
527  int64_t partial_data1;
528  int64_t partial_data2;
529  int64_t partial_data3;
530  int64_t partial_data4;
531  int64_t partial_data5;
532  int64_t partial_data6;
533  int64_t offset;
534  int64_t sensitivity;
535  uint64_t comp_press;
536 
537  partial_data1 = reg_calib_data->t_lin * reg_calib_data->t_lin;
538  partial_data2 = partial_data1 / 64;
539  partial_data3 = (partial_data2 * reg_calib_data->t_lin) / 256;
540  partial_data4 = (reg_calib_data->par_p8 * partial_data3) / 32;
541  partial_data5 = (reg_calib_data->par_p7 * partial_data1) * 16;
542  partial_data6 = (reg_calib_data->par_p6 * reg_calib_data->t_lin) * 4194304;
543  offset = (reg_calib_data->par_p5 * 140737488355328) + partial_data4 + partial_data5 + partial_data6;
544  partial_data2 = (reg_calib_data->par_p4 * partial_data3) / 32;
545  partial_data4 = (reg_calib_data->par_p3 * partial_data1) * 4;
546  partial_data5 = (reg_calib_data->par_p2 - 16384) * reg_calib_data->t_lin * 2097152;
547  sensitivity = ((reg_calib_data->par_p1 - 16384) * 70368744177664) + partial_data2 + partial_data4 + partial_data5;
548  partial_data1 = (sensitivity / 16777216) * uncomp_data->pressure;
549  partial_data2 = reg_calib_data->par_p10 * reg_calib_data->t_lin;
550  partial_data3 = partial_data2 + (65536 * reg_calib_data->par_p9);
551  partial_data4 = (partial_data3 * uncomp_data->pressure) / 8192;
552  /*dividing by 10 followed by multiplying by 10 to avoid overflow caused by (uncomp_data->pressure * partial_data4) */
553  partial_data5 = (uncomp_data->pressure * (partial_data4 / 10)) / 512;
554  partial_data5 = partial_data5 * 10;
555  partial_data6 = (int64_t)((uint64_t)uncomp_data->pressure * (uint64_t)uncomp_data->pressure);
556  partial_data2 = (reg_calib_data->par_p11 * partial_data6) / 65536;
557  partial_data3 = (partial_data2 * uncomp_data->pressure) / 128;
558  partial_data4 = (offset / 4) + partial_data1 + partial_data5 + partial_data3;
559  comp_press = (((uint64_t)partial_data4 * 25) / (uint64_t)1099511627776);
560 
561  return comp_press;
562 }
563 
564 /*!
565  * @brief This internal API is used to compensate the pressure or temperature
566  * or both the data according to the component selected by the user.
567  *
568  * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
569  */
570 bool
571 BMP388::compensate_data(uint8_t sensor_comp,
572  const struct bmp3_uncomp_data *uncomp_data,
573  struct bmp3_data *comp_data)
574 {
575  int8_t rslt = OK;
576  struct bmp3_calib_data calib_data = {0};
577  struct bmp3_reg_calib_data *reg_calib_data = &calib_data.reg_calib_data;
578  memcpy(reg_calib_data, _cal, 21);
579 
580  if ((uncomp_data != NULL) && (comp_data != NULL)) {
581  if (sensor_comp & (BMP3_PRESS | BMP3_TEMP)) {
582  comp_data->temperature = compensate_temperature(uncomp_data, &calib_data);
583  }
584 
585  if (sensor_comp & BMP3_PRESS) {
586  comp_data->pressure = compensate_pressure(uncomp_data, &calib_data);
587  }
588 
589  } else {
590  rslt = -1;
591  }
592 
593  return (rslt == 0);
594 }
595 
596 /*!
597  * @brief This API reads the pressure, temperature or both data from the
598  * sensor, compensates the data and store it in the bmp3_data structure
599  * instance passed by the user.
600  */
601 bool
602 BMP388::get_sensor_data(uint8_t sensor_comp, struct bmp3_data *comp_data)
603 {
604  bool result = false;
605  int8_t rslt;
606 
607  uint8_t reg_data[BMP3_P_T_DATA_LEN] = { 0 };
608  struct bmp3_uncomp_data uncomp_data = { 0 };
609 
611 
612  if (rslt == OK) {
613  parse_sensor_data(reg_data, &uncomp_data);
614  result = compensate_data(sensor_comp, &uncomp_data, comp_data);
615  }
616 
617  return result;
618 }
void print_status()
#define BMP3_SENS_STATUS_REG_ADDR
Definition: bmp388.h:82
uint16_t par_t1
@ Trim Variables
Definition: bmp388.h:214
uint8_t _osr_p
Definition: bmp388.h:325
int16_t par_p1
Definition: bmp388.h:217
#define BMP3_OVERSAMPLING_2X
Definition: bmp388.h:57
#define BPM3_CMD_SOFT_RESET
Definition: bmp388.h:164
#define BMP3_PWR_CTRL_ADDR
Definition: bmp388.h:84
void set_temperature(float temperature)
#define BMP3_ODR_ADDR
Definition: bmp388.h:165
void stop()
Definition: bmp388.cpp:141
static struct vehicle_status_s status
Definition: Commander.cpp:138
#define BMP3_POST_RESET_WAIT_TIME
Definition: bmp388.h:161
#define BMP3_CALIB_DATA_ADDR
Definition: bmp388.h:86
uint64_t pressure
Definition: bmp388.h:242
measure the time elapsed performing an event
Definition: perf_counter.h:56
bool set_op_mode(uint8_t op_mode)
This API sets the power mode of the sensor.
Definition: bmp388.cpp:424
uint32_t pressure
Definition: bmp388.h:259
int16_t par_p2
Definition: bmp388.h:218
int collect()
Definition: bmp388.cpp:180
void set_error_count(uint64_t error_count)
#define BMP3_CMD_ERR
Definition: bmp388.h:91
uint32_t get_measurement_time(uint8_t osr_t, uint8_t osr_p)
Definition: bmp388.cpp:302
#define BMP3_OVERSAMPLING_8X
Definition: bmp388.h:59
#define BMP3_IIR_ADDR
Definition: bmp388.h:166
uint16_t par_p5
Definition: bmp388.h:221
#define BMP3_PRESS
Definition: bmp388.h:110
#define BMP3_SET_BITS_POS_0(reg_data, bitname, data)
Definition: bmp388.h:149
bool set_sensor_settings()
This API sets the power control(pressure enable and temperature enable), over sampling, odr and filter settings in the sensor.
Definition: bmp388.cpp:361
virtual uint8_t get_reg(uint8_t addr)=0
#define BMP3_CMD_ADDR
Definition: bmp388.h:87
#define BMP3_GET_BITS(reg_data, bitname)
Definition: bmp388.h:153
#define BMP3_OP_MODE_MSK
Definition: bmp388.h:126
perf_counter_t _comms_errors
Definition: bmp388.h:331
void start()
Definition: bmp388.cpp:130
PX4Barometer _px4_baro
Definition: bmp388.h:320
#define BMP3_CHIP_ID_ADDR
Definition: bmp388.h:80
#define BMP3_ENABLE
Definition: bmp388.h:104
bool validate_trimming_param()
Definition: bmp388.cpp:276
count the number of times an event occurs
Definition: perf_counter.h:55
static uint64_t compensate_pressure(const struct bmp3_uncomp_data *uncomp_data, const struct bmp3_calib_data *calib_data)
This internal API is used to compensate the raw pressure data and return the compensated pressure dat...
Definition: bmp388.cpp:523
#define DRV_DEVTYPE_BMP388
Definition: drv_sensor.h:118
unsigned _measure_interval
Definition: bmp388.h:323
void print_info()
Definition: bmp388.cpp:119
uint32_t temperature
Definition: bmp388.h:262
static int8_t cal_crc(uint8_t seed, uint8_t data)
Definition: bmp388.cpp:248
#define BMP3_POST_SLEEP_WAIT_TIME
Definition: bmp388.h:160
#define BMP3_FORCED_MODE
Definition: bmp388.h:101
void perf_count(perf_counter_t handle)
Count a performance event.
void perf_free(perf_counter_t handle)
Free a counter.
perf_counter_t _sample_perf
Definition: bmp388.h:329
uint8_t _osr_t
Definition: bmp388.h:324
perf_counter_t _measure_perf
Definition: bmp388.h:330
#define BMP3_ERR_REG_ADDR
Definition: bmp388.h:81
#define perf_alloc(a, b)
Definition: px4io.h:59
void update(hrt_abstime timestamp, float pressure)
IBMP388 * _interface
Definition: bmp388.h:321
uint8_t * data
Definition: dataman.cpp:149
virtual calibration_s * get_calibration(uint8_t addr)=0
uint16_t par_t2
Definition: bmp388.h:215
bool compensate_data(uint8_t sensor_comp, const struct bmp3_uncomp_data *uncomp_data, struct bmp3_data *comp_data)
This internal API is used to compensate the pressure or temperature or both the data according to the...
Definition: bmp388.cpp:571
#define BMP3_CMD_RDY
Definition: bmp388.h:95
BMP388(IBMP388 *interface)
Definition: bmp388.cpp:45
virtual int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len)=0
void perf_end(perf_counter_t handle)
End a performance event.
#define BMP3_SET_BITS(reg_data, bitname, data)
Definition: bmp388.h:144
#define BMP3_NO_OVERSAMPLING
Definition: bmp388.h:56
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
#define BMP3_OVERSAMPLING_32X
Definition: bmp388.h:61
static void parse_sensor_data(const uint8_t *reg_data, struct bmp3_uncomp_data *uncomp_data)
This internal API is used to parse the pressure or temperature or both the data and store it in the b...
Definition: bmp388.cpp:467
uint8_t _odr
Definition: bmp388.h:326
void Run() override
Definition: bmp388.cpp:150
virtual ~BMP388()
Definition: bmp388.cpp:56
#define BMP3_OVERSAMPLING_4X
Definition: bmp388.h:58
#define BMP3_OSR_ADDR
Definition: bmp388.h:85
calibration_s * _cal
Definition: bmp388.h:333
virtual int init()
Definition: bmp388.cpp:70
virtual int set_reg(uint8_t value, uint8_t addr)=0
Shared defines for the bmp388 driver.
#define BMP3_TEMP
Definition: bmp388.h:111
#define BMP3_CHIP_ID
Definition: bmp388.h:53
#define BMP3_DATA_ADDR
Definition: bmp388.h:83
bool get_sensor_data(uint8_t sensor_comp, struct bmp3_data *comp_data)
This API reads the pressure, temperature or both data from the sensor, compensates the data and store...
Definition: bmp388.cpp:602
bool _collect_phase
Definition: bmp388.h:335
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
uint64_t perf_event_count(perf_counter_t handle)
Return current event_count.
#define BMP3_OVERSAMPLING_16X
Definition: bmp388.h:60
#define BMP3_SLEEP_MODE
Definition: bmp388.h:100
Definition: bst.cpp:62
void perf_cancel(perf_counter_t handle)
Cancel a performance event.
#define BMP3_P_T_DATA_LEN
Definition: bmp388.h:116
static int64_t compensate_temperature(const struct bmp3_uncomp_data *uncomp_data, struct bmp3_calib_data *calib_data)
This internal API is used to compensate the raw temperature data and return the compensated temperatu...
Definition: bmp388.cpp:492
struct bmp3_reg_calib_data reg_calib_data
Definition: bmp388.h:250
#define BMP3_CALIB_DATA_LEN
Definition: bmp388.h:115
#define OK
Definition: uavcan_main.cpp:71
bool soft_reset()
This API performs the soft reset of the sensor.
Definition: bmp388.cpp:219
int64_t temperature
Definition: bmp388.h:239
uint16_t par_p6
Definition: bmp388.h:222
int measure()
Definition: bmp388.cpp:160
int16_t par_p9
Definition: bmp388.h:225
#define BMP3_TRIM_CRC_DATA_ADDR
Definition: bmp388.h:163
void perf_begin(perf_counter_t handle)
Begin a performance event.
uint8_t _iir_coef
Definition: bmp388.h:327
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
void set_device_type(uint8_t devtype)