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