APM:Libraries
AP_Baro_BMP280.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #include "AP_Baro_BMP280.h"
16 
17 #include <utility>
18 
19 extern const AP_HAL::HAL &hal;
20 
21 #define BMP280_MODE_SLEEP 0
22 #define BMP280_MODE_FORCED 1
23 #define BMP280_MODE_NORMAL 3
24 #define BMP280_MODE BMP280_MODE_NORMAL
25 
26 #define BMP280_OVERSAMPLING_1 1
27 #define BMP280_OVERSAMPLING_2 2
28 #define BMP280_OVERSAMPLING_4 3
29 #define BMP280_OVERSAMPLING_8 4
30 #define BMP280_OVERSAMPLING_16 5
31 #define BMP280_OVERSAMPLING_P BMP280_OVERSAMPLING_16
32 #define BMP280_OVERSAMPLING_T BMP280_OVERSAMPLING_2
33 
34 #define BMP280_FILTER_COEFFICIENT 2
35 
36 #define BMP280_ID 0x58
37 
38 #define BMP280_REG_CALIB 0x88
39 #define BMP280_REG_ID 0xD0
40 #define BMP280_REG_RESET 0xE0
41 #define BMP280_REG_STATUS 0xF3
42 #define BMP280_REG_CTRL_MEAS 0xF4
43 #define BMP280_REG_CONFIG 0xF5
44 #define BMP280_REG_DATA 0xF7
45 
47  : AP_Baro_Backend(baro)
48  , _dev(std::move(dev))
49 {
50 }
51 
54 {
55  if (!dev) {
56  return nullptr;
57  }
58 
59  AP_Baro_BMP280 *sensor = new AP_Baro_BMP280(baro, std::move(dev));
60  if (!sensor || !sensor->_init()) {
61  delete sensor;
62  return nullptr;
63  }
64  return sensor;
65 }
66 
68 {
70  return false;
71  }
72 
73  _has_sample = false;
74 
76 
77  uint8_t whoami;
78  if (!_dev->read_registers(BMP280_REG_ID, &whoami, 1) ||
79  whoami != BMP280_ID) {
80  // not a BMP280
81  _dev->get_semaphore()->give();
82  return false;
83  }
84 
85  // read the calibration data
86  uint8_t buf[24];
87  _dev->read_registers(BMP280_REG_CALIB, buf, sizeof(buf));
88 
89  _t1 = ((int16_t)buf[1] << 8) | buf[0];
90  _t2 = ((int16_t)buf[3] << 8) | buf[2];
91  _t3 = ((int16_t)buf[5] << 8) | buf[4];
92  _p1 = ((int16_t)buf[7] << 8) | buf[6];
93  _p2 = ((int16_t)buf[9] << 8) | buf[8];
94  _p3 = ((int16_t)buf[11] << 8) | buf[10];
95  _p4 = ((int16_t)buf[13] << 8) | buf[12];
96  _p5 = ((int16_t)buf[15] << 8) | buf[14];
97  _p6 = ((int16_t)buf[17] << 8) | buf[16];
98  _p7 = ((int16_t)buf[19] << 8) | buf[18];
99  _p8 = ((int16_t)buf[21] << 8) | buf[20];
100  _p9 = ((int16_t)buf[23] << 8) | buf[22];
101 
102  // SPI write needs bit mask
103  uint8_t mask = 0xFF;
105  mask = 0x7F;
106  }
107 
110 
112 
114 
115  _dev->get_semaphore()->give();
116 
117  // request 50Hz update
119 
120  return true;
121 }
122 
123 
124 
125 // acumulate a new sensor reading
127 {
128  uint8_t buf[6];
129 
130  _dev->read_registers(BMP280_REG_DATA, buf, sizeof(buf));
131 
132  _update_temperature((buf[3] << 12) | (buf[4] << 4) | (buf[5] >> 4));
133  _update_pressure((buf[0] << 12) | (buf[1] << 4) | (buf[2] >> 4));
134 }
135 
136 // transfer data to the frontend
138 {
139  if (_sem->take_nonblocking()) {
140  if (!_has_sample) {
141  _sem->give();
142  return;
143  }
144 
146  _has_sample = false;
147  _sem->give();
148  }
149 }
150 
151 // calculate temperature
153 {
154  int32_t var1, var2, t;
155 
156  // according to datasheet page 22
157  var1 = ((((temp_raw >> 3) - ((int32_t)_t1 << 1))) * ((int32_t)_t2)) >> 11;
158  var2 = (((((temp_raw >> 4) - ((int32_t)_t1)) * ((temp_raw >> 4) - ((int32_t)_t1))) >> 12) * ((int32_t)_t3)) >> 14;
159  _t_fine = var1 + var2;
160  t = (_t_fine * 5 + 128) >> 8;
161 
162  const float temp = ((float)t) / 100.0f;
163 
165  _temperature = temp;
166  _sem->give();
167  }
168 }
169 
170 // calculate pressure
171 void AP_Baro_BMP280::_update_pressure(int32_t press_raw)
172 {
173  int64_t var1, var2, p;
174 
175  // according to datasheet page 22
176  var1 = ((int64_t)_t_fine) - 128000;
177  var2 = var1 * var1 * (int64_t)_p6;
178  var2 = var2 + ((var1 * (int64_t)_p5) << 17);
179  var2 = var2 + (((int64_t)_p4) << 35);
180  var1 = ((var1 * var1 * (int64_t)_p3) >> 8) + ((var1 * (int64_t)_p2) << 12);
181  var1 = (((((int64_t)1) << 47) + var1)) * ((int64_t)_p1) >> 33;
182 
183  if (var1 == 0) {
184  return;
185  }
186 
187  p = 1048576 - press_raw;
188  p = (((p << 31) - var2) * 3125) / var1;
189  var1 = (((int64_t)_p9) * (p >> 13) * (p >> 13)) >> 25;
190  var2 = (((int64_t)_p8) * p) >> 19;
191  p = ((p + var1 + var2) >> 8) + (((int64_t)_p7) << 4);
192 
193 
194  const float press = (float)p / 256.0f;
195  if (!pressure_ok(press)) {
196  return;
197  }
199  _pressure = press;
200  _has_sample = true;
201  _sem->give();
202  }
203 }
#define BMP280_REG_DATA
#define BMP280_OVERSAMPLING_P
#define AP_USEC_PER_MSEC
Definition: definitions.h:93
#define BMP280_FILTER_COEFFICIENT
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define BMP280_REG_CTRL_MEAS
bool _init(void)
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
AP_HAL::Semaphore * _sem
virtual AP_HAL::Semaphore * get_semaphore()=0
AP_Baro_BMP280(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define BMP280_REG_ID
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
AP_HAL::OwnPtr< AP_HAL::Device > _dev
void _update_temperature(int32_t)
#define BMP280_REG_CONFIG
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Baro & _frontend
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
virtual bool set_speed(Speed speed)=0
#define f(i)
#define BMP280_ID
static AP_Baro baro
Definition: ModuleTest.cpp:18
enum BusType bus_type(void) const
Definition: Device.h:50
bool pressure_ok(float press)
virtual bool give()=0
#define BMP280_REG_CALIB
#define BMP280_OVERSAMPLING_T
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
#define BMP280_MODE
void _update_pressure(int32_t)