PX4 Firmware
PX4 Autopilot Software http://px4.io
bmp388.h
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.h
36  *
37  * Shared defines for the bmp388 driver.
38  */
39 #pragma once
40 
41 #include <math.h>
42 #include <drivers/drv_baro.h>
43 #include <drivers/drv_hrt.h>
44 #include <lib/cdev/CDev.hpp>
45 #include <perf/perf_counter.h>
46 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
48 
49 #include "board_config.h"
50 
51 // From https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h
52 
53 #define BMP3_CHIP_ID (0x50)
54 
55 /* Over sampling macros */
56 #define BMP3_NO_OVERSAMPLING (0x00)
57 #define BMP3_OVERSAMPLING_2X (0x01)
58 #define BMP3_OVERSAMPLING_4X (0x02)
59 #define BMP3_OVERSAMPLING_8X (0x03)
60 #define BMP3_OVERSAMPLING_16X (0x04)
61 #define BMP3_OVERSAMPLING_32X (0x05)
62 
63 /* Filter setting macros */
64 #define BMP3_IIR_FILTER_DISABLE (0x00)
65 #define BMP3_IIR_FILTER_COEFF_1 (0x01)
66 #define BMP3_IIR_FILTER_COEFF_3 (0x02)
67 #define BMP3_IIR_FILTER_COEFF_7 (0x03)
68 #define BMP3_IIR_FILTER_COEFF_15 (0x04)
69 #define BMP3_IIR_FILTER_COEFF_31 (0x05)
70 #define BMP3_IIR_FILTER_COEFF_63 (0x06)
71 #define BMP3_IIR_FILTER_COEFF_127 (0x07)
72 
73 /* Odr setting macros */
74 #define BMP3_ODR_200_HZ (0x00)
75 #define BMP3_ODR_100_HZ (0x01)
76 #define BMP3_ODR_50_HZ (0x02)
77 #define BMP3_ODR_25_HZ (0x03)
78 
79 /* Register Address */
80 #define BMP3_CHIP_ID_ADDR (0x00)
81 #define BMP3_ERR_REG_ADDR (0x02)
82 #define BMP3_SENS_STATUS_REG_ADDR (0x03)
83 #define BMP3_DATA_ADDR (0x04)
84 #define BMP3_PWR_CTRL_ADDR (0x1B)
85 #define BMP3_OSR_ADDR (0X1C)
86 #define BMP3_CALIB_DATA_ADDR (0x31)
87 #define BMP3_CMD_ADDR (0x7E)
88 
89 /* Error status macros */
90 #define BMP3_FATAL_ERR (0x01)
91 #define BMP3_CMD_ERR (0x02)
92 #define BMP3_CONF_ERR (0x04)
93 
94 /* Status macros */
95 #define BMP3_CMD_RDY (0x10)
96 #define BMP3_DRDY_PRESS (0x20)
97 #define BMP3_DRDY_TEMP (0x40)
98 
99 /* Power mode macros */
100 #define BMP3_SLEEP_MODE (0x00)
101 #define BMP3_FORCED_MODE (0x01)
102 #define BMP3_NORMAL_MODE (0x03)
103 
104 #define BMP3_ENABLE (0x01)
105 #define BMP3_DISABLE (0x00)
106 
107 /* Sensor component selection macros. These values are internal for API implementation.
108  * Don't relate this t0 data sheet.
109  */
110 #define BMP3_PRESS (1)
111 #define BMP3_TEMP (1 << 1)
112 #define BMP3_ALL (0x03)
113 
114 /* Macros related to size */
115 #define BMP3_CALIB_DATA_LEN (21)
116 #define BMP3_P_T_DATA_LEN (6)
117 
118 /* Macros to select the which sensor settings are to be set by the user.
119  * These values are internal for API implementation. Don't relate this to
120  * data sheet. */
121 #define BMP3_PRESS_EN_SEL (1 << 1)
122 #define BMP3_TEMP_EN_SEL (1 << 2)
123 #define BMP3_PRESS_OS_SEL (1 << 4)
124 
125 /* Macros for bit masking */
126 #define BMP3_OP_MODE_MSK (0x30)
127 #define BMP3_OP_MODE_POS (0x04)
128 
129 #define BMP3_PRESS_EN_MSK (0x01)
130 
131 #define BMP3_TEMP_EN_MSK (0x02)
132 #define BMP3_TEMP_EN_POS (0x01)
133 
134 #define BMP3_IIR_FILTER_MSK (0x0E)
135 #define BMP3_IIR_FILTER_POS (0x01)
136 
137 #define BMP3_ODR_MSK (0x1F)
138 
139 #define BMP3_PRESS_OS_MSK (0x07)
140 
141 #define BMP3_TEMP_OS_MSK (0x38)
142 #define BMP3_TEMP_OS_POS (0x03)
143 
144 #define BMP3_SET_BITS(reg_data, bitname, data) \
145  ((reg_data & ~(bitname##_MSK)) | \
146  ((data << bitname##_POS) & bitname##_MSK))
147 
148 /* Macro variant to handle the bitname position if it is zero */
149 #define BMP3_SET_BITS_POS_0(reg_data, bitname, data) \
150  ((reg_data & ~(bitname##_MSK)) | \
151  (data & bitname##_MSK))
152 
153 #define BMP3_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> \
154  (bitname##_POS))
155 
156 /* Macro variant to handle the bitname position if it is zero */
157 #define BMP3_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK))
158 
159 // From https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/self-test/bmp3_selftest.c
160 #define BMP3_POST_SLEEP_WAIT_TIME 5000
161 #define BMP3_POST_RESET_WAIT_TIME 2000
162 #define BMP3_POST_INIT_WAIT_TIME 40000
163 #define BMP3_TRIM_CRC_DATA_ADDR 0x30
164 #define BPM3_CMD_SOFT_RESET 0xB6
165 #define BMP3_ODR_ADDR 0x1D
166 #define BMP3_IIR_ADDR 0x1F
167 
168 // https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
169 /* Power control settings */
170 #define POWER_CNTL (0x0006)
171 /* Odr and filter settings */
172 #define ODR_FILTER (0x00F0)
173 /* Interrupt control settings */
174 #define INT_CTRL (0x0708)
175 /* Advance settings */
176 #define ADV_SETT (0x1800)
177 
178 #pragma pack(push,1)
180  uint16_t par_t1;
181  uint16_t par_t2;
182  int8_t par_t3;
183 
184  int16_t par_p1;
185  int16_t par_p2;
186  int8_t par_p3;
187  int8_t par_p4;
188  uint16_t par_p5;
189  uint16_t par_p6;
190  int8_t par_p7;
191  int8_t par_p8;
192  int16_t par_p9;
193  int8_t par_p10;
194  int8_t par_p11;
195 
196 }; //calibration data
197 
198 struct data_s {
199  uint8_t p_msb;
200  uint8_t p_lsb;
201  uint8_t p_xlsb;
202 
203  uint8_t t_msb;
204  uint8_t t_lsb;
205  uint8_t t_xlsb;
206 }; // data
207 
209  /**
210  * @ Trim Variables
211  */
212 
213  /**@{*/
214  uint16_t par_t1;
215  uint16_t par_t2;
216  int8_t par_t3;
217  int16_t par_p1;
218  int16_t par_p2;
219  int8_t par_p3;
220  int8_t par_p4;
221  uint16_t par_p5;
222  uint16_t par_p6;
223  int8_t par_p7;
224  int8_t par_p8;
225  int16_t par_p9;
226  int8_t par_p10;
227  int8_t par_p11;
228  int64_t t_lin;
229 
230  /**@}*/
231 };
232 #pragma pack(pop)
233 
234 /*!
235  * bmp3 sensor structure which comprises of temperature and pressure data.
236  */
237 struct bmp3_data {
238  /* Compensated temperature */
239  int64_t temperature;
240 
241  /* Compensated pressure */
242  uint64_t pressure;
243 };
244 
245 /*!
246  * Calibration data
247  */
249  /*! Register data */
250  struct bmp3_reg_calib_data reg_calib_data;
251 };
252 
253 /*!
254  * bmp3 sensor structure which comprises of un-compensated temperature
255  * and pressure data.
256  */
258  /*! un-compensated pressure */
259  uint32_t pressure;
260 
261  /*! un-compensated temperature */
262  uint32_t temperature;
263 };
264 
266  float t1;
267  float t2;
268  float t3;
269 
270  float p1;
271  float p2;
272  float p3;
273  float p4;
274  float p5;
275  float p6;
276  float p7;
277  float p8;
278  float p9;
279 };
280 
281 /*
282  * BMP388 internal constants and data structures.
283  */
284 class IBMP388
285 {
286 public:
287  virtual ~IBMP388() = default;
288 
289  virtual int init() = 0;
290 
291  // read reg value
292  virtual uint8_t get_reg(uint8_t addr) = 0;
293 
294  // bulk read reg value
295  virtual int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) = 0;
296 
297  // write reg value
298  virtual int set_reg(uint8_t value, uint8_t addr) = 0;
299 
300  // bulk read of data into buffer, return same pointer
301  virtual data_s *get_data(uint8_t addr) = 0;
302 
303  // bulk read of calibration data into buffer, return same pointer
304  virtual calibration_s *get_calibration(uint8_t addr) = 0;
305 
306  virtual uint32_t get_device_id() const = 0;
307 };
308 
309 class BMP388 : public px4::ScheduledWorkItem
310 {
311 public:
312  BMP388(IBMP388 *interface);
313  virtual ~BMP388();
314 
315  virtual int init();
316 
317  void print_info();
318 
319 private:
321  IBMP388 *_interface{nullptr};
322 
323  unsigned _measure_interval{0}; // interval in microseconds needed to measure
324  uint8_t _osr_t{BMP3_OVERSAMPLING_2X}; // oversampling rate, temperature
325  uint8_t _osr_p{BMP3_OVERSAMPLING_16X}; // oversampling rate, pressure
326  uint8_t _odr{BMP3_ODR_50_HZ}; // output data rate
327  uint8_t _iir_coef{BMP3_IIR_FILTER_DISABLE}; // IIR coefficient
328 
332 
333  calibration_s *_cal {nullptr}; // stored calibration constants
334 
335  bool _collect_phase{false};
336 
337  void Run() override;
338  void start();
339  void stop();
340  int measure();
341  int collect(); //get results and publish
342  uint32_t get_measurement_time(uint8_t osr_t, uint8_t osr_p);
343 
344  bool soft_reset();
345  bool get_calib_data();
346  bool validate_trimming_param();
347  bool set_sensor_settings();
348  bool set_op_mode(uint8_t op_mode);
349 
350  bool get_sensor_data(uint8_t sensor_comp, struct bmp3_data *comp_data);
351  bool compensate_data(uint8_t sensor_comp, const struct bmp3_uncomp_data *uncomp_data, struct bmp3_data *comp_data);
352 };
353 
354 
355 /* interface factories */
356 extern IBMP388 *bmp388_spi_interface(uint8_t busnum, uint32_t device);
357 extern IBMP388 *bmp388_i2c_interface(uint8_t busnum, uint32_t device);
358 typedef IBMP388 *(*BMP388_constructor)(uint8_t, uint32_t);
float p6
Definition: bmp388.h:275
uint16_t par_t1
@ Trim Variables
Definition: bmp388.h:214
int16_t par_p1
Definition: bmp388.h:217
#define BMP3_OVERSAMPLING_2X
Definition: bmp388.h:57
uint8_t p_xlsb
Definition: bmp388.h:201
int16_t par_p2
Definition: bmp388.h:185
uint64_t pressure
Definition: bmp388.h:242
uint32_t pressure
Definition: bmp388.h:259
int16_t par_p2
Definition: bmp388.h:218
float p9
Definition: bmp388.h:278
int16_t par_p1
Definition: bmp388.h:184
uint16_t par_p5
Definition: bmp388.h:221
uint16_t par_t2
Definition: bmp388.h:181
float p2
Definition: bmp388.h:271
float p4
Definition: bmp388.h:273
uint8_t t_lsb
Definition: bmp388.h:204
#define BMP3_IIR_FILTER_DISABLE
Definition: bmp388.h:64
perf_counter_t _comms_errors
Definition: bmp388.h:331
uint8_t t_msb
Definition: bmp388.h:203
PX4Barometer _px4_baro
Definition: bmp388.h:320
static void stop()
Definition: dataman.cpp:1491
float t3
Definition: bmp388.h:268
uint16_t par_p6
Definition: bmp388.h:189
uint8_t p_lsb
Definition: bmp388.h:200
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
High-resolution timer with callouts and timekeeping.
uint32_t temperature
Definition: bmp388.h:262
Definition: bmp388.h:309
float t2
Definition: bmp388.h:267
int8_t par_p8
Definition: bmp388.h:191
Definition: bmp388.h:198
Header common to all counters.
perf_counter_t _sample_perf
Definition: bmp388.h:329
void init()
Activates/configures the hardware registers.
perf_counter_t _measure_perf
Definition: bmp388.h:330
float p5
Definition: bmp388.h:274
float p8
Definition: bmp388.h:277
uint16_t par_t2
Definition: bmp388.h:215
int16_t par_p9
Definition: bmp388.h:192
int8_t par_p11
Definition: bmp388.h:194
float p3
Definition: bmp388.h:272
float p7
Definition: bmp388.h:276
uint8_t p_msb
Definition: bmp388.h:199
static int start()
Definition: dataman.cpp:1452
IBMP388 * bmp388_i2c_interface(uint8_t busnum, uint32_t device)
int8_t par_p4
Definition: bmp388.h:187
int8_t par_p10
Definition: bmp388.h:193
#define BMP3_ODR_50_HZ
Definition: bmp388.h:76
float p1
Definition: bmp388.h:270
uint16_t par_p5
Definition: bmp388.h:188
#define BMP3_OVERSAMPLING_16X
Definition: bmp388.h:60
IBMP388 * bmp388_spi_interface(uint8_t busnum, uint32_t device)
int64_t temperature
Definition: bmp388.h:239
uint16_t par_t1
Definition: bmp388.h:180
uint16_t par_p6
Definition: bmp388.h:222
Barometric pressure sensor driver interface.
float t1
Definition: bmp388.h:266
int8_t par_t3
Definition: bmp388.h:182
int8_t par_p3
Definition: bmp388.h:186
int16_t par_p9
Definition: bmp388.h:225
uint8_t t_xlsb
Definition: bmp388.h:205
Performance measuring tools.
int8_t par_p7
Definition: bmp388.h:190