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_KellerLD.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
16
#include "AP_Baro_KellerLD.h"
17
18
#if AP_BARO_KELLERLD_ENABLED
19
20
#include <utility>
21
#include <stdio.h>
22
23
#include <AP_Math/AP_Math.h>
24
25
#define KELLER_DEBUG 0
26
27
#if KELLER_DEBUG
28
# define Debug(fmt, args ...) do {printf(fmt "\n", ## args);} while(0)
29
#else
30
# define Debug(fmt, args ...)
31
#endif
32
33
extern const AP_HAL::HAL &hal;
34
35
// sensor metadata register
36
static const uint8_t CMD_METADATA_PMODE = 0x12;
37
// Measurement range registers
38
static const uint8_t CMD_PRANGE_MIN_MSB = 0x13;
39
static const uint8_t CMD_PRANGE_MIN_LSB = 0x14;
40
static const uint8_t CMD_PRANGE_MAX_MSB = 0x15;
41
static const uint8_t CMD_PRANGE_MAX_LSB = 0x16;
42
43
// write to this address to start pressure measurement
44
static const uint8_t CMD_REQUEST_MEASUREMENT = 0xAC;
45
46
AP_Baro_KellerLD::AP_Baro_KellerLD(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
47
: AP_Baro_Backend(baro)
48
, _dev(std::move(dev))
49
{
50
}
51
52
// Look for the device on the bus and see if it responds appropriately
53
AP_Baro_Backend *AP_Baro_KellerLD::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
54
{
55
if (!dev) {
56
return nullptr;
57
}
58
AP_Baro_KellerLD *sensor = NEW_NOTHROW AP_Baro_KellerLD(baro, std::move(dev));
59
if (!sensor || !sensor->_init()) {
60
delete sensor;
61
return nullptr;
62
}
63
return sensor;
64
}
65
66
67
// convenience function to work around device transfer oddities
68
bool AP_Baro_KellerLD::transfer_with_delays(uint8_t *send, uint8_t sendlen, uint8_t *recv, uint8_t recvlen)
69
{
70
if (!_dev->transfer(send, sendlen, nullptr, 0)) {
71
return false;
72
}
73
hal.scheduler->delay(1);
74
75
if(!_dev->transfer(nullptr, 0, recv, recvlen)) {
76
return false;
77
}
78
hal.scheduler->delay(1);
79
return true;
80
}
81
82
// This device has some undocumented finicky quirks and requires
83
// delays when reading out the measurement range, but for some reason
84
// this isn't an issue when requesting measurements. This is why we
85
// need to split the transfers with delays like this. (Using
86
// AP_HAL::I2CDevice::set_split_transfers will not work with these
87
// sensors)
88
bool AP_Baro_KellerLD::read_measurement_limit(float *limit, uint8_t msb_addr, uint8_t lsb_addr)
89
{
90
uint8_t data[3];
91
92
if (!transfer_with_delays(&msb_addr, 1, data, ARRAY_SIZE(data))) {
93
return false;
94
}
95
96
const uint16_t ms_word = (data[1] << 8) | data[2];
97
Debug("0x%02x: %d [%d, %d, %d]", msb_addr, ms_word, data[0], data[1], data[2]);
98
99
if (!transfer_with_delays(&lsb_addr, 1, data, ARRAY_SIZE(data))) {
100
return false;
101
}
102
103
const uint16_t ls_word = (data[1] << 8) | data[2];
104
Debug("0x%02x: %d [%d, %d, %d]", lsb_addr, ls_word, data[0], data[1], data[2]);
105
106
const uint32_t cal_data = (ms_word << 16) | ls_word;
107
memcpy(limit, &cal_data, sizeof(*limit));
108
109
if (isinf(*limit) || isnan(*limit)) {
110
return false;
111
}
112
113
Debug("data: %d, float: %.2f", cal_data, _p_min);
114
return true;
115
}
116
117
bool AP_Baro_KellerLD::read_cal()
118
{
119
// Read out pressure measurement range
120
if (!read_measurement_limit(&_p_min, CMD_PRANGE_MIN_MSB, CMD_PRANGE_MIN_LSB)) {
121
return false;
122
}
123
124
if (!read_measurement_limit(&_p_max, CMD_PRANGE_MAX_MSB, CMD_PRANGE_MAX_LSB)) {
125
return false;
126
}
127
128
if (_p_max <= _p_min) {
129
return false;
130
}
131
132
return true;
133
}
134
135
// Read sensor P-Mode type and set pressure reference offset
136
// This determines the pressure offset based on the type of sensor
137
// vented to atmosphere, gauged to vacuum, or gauged to standard sea-level pressure
138
bool AP_Baro_KellerLD::read_mode_type()
139
{
140
uint8_t cmd = CMD_METADATA_PMODE;
141
uint8_t data[3];
142
if (!transfer_with_delays(&cmd, 1, data, ARRAY_SIZE(data))) {
143
return false;
144
}
145
146
// Byte 3, Bit 0 & 1: Represents P-Mode
147
// "Communication Protocol 4 LD…9 LD", Version 2.6 pg 12 of 25
148
// https://keller-druck.com/?d=VeMYAQBxgoSNjUSHbdnBTU
149
_p_mode = (SensorMode)(data[2] & 0b11);
150
151
// update pressure offset based on P-Mode
152
switch (_p_mode) {
153
case SensorMode::PR_MODE:
154
// PR-Mode vented gauge sensor
155
// pressure reads zero when the pressure outside is equal to the pressure inside the enclosure
156
_p_mode_offset = _frontend.get_pressure(0);
157
break;
158
case SensorMode::PA_MODE:
159
// PA-Mode sealed gauge sensor
160
// pressure reads zero when the pressure outside is equal to 1.0 bar
161
// i.e., the pressure at which the vent is sealed
162
_p_mode_offset = 1.0;
163
break;
164
case SensorMode::PAA_MODE:
165
// PAA-mode Absolute sensor (zero at vacuum)
166
_p_mode_offset = 0.0;
167
break;
168
case SensorMode::UNDEFINED:
169
// we should give an error here
170
printf("KellerLD Device Mode UNDEFINED\n");
171
return false;
172
}
173
174
return true;
175
}
176
177
// We read out the measurement range to be used in raw value conversions
178
bool AP_Baro_KellerLD::_init()
179
{
180
if (!_dev) {
181
return false;
182
}
183
184
WITH_SEMAPHORE(_dev->get_semaphore());
185
186
// high retries for init
187
_dev->set_retries(10);
188
189
if (!read_cal()) {
190
printf("Cal read bad!\n");
191
return false;
192
}
193
194
if (!read_mode_type()) {
195
printf("Mode_Type read bad!\n");
196
return false;
197
}
198
199
printf("Keller LD found on bus %u address 0x%02x\n", _dev->bus_num(), _dev->get_bus_address());
200
201
// Send a command to take a measurement
202
_dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);
203
204
memset(&_accum, 0, sizeof(_accum));
205
206
_instance = _frontend.register_sensor();
207
208
_dev->set_device_type(DEVTYPE_BARO_KELLERLD);
209
set_bus_id(_instance, _dev->get_bus_id());
210
211
_frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);
212
213
// lower retries for run
214
_dev->set_retries(3);
215
216
// The sensor needs time to take a deep breath after reading out the calibration...
217
hal.scheduler->delay(150);
218
219
// Request 50Hz update
220
// The sensor really struggles with any jitter in timing at 100Hz, and will sometimes start reading out all zeros
221
_dev->register_periodic_callback(20 * AP_USEC_PER_MSEC,
222
FUNCTOR_BIND_MEMBER(&AP_Baro_KellerLD::_timer, void));
223
return true;
224
}
225
226
// Read out most recent measurement from sensor hw
227
bool AP_Baro_KellerLD::_read()
228
{
229
uint8_t data[5];
230
if (!_dev->transfer(nullptr, 0, data, sizeof(data))) {
231
Debug("Keller LD read failed!");
232
return false;
233
}
234
235
//uint8_t status = data[0];
236
uint16_t pressure_raw = (data[1] << 8) | data[2];
237
uint16_t temperature_raw = (data[3] << 8) | data[4];
238
239
#if KELLER_DEBUG
240
static uint8_t samples = 0;
241
if (samples < 3) {
242
samples++;
243
Debug("data: [%d, %d, %d, %d, %d]", data[0], data[1], data[2], data[3], data[4]);
244
Debug("pressure_raw: %d\ttemperature_raw: %d", pressure_raw, temperature_raw);
245
}
246
#endif
247
248
if (pressure_raw == 0 || temperature_raw == 0) {
249
Debug("Keller: bad read");
250
return false;
251
}
252
253
if (!pressure_ok(pressure_raw)) {
254
return false;
255
}
256
257
WITH_SEMAPHORE(_sem);
258
259
_update_and_wrap_accumulator(pressure_raw, temperature_raw, 128);
260
261
return true;
262
}
263
264
// Periodic callback, regular update at 50Hz
265
// Read out most recent measurement, and request another
266
// Max conversion time according to datasheet is ~8ms, so
267
// max update rate is ~125Hz, yet we struggle to get consistent
268
// performance/data at 100Hz
269
void AP_Baro_KellerLD::_timer(void)
270
{
271
_read();
272
_dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);
273
}
274
275
// Accumulate a reading, shrink if necessary to prevent overflow
276
void AP_Baro_KellerLD::_update_and_wrap_accumulator(uint16_t pressure, uint16_t temperature, uint8_t max_count)
277
{
278
_accum.sum_pressure += pressure;
279
_accum.sum_temperature += temperature;
280
_accum.num_samples += 1;
281
282
if (_accum.num_samples == max_count) {
283
_accum.sum_pressure /= 2;
284
_accum.sum_temperature /= 2;
285
_accum.num_samples /= 2;
286
}
287
}
288
289
// Take the average of accumulated values and push to frontend
290
void AP_Baro_KellerLD::update()
291
{
292
float sum_pressure, sum_temperature;
293
float num_samples;
294
295
// update _p_mode_offset if vented guage
296
if (_p_mode == SensorMode::PR_MODE) {
297
// we need to get the pressure from on-board barometer
298
_p_mode_offset = _frontend.get_pressure(0);
299
}
300
301
{
302
WITH_SEMAPHORE(_sem);
303
304
if (_accum.num_samples == 0) {
305
return;
306
}
307
308
sum_pressure = _accum.sum_pressure;
309
sum_temperature = _accum.sum_temperature;
310
num_samples = _accum.num_samples;
311
memset(&_accum, 0, sizeof(_accum));
312
}
313
314
uint16_t raw_pressure_avg = sum_pressure / num_samples;
315
uint16_t raw_temperature_avg = sum_temperature / num_samples;
316
317
// per datasheet
318
float pressure = (raw_pressure_avg - 16384) * (_p_max - _p_min) / 32768 + _p_min + _p_mode_offset;
319
pressure *= 100000; // bar -> Pascal
320
float temperature = ((raw_temperature_avg >> 4) - 24) * 0.05f - 50;
321
322
_copy_to_frontend(_instance, pressure, temperature);
323
}
324
325
#endif // AP_BARO_KELLERLD_ENABLED
326
327