APM:Libraries
AP_Baro_BMP085.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_BMP085.h"
16 
17 #include <utility>
18 #include <stdio.h>
19 
20 #include <AP_Common/AP_Common.h>
21 #include <AP_HAL/AP_HAL.h>
22 
23 extern const AP_HAL::HAL &hal;
24 
25 #define BMP085_OVERSAMPLING_ULTRALOWPOWER 0
26 #define BMP085_OVERSAMPLING_STANDARD 1
27 #define BMP085_OVERSAMPLING_HIGHRES 2
28 #define BMP085_OVERSAMPLING_ULTRAHIGHRES 3
29 
30 #ifndef BMP085_EOC
31 #define BMP085_EOC -1
32 #define OVERSAMPLING BMP085_OVERSAMPLING_ULTRAHIGHRES
33 #else
34 #define OVERSAMPLING BMP085_OVERSAMPLING_HIGHRES
35 #endif
36 
38  : AP_Baro_Backend(baro)
39  , _dev(std::move(dev))
40 { }
41 
43 {
44 
45  if (!dev) {
46  return nullptr;
47  }
48 
49  AP_Baro_BMP085 *sensor = new AP_Baro_BMP085(baro, std::move(dev));
50  if (!sensor || !sensor->_init()) {
51  delete sensor;
52  return nullptr;
53  }
54  return sensor;
55 
56 }
57 
59 {
60  union {
61  uint8_t buff[22];
62  uint16_t wb[11];
63  } bb;
64 
65  // get pointer to i2c bus semaphore
67 
68  // take i2c bus sempahore
69  if (!sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
70  AP_HAL::panic("BMP085: unable to get semaphore");
71  }
72 
73  if (BMP085_EOC >= 0) {
74  _eoc = hal.gpio->channel(BMP085_EOC);
76  }
77 
78 
79  uint8_t id;
80 
81  if (!_dev->read_registers(0xD0, &id, 1)) {
82  sem->give();
83  return false;
84  }
85 
86  if (id!=0x55) {
87  return false; // not BMP180
88  }
89 
90 
91  _dev->read_registers(0xD1, &_vers, 1);
92 
93  bool prom_ok=false;
94  _type=0;
95 
96  // We read the calibration data registers
97  if (_dev->read_registers(0xAA, bb.buff, sizeof(bb.buff))) {
98  prom_ok=true;
99 
100  }
101 
102  if (!prom_ok) {
103  if (_read_prom((uint16_t *)&bb.wb[0])) { // BMP180 requires reads by 2 bytes
104  prom_ok=true;
105  _type=1;
106  }
107  }
108  if (!prom_ok) {
109  sem->give();
110  return false;
111  }
112 
113  ac1 = ((int16_t)bb.buff[0] << 8) | bb.buff[1];
114  ac2 = ((int16_t)bb.buff[2] << 8) | bb.buff[3];
115  ac3 = ((int16_t)bb.buff[4] << 8) | bb.buff[5];
116  ac4 = ((int16_t)bb.buff[6] << 8) | bb.buff[7];
117  ac5 = ((int16_t)bb.buff[8] << 8) | bb.buff[9];
118  ac6 = ((int16_t)bb.buff[10]<< 8) | bb.buff[11];
119  b1 = ((int16_t)bb.buff[12] << 8) | bb.buff[13];
120  b2 = ((int16_t)bb.buff[14] << 8) | bb.buff[15];
121  mb = ((int16_t)bb.buff[16] << 8) | bb.buff[17];
122  mc = ((int16_t)bb.buff[18] << 8) | bb.buff[19];
123  md = ((int16_t)bb.buff[20] << 8) | bb.buff[21];
124 
125  if ((ac1==0 || ac1==-1) ||
126  (ac2==0 || ac2==-1) ||
127  (ac3==0 || ac3==-1) ||
128  (ac4==0 || ac4==0xFFFF) ||
129  (ac5==0 || ac5==0xFFFF) ||
130  (ac6==0 || ac6==0xFFFF)) {
131  return false;
132  }
133 
136 
137  // Send a command to read temperature
138  _cmd_read_temp();
139 
140  _state = 0;
141 
143 
144  sem->give();
145 
147  return true;
148 }
149 
150 uint16_t AP_Baro_BMP085::_read_prom_word(uint8_t word)
151 {
152  const uint8_t reg = 0xAA + (word << 1);
153  uint8_t val[2];
154  if (!_dev->transfer(&reg, 1, val, sizeof(val))) {
155  return 0;
156  }
157  return (val[0] << 8) | val[1];
158 }
159 
160 bool AP_Baro_BMP085::_read_prom(uint16_t *prom)
161 {
162  bool all_zero = true;
163  for (uint8_t i = 0; i < 11; i++) {
164  prom[i] = _read_prom_word(i);
165  if (prom[i] != 0) {
166  all_zero = false;
167  }
168  }
169 
170  if (all_zero) {
171  return false;
172  }
173 
174  return true;
175 }
176 
177 /*
178  This is a state machine. Acumulate a new sensor reading.
179  */
181 {
182  if (!_data_ready()) {
183  return;
184  }
185 
186  if (_state == 0) {
187  _read_temp();
188  } else if (_read_pressure()) {
189  _calculate();
190  }
191 
192  _state++;
193  if (_state == 25) {
194  _state = 0;
195  _cmd_read_temp();
196  } else {
198  }
199 }
200 
201 /*
202  transfer data to the frontend
203  */
205 {
206  if (_sem->take_nonblocking()) {
207  if (!_has_sample) {
208  _sem->give();
209  return;
210  }
211 
212  float temperature = 0.1f * _temp;
213  float pressure = _pressure_filter.getf();
214 
215  _copy_to_frontend(_instance, pressure, temperature);
216  _sem->give();
217  }
218 }
219 
220 // Send command to Read Pressure
222 {
223  _dev->write_register(0xF4, 0x34 + (OVERSAMPLING << 6));
225 }
226 
227 // Read raw pressure values
229 {
230  uint8_t buf[3];
231  if (_dev->read_registers(0xF6, buf, sizeof(buf))) {
232  _raw_pressure = (((uint32_t)buf[0] << 16)
233  | ((uint32_t)buf[1] << 8)
234  | ((uint32_t)buf[2])) >> (8 - OVERSAMPLING);
235  return true;
236  }
237 
238  uint8_t xlsb;
239  if (_dev->read_registers(0xF6, buf, 2) && _dev->read_registers(0xF8, &xlsb, 1)) {
240  _raw_pressure = (((uint32_t)buf[0] << 16)
241  | ((uint32_t)buf[1] << 8)
242  | ((uint32_t)xlsb)) >> (8 - OVERSAMPLING);
243  return true;
244  }
245 
248  return false;
249 }
250 
251 // Send Command to Read Temperature
253 {
254  _dev->write_register(0xF4, 0x2E);
256 }
257 
258 // Read raw temperature values
260 {
261  uint8_t buf[2];
262  int32_t _temp_sensor;
263 
264  if (!_dev->read_registers(0xF6, buf, sizeof(buf))) {
266  return;
267  }
268  _temp_sensor = buf[0];
269  _temp_sensor = (_temp_sensor << 8) | buf[1];
270 
271  _raw_temp = _temp_sensor;
272 }
273 
274 // _calculate Temperature and Pressure in real units.
276 {
277  int32_t x1, x2, x3, b3, b5, b6, p;
278  uint32_t b4, b7;
279  int32_t tmp;
280 
281  // See Datasheet page 13 for this formulas
282  // Based also on Jee Labs BMP085 example code. Thanks for share.
283  // Temperature calculations
284  x1 = ((int32_t)_raw_temp - ac6) * ac5 >> 15;
285  x2 = ((int32_t) mc << 11) / (x1 + md);
286  b5 = x1 + x2;
287  _temp = (b5 + 8) >> 4;
288 
289  // Pressure calculations
290  b6 = b5 - 4000;
291  x1 = (b2 * (b6 * b6 >> 12)) >> 11;
292  x2 = ac2 * b6 >> 11;
293  x3 = x1 + x2;
294  //b3 = (((int32_t) ac1 * 4 + x3)<<OVERSAMPLING + 2) >> 2; // BAD
295  //b3 = ((int32_t) ac1 * 4 + x3 + 2) >> 2; //OK for OVERSAMPLING=0
296  tmp = ac1;
297  tmp = (tmp*4 + x3)<<OVERSAMPLING;
298  b3 = (tmp+2)/4;
299  x1 = ac3 * b6 >> 13;
300  x2 = (b1 * (b6 * b6 >> 12)) >> 16;
301  x3 = ((x1 + x2) + 2) >> 2;
302  b4 = (ac4 * (uint32_t)(x3 + 32768)) >> 15;
303  b7 = ((uint32_t) _raw_pressure - b3) * (50000 >> OVERSAMPLING);
304  p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2;
305 
306  x1 = (p >> 8) * (p >> 8);
307  x1 = (x1 * 3038) >> 16;
308  x2 = (-7357 * p) >> 16;
309  p += ((x1 + x2 + 3791) >> 4);
310 
311  if (!pressure_ok(p)) {
312  return;
313  }
314 
317  _has_sample = true;
318  _sem->give();
319  }
320 }
321 
323 {
324  if (BMP085_EOC >= 0) {
325  return _eoc->read();
326  }
327 
328  // No EOC pin: use time from last read instead.
329  if (_state == 0) {
331  }
332 
333  uint32_t conversion_time_msec;
334 
335  switch (OVERSAMPLING) {
337  conversion_time_msec = 5;
338  break;
340  conversion_time_msec = 8;
341  break;
343  conversion_time_msec = 14;
344  break;
346  conversion_time_msec = 26;
347  default:
348  break;
349  }
350 
351  return AP_HAL::millis() > _last_press_read_command_time + conversion_time_msec;
352 }
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
AP_HAL::DigitalSource * _eoc
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
AP_HAL::Semaphore * _sem
virtual AP_HAL::Semaphore * get_semaphore()=0
uint16_t _read_prom_word(uint8_t word)
AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define BMP085_EOC
uint32_t _last_press_read_command_time
uint32_t _last_temp_read_command_time
virtual void mode(uint8_t output)=0
AP_HAL::OwnPtr< AP_HAL::Device > _dev
float temperature
Definition: Airspeed.cpp:32
int32_t _raw_pressure
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Baro & _frontend
AverageIntegralFilter< int32_t, int32_t, 10 > _pressure_filter
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
virtual T apply(T sample) override
virtual bool set_speed(Speed speed)=0
static AP_Baro baro
Definition: ModuleTest.cpp:18
uint32_t millis()
Definition: system.cpp:157
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
bool pressure_ok(float press)
#define OVERSAMPLING
#define BMP085_OVERSAMPLING_STANDARD
virtual bool give()=0
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)=0
#define HAL_GPIO_INPUT
Definition: GPIO.h:7
Common definitions and utility routines for the ArduPilot libraries.
virtual uint8_t read()=0
bool _read_prom(uint16_t *prom)
AP_HAL::GPIO * gpio
Definition: HAL.h:111
#define BMP085_OVERSAMPLING_ULTRAHIGHRES
#define BMP085_OVERSAMPLING_ULTRALOWPOWER
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
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define BMP085_OVERSAMPLING_HIGHRES
virtual float getf()
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125