Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro_SPL06.cpp
9610 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_SPL06.h"
16
17
#if AP_BARO_SPL06_ENABLED
18
19
#include <strings.h>
20
#include <AP_Math/definitions.h>
21
22
extern const AP_HAL::HAL &hal;
23
24
#define SPL06_CHIP_ID 0x10
25
#define SPA06_CHIP_ID 0x11
26
27
#define SPL06_REG_PRESSURE_B2 0x00 // Pressure MSB Register
28
#define SPL06_REG_PRESSURE_B1 0x01 // Pressure middle byte Register
29
#define SPL06_REG_PRESSURE_B0 0x02 // Pressure LSB Register
30
#define SPL06_REG_PRESSURE_START SPL06_REG_PRESSURE_B2
31
#define SPL06_PRESSURE_LEN 3 // 24 bits, 3 bytes
32
#define SPL06_REG_TEMPERATURE_B2 0x03 // Temperature MSB Register
33
#define SPL06_REG_TEMPERATURE_B1 0x04 // Temperature middle byte Register
34
#define SPL06_REG_TEMPERATURE_B0 0x05 // Temperature LSB Register
35
#define SPL06_REG_TEMPERATURE_START SPL06_REG_TEMPERATURE_B2
36
#define SPL06_TEMPERATURE_LEN 3 // 24 bits, 3 bytes
37
#define SPL06_REG_PRESSURE_CFG 0x06 // Pressure config
38
#define SPL06_REG_TEMPERATURE_CFG 0x07 // Temperature config
39
#define SPL06_REG_MODE_AND_STATUS 0x08 // Mode and status
40
#define SPL06_REG_INT_AND_FIFO_CFG 0x09 // Interrupt and FIFO config
41
#define SPL06_REG_INT_STATUS 0x0A // Interrupt and FIFO config
42
#define SPL06_REG_FIFO_STATUS 0x0B // Interrupt and FIFO config
43
#define SPL06_REG_RST 0x0C // Softreset Register
44
#define SPL06_REG_CHIP_ID 0x0D // Chip ID Register
45
#define SPL06_REG_CALIB_COEFFS_START 0x10
46
#define SPL06_REG_CALIB_COEFFS_END 0x21
47
#define SPA06_REG_CALIB_COEFFS_END 0x24
48
49
// PRESSURE_CFG_REG
50
#define SPL06_PRES_RATE_32HZ (0x05 << 4)
51
52
// TEMPERATURE_CFG_REG
53
#define SPL06_TEMP_USE_EXT_SENSOR (1<<7)
54
#define SPL06_TEMP_RATE_32HZ (0x05 << 4)
55
56
// MODE_AND_STATUS_REG
57
#define SPL06_MEAS_PRESSURE (1<<0) // measure pressure
58
#define SPL06_MEAS_TEMPERATURE (1<<1) // measure temperature
59
#define SPL06_MEAS_CON_PRE_TEM 0x07
60
61
#define SPL06_MEAS_CFG_CONTINUOUS (1<<2)
62
#define SPL06_MEAS_CFG_PRESSURE_RDY (1<<4)
63
#define SPL06_MEAS_CFG_TEMPERATURE_RDY (1<<5)
64
#define SPL06_MEAS_CFG_SENSOR_RDY (1<<6)
65
#define SPL06_MEAS_CFG_COEFFS_RDY (1<<7)
66
67
// INT_AND_FIFO_CFG_REG
68
#define SPL06_PRESSURE_RESULT_BIT_SHIFT (1<<2) // necessary for pressure oversampling > 8
69
#define SPL06_TEMPERATURE_RESULT_BIT_SHIFT (1<<3) // necessary for temperature oversampling > 8
70
71
// Don't set oversampling higher than 8 or the measurement time will be higher than 20ms (timer period)
72
#define SPL06_PRESSURE_OVERSAMPLING 8
73
#define SPL06_TEMPERATURE_OVERSAMPLING 8
74
75
#define SPL06_OVERSAMPLING_TO_REG_VALUE(n) (ffs(n)-1)
76
77
#define SPL06_BACKGROUND_SAMPLE_RATE 32
78
79
// enable Background Mode for continuous measurement
80
#ifndef AP_BARO_SPL06_BACKGROUND_ENABLE
81
#define AP_BARO_SPL06_BACKGROUND_ENABLE 1
82
#endif
83
84
AP_Baro_SPL06::AP_Baro_SPL06(AP_Baro &baro, AP_HAL::Device &dev)
85
: AP_Baro_Backend(baro)
86
, _dev(&dev)
87
{
88
}
89
90
AP_Baro_Backend *AP_Baro_SPL06::probe(AP_Baro &baro, AP_HAL::Device &dev)
91
{
92
if (dev.bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
93
dev.set_read_flag(0x80);
94
}
95
96
AP_Baro_SPL06 *sensor = NEW_NOTHROW AP_Baro_SPL06(baro, dev);
97
if (!sensor || !sensor->_init()) {
98
delete sensor;
99
return nullptr;
100
}
101
return sensor;
102
}
103
104
bool AP_Baro_SPL06::_init()
105
{
106
if (!_dev) {
107
return false;
108
}
109
WITH_SEMAPHORE(_dev->get_semaphore());
110
111
_dev->set_speed(AP_HAL::Device::SPEED_HIGH);
112
113
uint8_t whoami;
114
115
// Sometimes SPL06 has init problems, that's due to failure of reading using SPI for the first time. The SPL06 is a dual
116
// protocol sensor(I2C and SPI), sometimes it takes one SPI operation to convert it to SPI mode after it starts up.
117
118
for (uint8_t i=0; i<5; i++) {
119
if (_dev->read_registers(SPL06_REG_CHIP_ID, &whoami, 1)) {
120
switch(whoami) {
121
case SPL06_CHIP_ID:
122
type = Type::SPL06;
123
break;
124
case SPA06_CHIP_ID:
125
type = Type::SPA06;
126
break;
127
default:
128
type = Type::UNKNOWN;
129
break;
130
}
131
}
132
133
if (type != Type::UNKNOWN)
134
break;
135
}
136
137
if (type == Type::UNKNOWN) {
138
return false;
139
}
140
141
// read the calibration data
142
uint8_t SPL06_CALIB_COEFFS_LEN = 18;
143
switch(type) {
144
case Type::SPL06:
145
SPL06_CALIB_COEFFS_LEN = SPL06_REG_CALIB_COEFFS_END - SPL06_REG_CALIB_COEFFS_START + 1;
146
break;
147
case Type::SPA06:
148
SPL06_CALIB_COEFFS_LEN = SPA06_REG_CALIB_COEFFS_END - SPL06_REG_CALIB_COEFFS_START + 1;
149
break;
150
default:
151
break;
152
}
153
154
bool ready = false;
155
for (uint8_t i=0; i<5; i++) {
156
uint8_t status = 0;
157
if (_dev->read_registers(SPL06_REG_MODE_AND_STATUS, &status, 1)) {
158
if ((status & 1<<7U) && (status & 1<<6U)) {
159
ready = true;
160
break;
161
}
162
}
163
hal.scheduler->delay_microseconds(100);
164
}
165
166
if (!ready) {
167
return false;
168
}
169
170
uint8_t buf[SPL06_CALIB_COEFFS_LEN];
171
172
#define READ_LENGTH 9
173
174
for (uint8_t i = 0; i < ARRAY_SIZE(buf); ) {
175
ssize_t chunk = MIN(READ_LENGTH, SPL06_CALIB_COEFFS_LEN - i);
176
if (!_dev->read_registers(SPL06_REG_CALIB_COEFFS_START + i, buf + i, chunk)) {
177
return false;
178
}
179
i += chunk;
180
}
181
182
// 0x11 c0 [3:0] + 0x10 c0 [11:4]
183
_c0 = get_twos_complement(((uint32_t)buf[0] << 4) | (((uint32_t)buf[1] >> 4) & 0x0F), 12);
184
// 0x11 c1 [11:8] + 0x12 c1 [7:0]
185
_c1 = get_twos_complement((((uint32_t)buf[1] & 0x0F) << 8) | (uint32_t)buf[2], 12);
186
// 0x13 c00 [19:12] + 0x14 c00 [11:4] + 0x15 c00 [3:0]
187
_c00 = get_twos_complement(((uint32_t)buf[3] << 12) | ((uint32_t)buf[4] << 4) | (((uint32_t)buf[5] >> 4) & 0x0F), 20);
188
// 0x15 c10 [19:16] + 0x16 c10 [15:8] + 0x17 c10 [7:0]
189
_c10 = get_twos_complement((((uint32_t)buf[5] & 0x0F) << 16) | ((uint32_t)buf[6] << 8) | (uint32_t)buf[7], 20);
190
// 0x18 c01 [15:8] + 0x19 c01 [7:0]
191
_c01 = get_twos_complement(((uint32_t)buf[8] << 8) | (uint32_t)buf[9], 16);
192
// 0x1A c11 [15:8] + 0x1B c11 [7:0]
193
_c11 = get_twos_complement(((uint32_t)buf[10] << 8) | (uint32_t)buf[11], 16);
194
// 0x1C c20 [15:8] + 0x1D c20 [7:0]
195
_c20 = get_twos_complement(((uint32_t)buf[12] << 8) | (uint32_t)buf[13], 16);
196
// 0x1E c21 [15:8] + 0x1F c21 [7:0]
197
_c21 = get_twos_complement(((uint32_t)buf[14] << 8) | (uint32_t)buf[15], 16);
198
// 0x20 c30 [15:8] + 0x21 c30 [7:0]
199
_c30 = get_twos_complement(((uint32_t)buf[16] << 8) | (uint32_t)buf[17], 16);
200
201
if(type == Type::SPA06) {
202
// 0x23 c31 [3:0] + 0x22 c31 [11:4]
203
_c31 = get_twos_complement(((uint32_t)buf[18] << 4) | (((uint32_t)buf[19] >> 4) & 0x0F), 12);
204
// 0x23 c40 [11:8] + 0x24 c40 [7:0]
205
_c40 = get_twos_complement((((uint32_t)buf[19] & 0x0F) << 8) | (uint32_t)buf[20], 12);
206
}
207
208
const uint8_t tmp_sensor = (type == Type::SPA06 ? 0 : SPL06_TEMP_USE_EXT_SENSOR);
209
#if AP_BARO_SPL06_BACKGROUND_ENABLE
210
// setup temperature and pressure measurements
211
_dev->setup_checked_registers(4, 20);
212
213
//set rate and oversampling
214
_dev->write_register(SPL06_REG_TEMPERATURE_CFG, tmp_sensor | SPL06_TEMP_RATE_32HZ | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_TEMPERATURE_OVERSAMPLING), true);
215
_dev->write_register(SPL06_REG_PRESSURE_CFG, SPL06_PRES_RATE_32HZ | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_PRESSURE_OVERSAMPLING), true);
216
217
//enable background mode
218
_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_CON_PRE_TEM, true);
219
#else
220
// setup temperature and pressure measurements
221
_dev->setup_checked_registers(3, 20);
222
223
_dev->write_register(SPL06_REG_TEMPERATURE_CFG, tmp_sensor | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_TEMPERATURE_OVERSAMPLING), true);
224
_dev->write_register(SPL06_REG_PRESSURE_CFG, SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_PRESSURE_OVERSAMPLING), true);
225
#endif //AP_BARO_SPL06_BACKGROUND_ENABLE
226
227
uint8_t int_and_fifo_reg_value = 0;
228
if (SPL06_TEMPERATURE_OVERSAMPLING > 8) {
229
int_and_fifo_reg_value |= SPL06_TEMPERATURE_RESULT_BIT_SHIFT;
230
}
231
if (SPL06_PRESSURE_OVERSAMPLING > 8) {
232
int_and_fifo_reg_value |= SPL06_PRESSURE_RESULT_BIT_SHIFT;
233
}
234
_dev->write_register(SPL06_REG_INT_AND_FIFO_CFG, int_and_fifo_reg_value, true);
235
236
_instance = _frontend.register_sensor();
237
238
if(type == Type::SPA06) {
239
_dev->set_device_type(DEVTYPE_BARO_SPA06);
240
} else {
241
_dev->set_device_type(DEVTYPE_BARO_SPL06);
242
}
243
244
set_bus_id(_instance, _dev->get_bus_id());
245
246
// request 50Hz update
247
_timer_counter = -1;
248
#if AP_BARO_SPL06_BACKGROUND_ENABLE
249
_dev->register_periodic_callback(1000000/SPL06_BACKGROUND_SAMPLE_RATE, FUNCTOR_BIND_MEMBER(&AP_Baro_SPL06::_timer, void));
250
#else
251
_dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_SPL06::_timer, void));
252
#endif //AP_BARO_SPL06_BACKGROUND_ENABLE
253
254
return true;
255
}
256
257
int32_t AP_Baro_SPL06::raw_value_scale_factor(uint8_t oversampling)
258
{
259
// From the datasheet page 13
260
switch(oversampling)
261
{
262
case 1: return 524288;
263
case 2: return 1572864;
264
case 4: return 3670016;
265
case 8: return 7864320;
266
case 16: return 253952;
267
case 32: return 516096;
268
case 64: return 1040384;
269
case 128: return 2088960;
270
default: return -1; // invalid
271
}
272
}
273
274
// accumulate a new sensor reading
275
void AP_Baro_SPL06::_timer(void)
276
{
277
uint8_t buf[3];
278
279
#if AP_BARO_SPL06_BACKGROUND_ENABLE
280
_dev->read_registers(SPL06_REG_TEMPERATURE_START, buf, sizeof(buf));
281
_update_temperature((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));
282
283
_dev->read_registers(SPL06_REG_PRESSURE_START, buf, sizeof(buf));
284
_update_pressure((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));
285
#else
286
//command mode
287
if ((_timer_counter == -1) || (_timer_counter == 49)) {
288
// First call and every second start a temperature measurement (50Hz call)
289
_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_TEMPERATURE, false);
290
_timer_counter = 0; // Next cycle we are reading the temperature
291
} else if (_timer_counter == 0) {
292
// A temperature measurement had been started during the previous call
293
_dev->read_registers(SPL06_REG_TEMPERATURE_START, buf, sizeof(buf));
294
_update_temperature((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));
295
_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_PRESSURE, false);
296
_timer_counter += 1;
297
} else {
298
// The rest of the time read the latest pressure and start a new measurement
299
_dev->read_registers(SPL06_REG_PRESSURE_START, buf, sizeof(buf));
300
_update_pressure((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));
301
_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_PRESSURE, false);
302
_timer_counter += 1;
303
}
304
#endif //AP_BARO_SPL06_BACKGROUND_ENABLE
305
306
_dev->check_next_register();
307
}
308
309
// transfer data to the frontend
310
void AP_Baro_SPL06::update(void)
311
{
312
WITH_SEMAPHORE(_sem);
313
314
if (_pressure_count == 0) {
315
return;
316
}
317
318
_copy_to_frontend(_instance, _pressure_sum/_pressure_count, _temperature);
319
320
_pressure_sum = 0;
321
_pressure_count = 0;
322
}
323
324
// calculate temperature
325
void AP_Baro_SPL06::_update_temperature(int32_t temp_raw)
326
{
327
_temp_raw = (float)temp_raw / raw_value_scale_factor(SPL06_TEMPERATURE_OVERSAMPLING);
328
const float temp_comp = (float)_c0 / 2 + _temp_raw * _c1;
329
330
WITH_SEMAPHORE(_sem);
331
332
_temperature = temp_comp;
333
}
334
335
// calculate pressure
336
void AP_Baro_SPL06::_update_pressure(int32_t press_raw)
337
{
338
const float press_raw_sc = (float)press_raw / raw_value_scale_factor(SPL06_PRESSURE_OVERSAMPLING);
339
float pressure_cal = 0;
340
float press_temp_comp = 0;
341
342
switch(type) {
343
case Type::SPL06:
344
pressure_cal = (float)_c00 + press_raw_sc * ((float)_c10 + press_raw_sc * ((float)_c20 + press_raw_sc * _c30));
345
press_temp_comp = _temp_raw * ((float)_c01 + press_raw_sc * ((float)_c11 + press_raw_sc * _c21));
346
break;
347
case Type::SPA06:
348
pressure_cal = (float)_c00 + press_raw_sc * ((float)_c10 + press_raw_sc * ((float)_c20 + press_raw_sc * ((float)_c30 + press_raw_sc * _c40)));
349
press_temp_comp = _temp_raw * ((float)_c01 + press_raw_sc * ((float)_c11 + press_raw_sc * ((float)_c21) + press_raw_sc * _c31));
350
break;
351
default:
352
break;
353
}
354
355
const float press_comp = pressure_cal + press_temp_comp;
356
357
if (!pressure_ok(press_comp)) {
358
return;
359
}
360
361
WITH_SEMAPHORE(_sem);
362
363
_pressure_sum += press_comp;
364
_pressure_count++;
365
}
366
367
#endif // AP_BARO_SPL06_ENABLED
368
369