CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro_BMP085.cpp
Views: 1798
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 <utility>
20
#include <stdio.h>
21
22
#include <AP_Common/AP_Common.h>
23
#include <AP_HAL/AP_HAL.h>
24
25
extern const AP_HAL::HAL &hal;
26
27
#define BMP085_OVERSAMPLING_ULTRALOWPOWER 0
28
#define BMP085_OVERSAMPLING_STANDARD 1
29
#define BMP085_OVERSAMPLING_HIGHRES 2
30
#define BMP085_OVERSAMPLING_ULTRAHIGHRES 3
31
32
#ifndef BMP085_EOC
33
#define BMP085_EOC -1
34
#define OVERSAMPLING BMP085_OVERSAMPLING_ULTRAHIGHRES
35
#else
36
#define OVERSAMPLING BMP085_OVERSAMPLING_HIGHRES
37
#endif
38
39
AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
40
: AP_Baro_Backend(baro)
41
, _dev(std::move(dev))
42
{ }
43
44
AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
45
{
46
47
if (!dev) {
48
return nullptr;
49
}
50
51
AP_Baro_BMP085 *sensor = NEW_NOTHROW AP_Baro_BMP085(baro, std::move(dev));
52
if (!sensor || !sensor->_init()) {
53
delete sensor;
54
return nullptr;
55
}
56
return sensor;
57
58
}
59
60
bool AP_Baro_BMP085::_init()
61
{
62
if (!_dev) {
63
return false;
64
}
65
union {
66
uint8_t buff[22];
67
uint16_t wb[11];
68
} bb;
69
70
// get pointer to i2c bus semaphore
71
AP_HAL::Semaphore *sem = _dev->get_semaphore();
72
73
// take i2c bus semaphore
74
WITH_SEMAPHORE(sem);
75
76
if (BMP085_EOC >= 0) {
77
_eoc = hal.gpio->channel(BMP085_EOC);
78
_eoc->mode(HAL_GPIO_INPUT);
79
}
80
81
82
uint8_t id;
83
84
if (!_dev->read_registers(0xD0, &id, 1)) {
85
return false;
86
}
87
88
if (id!=0x55) {
89
return false; // not BMP180
90
}
91
92
93
_dev->read_registers(0xD1, &_vers, 1);
94
95
bool prom_ok=false;
96
_type=0;
97
98
// We read the calibration data registers
99
if (_dev->read_registers(0xAA, bb.buff, sizeof(bb.buff))) {
100
prom_ok=true;
101
102
}
103
104
if (!prom_ok) {
105
if (_read_prom((uint16_t *)&bb.wb[0])) { // BMP180 requires reads by 2 bytes
106
prom_ok=true;
107
_type=1;
108
}
109
}
110
if (!prom_ok) {
111
return false;
112
}
113
114
ac1 = ((int16_t)bb.buff[0] << 8) | bb.buff[1];
115
ac2 = ((int16_t)bb.buff[2] << 8) | bb.buff[3];
116
ac3 = ((int16_t)bb.buff[4] << 8) | bb.buff[5];
117
ac4 = ((int16_t)bb.buff[6] << 8) | bb.buff[7];
118
ac5 = ((int16_t)bb.buff[8] << 8) | bb.buff[9];
119
ac6 = ((int16_t)bb.buff[10]<< 8) | bb.buff[11];
120
b1 = ((int16_t)bb.buff[12] << 8) | bb.buff[13];
121
b2 = ((int16_t)bb.buff[14] << 8) | bb.buff[15];
122
mb = ((int16_t)bb.buff[16] << 8) | bb.buff[17];
123
mc = ((int16_t)bb.buff[18] << 8) | bb.buff[19];
124
md = ((int16_t)bb.buff[20] << 8) | bb.buff[21];
125
126
if ((ac1==0 || ac1==-1) ||
127
(ac2==0 || ac2==-1) ||
128
(ac3==0 || ac3==-1) ||
129
(ac4==0 || ac4==0xFFFF) ||
130
(ac5==0 || ac5==0xFFFF) ||
131
(ac6==0 || ac6==0xFFFF)) {
132
return false;
133
}
134
135
_last_press_read_command_time = 0;
136
_last_temp_read_command_time = 0;
137
138
// Send a command to read temperature
139
_cmd_read_temp();
140
141
_state = 0;
142
143
_instance = _frontend.register_sensor();
144
145
_dev->set_device_type(DEVTYPE_BARO_BMP085);
146
set_bus_id(_instance, _dev->get_bus_id());
147
148
_dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&AP_Baro_BMP085::_timer, void));
149
return true;
150
}
151
152
uint16_t AP_Baro_BMP085::_read_prom_word(uint8_t word)
153
{
154
const uint8_t reg = 0xAA + (word << 1);
155
uint8_t val[2];
156
if (!_dev->transfer(&reg, 1, val, sizeof(val))) {
157
return 0;
158
}
159
return (val[0] << 8) | val[1];
160
}
161
162
bool AP_Baro_BMP085::_read_prom(uint16_t *prom)
163
{
164
bool all_zero = true;
165
for (uint8_t i = 0; i < 11; i++) {
166
prom[i] = _read_prom_word(i);
167
if (prom[i] != 0) {
168
all_zero = false;
169
}
170
}
171
172
if (all_zero) {
173
return false;
174
}
175
176
return true;
177
}
178
179
/*
180
This is a state machine. Accumulate a new sensor reading.
181
*/
182
void AP_Baro_BMP085::_timer(void)
183
{
184
if (!_data_ready()) {
185
return;
186
}
187
188
if (_state == 0) {
189
_read_temp();
190
} else if (_read_pressure()) {
191
_calculate();
192
}
193
194
_state++;
195
if (_state == 25) {
196
_state = 0;
197
_cmd_read_temp();
198
} else {
199
_cmd_read_pressure();
200
}
201
}
202
203
/*
204
transfer data to the frontend
205
*/
206
void AP_Baro_BMP085::update(void)
207
{
208
WITH_SEMAPHORE(_sem);
209
210
if (!_has_sample) {
211
return;
212
}
213
214
float temperature = 0.1f * _temp;
215
float pressure = _pressure_filter.getf();
216
217
_copy_to_frontend(_instance, pressure, temperature);
218
}
219
220
// Send command to Read Pressure
221
void AP_Baro_BMP085::_cmd_read_pressure()
222
{
223
_dev->write_register(0xF4, 0x34 + (OVERSAMPLING << 6));
224
_last_press_read_command_time = AP_HAL::millis();
225
}
226
227
// Read raw pressure values
228
bool AP_Baro_BMP085::_read_pressure()
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
246
_last_press_read_command_time = AP_HAL::millis() + 1000;
247
_dev->set_speed(AP_HAL::Device::SPEED_LOW);
248
return false;
249
}
250
251
// Send Command to Read Temperature
252
void AP_Baro_BMP085::_cmd_read_temp()
253
{
254
_dev->write_register(0xF4, 0x2E);
255
_last_temp_read_command_time = AP_HAL::millis();
256
}
257
258
// Read raw temperature values
259
void AP_Baro_BMP085::_read_temp()
260
{
261
uint8_t buf[2];
262
int32_t _temp_sensor;
263
264
if (!_dev->read_registers(0xF6, buf, sizeof(buf))) {
265
_dev->set_speed(AP_HAL::Device::SPEED_LOW);
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.
275
void AP_Baro_BMP085::_calculate()
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
315
WITH_SEMAPHORE(_sem);
316
317
_pressure_filter.apply(p);
318
_has_sample = true;
319
}
320
321
bool AP_Baro_BMP085::_data_ready()
322
{
323
if (BMP085_EOC >= 0) {
324
return _eoc->read();
325
}
326
327
// No EOC pin: use time from last read instead.
328
if (_state == 0) {
329
return AP_HAL::millis() - _last_temp_read_command_time > 5u;
330
}
331
332
uint32_t conversion_time_msec;
333
334
switch (OVERSAMPLING) {
335
case BMP085_OVERSAMPLING_ULTRALOWPOWER:
336
conversion_time_msec = 5;
337
break;
338
case BMP085_OVERSAMPLING_STANDARD:
339
conversion_time_msec = 8;
340
break;
341
case BMP085_OVERSAMPLING_HIGHRES:
342
conversion_time_msec = 14;
343
break;
344
case BMP085_OVERSAMPLING_ULTRAHIGHRES:
345
conversion_time_msec = 26;
346
break;
347
default:
348
break;
349
}
350
351
return AP_HAL::millis() - _last_press_read_command_time > conversion_time_msec;
352
}
353
354
#endif // AP_BARO_BMP085_ENABLED
355
356