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