forked from iNavFlight/inav
-
Notifications
You must be signed in to change notification settings - Fork 0
/
barometer.c
311 lines (266 loc) · 8.89 KB
/
barometer.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <math.h>
#include "platform.h"
#include "build/debug.h"
#include "common/maths.h"
#include "common/time.h"
#include "common/utils.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/barometer/barometer.h"
#include "drivers/barometer/barometer_bmp085.h"
#include "drivers/barometer/barometer_bmp280.h"
#include "drivers/barometer/barometer_fake.h"
#include "drivers/barometer/barometer_ms56xx.h"
#include "drivers/logging.h"
#include "drivers/time.h"
#include "fc/runtime_config.h"
#include "sensors/barometer.h"
#include "sensors/sensors.h"
#include "flight/hil.h"
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
baro_t baro; // barometer access functions
PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 0);
#ifdef USE_BARO
#define BARO_HARDWARE_DEFAULT BARO_AUTODETECT
#else
#define BARO_HARDWARE_DEFAULT BARO_NONE
#endif
PG_RESET_TEMPLATE(barometerConfig_t, barometerConfig,
.baro_hardware = BARO_HARDWARE_DEFAULT,
.use_median_filtering = 1
);
#ifdef USE_BARO
static timeMs_t baroCalibrationTimeout = 0;
static bool baroCalibrationFinished = false;
static float baroGroundAltitude = 0;
static float baroGroundPressure = 101325.0f; // 101325 pascal, 1 standard atmosphere
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
{
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
baroSensor_e baroHardware = BARO_NONE;
requestedSensors[SENSOR_INDEX_BARO] = baroHardwareToUse;
switch (baroHardwareToUse) {
case BARO_AUTODETECT:
case BARO_BMP085:
#ifdef USE_BARO_BMP085
if (bmp085Detect(dev)) {
baroHardware = BARO_BMP085;
break;
}
#endif
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
if (baroHardwareToUse != BARO_AUTODETECT) {
break;
}
FALLTHROUGH;
case BARO_MS5607:
#ifdef USE_BARO_MS5607
if (ms5607Detect(dev)) {
baroHardware = BARO_MS5607;
break;
}
#endif
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
if (baroHardwareToUse != BARO_AUTODETECT) {
break;
}
FALLTHROUGH;
case BARO_MS5611:
#ifdef USE_BARO_MS5611
if (ms5611Detect(dev)) {
baroHardware = BARO_MS5611;
break;
}
#endif
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
if (baroHardwareToUse != BARO_AUTODETECT) {
break;
}
FALLTHROUGH;
case BARO_BMP280:
#if defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)
if (bmp280Detect(dev)) {
baroHardware = BARO_BMP280;
break;
}
#endif
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
if (baroHardwareToUse != BARO_AUTODETECT) {
break;
}
FALLTHROUGH;
case BARO_FAKE:
#ifdef USE_FAKE_BARO
if (fakeBaroDetect(dev)) {
baroHardware = BARO_FAKE;
break;
}
#endif
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
if (baroHardwareToUse != BARO_AUTODETECT) {
break;
}
FALLTHROUGH;
case BARO_NONE:
baroHardware = BARO_NONE;
break;
}
addBootlogEvent6(BOOT_EVENT_BARO_DETECTION, BOOT_EVENT_FLAGS_NONE, baroHardware, 0, 0, 0);
if (baroHardware == BARO_NONE) {
sensorsClear(SENSOR_BARO);
return false;
}
detectedSensors[SENSOR_INDEX_BARO] = baroHardware;
sensorsSet(SENSOR_BARO);
return true;
}
bool baroInit(void)
{
if (!baroDetect(&baro.dev, barometerConfig()->baro_hardware)) {
return false;
}
return true;
}
bool baroIsCalibrationComplete(void)
{
return baroCalibrationFinished;
}
void baroStartCalibration(void)
{
baroCalibrationTimeout = millis();
baroCalibrationFinished = false;
}
#define PRESSURE_SAMPLES_MEDIAN 3
/*
altitude pressure
0m 101325Pa
100m 100129Pa delta = 1196
1000m 89875Pa
1100m 88790Pa delta = 1085
At sea level an altitude change of 100m results in a pressure change of 1196Pa, at 1000m pressure change is 1085Pa
So set glitch threshold at 1000 - this represents an altitude change of approximately 100m.
*/
#define PRESSURE_DELTA_GLITCH_THRESHOLD 1000
static int32_t applyBarometerMedianFilter(int32_t newPressureReading)
{
static int32_t barometerFilterSamples[PRESSURE_SAMPLES_MEDIAN];
static int currentFilterSampleIndex = 0;
static bool medianFilterReady = false;
int nextSampleIndex = currentFilterSampleIndex + 1;
if (nextSampleIndex == PRESSURE_SAMPLES_MEDIAN) {
nextSampleIndex = 0;
medianFilterReady = true;
}
int previousSampleIndex = currentFilterSampleIndex - 1;
if (previousSampleIndex < 0) {
previousSampleIndex = PRESSURE_SAMPLES_MEDIAN - 1;
}
const int previousPressureReading = barometerFilterSamples[previousSampleIndex];
if (medianFilterReady) {
if (ABS(previousPressureReading - newPressureReading) < PRESSURE_DELTA_GLITCH_THRESHOLD) {
barometerFilterSamples[currentFilterSampleIndex] = newPressureReading;
currentFilterSampleIndex = nextSampleIndex;
return quickMedianFilter3(barometerFilterSamples);
} else {
// glitch threshold exceeded, so just return previous reading and don't add the glitched reading to the filter array
return barometerFilterSamples[previousSampleIndex];
}
} else {
barometerFilterSamples[currentFilterSampleIndex] = newPressureReading;
currentFilterSampleIndex = nextSampleIndex;
return newPressureReading;
}
}
typedef enum {
BAROMETER_NEEDS_SAMPLES = 0,
BAROMETER_NEEDS_CALCULATION
} barometerState_e;
uint32_t baroUpdate(void)
{
static barometerState_e state = BAROMETER_NEEDS_SAMPLES;
switch (state) {
default:
case BAROMETER_NEEDS_SAMPLES:
baro.dev.get_ut(&baro.dev);
baro.dev.start_up(&baro.dev);
state = BAROMETER_NEEDS_CALCULATION;
return baro.dev.up_delay;
break;
case BAROMETER_NEEDS_CALCULATION:
baro.dev.get_up(&baro.dev);
baro.dev.start_ut(&baro.dev);
baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature);
if (barometerConfig()->use_median_filtering) {
baro.baroPressure = applyBarometerMedianFilter(baro.baroPressure);
}
state = BAROMETER_NEEDS_SAMPLES;
return baro.dev.ut_delay;
break;
}
}
static float pressureToAltitude(const float pressure)
{
return (1.0f - powf(pressure / 101325.0f, 0.190295f)) * 4433000.0f;
}
static void performBaroCalibrationCycle(void)
{
const float baroGroundPressureError = baro.baroPressure - baroGroundPressure;
baroGroundPressure += baroGroundPressureError * 0.15f;
if (ABS(baroGroundPressureError) < (baroGroundPressure * 0.00005f)) { // 0.005% calibration error (should give c. 10cm calibration error)
if ((millis() - baroCalibrationTimeout) > 250) {
baroGroundAltitude = pressureToAltitude(baroGroundPressure);
baroCalibrationFinished = true;
DEBUG_TRACE_SYNC("Barometer calibration complete (%d)", lrintf(baroGroundAltitude));
}
}
else {
baroCalibrationTimeout = millis();
}
}
int32_t baroCalculateAltitude(void)
{
if (!baroIsCalibrationComplete()) {
performBaroCalibrationCycle();
baro.BaroAlt = 0;
}
else {
#ifdef HIL
if (hilActive) {
baro.BaroAlt = hilToFC.baroAlt;
return baro.BaroAlt;
}
#endif
// calculates height from ground via baro readings
baro.BaroAlt = pressureToAltitude(baro.baroPressure) - baroGroundAltitude;
}
return baro.BaroAlt;
}
int32_t baroGetLatestAltitude(void)
{
return baro.BaroAlt;
}
bool baroIsHealthy(void)
{
return true;
}
#endif /* BARO */