-
Notifications
You must be signed in to change notification settings - Fork 1.4k
/
gyro.c
527 lines (449 loc) · 15.5 KB
/
gyro.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
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
/*
* 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 <string.h>
#include <math.h>
#include "platform.h"
#include "build/build_config.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/maths.h"
#include "common/filter.h"
#include "common/utils.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_mpu.h"
#include "drivers/accgyro/accgyro_mpu3050.h"
#include "drivers/accgyro/accgyro_mpu6000.h"
#include "drivers/accgyro/accgyro_mpu6050.h"
#include "drivers/accgyro/accgyro_mpu6500.h"
#include "drivers/accgyro/accgyro_mpu9250.h"
#include "drivers/accgyro/accgyro_lsm303dlhc.h"
#include "drivers/accgyro/accgyro_l3g4200d.h"
#include "drivers/accgyro/accgyro_l3gd20.h"
#include "drivers/accgyro/accgyro_adxl345.h"
#include "drivers/accgyro/accgyro_mma845x.h"
#include "drivers/accgyro/accgyro_bma280.h"
#include "drivers/accgyro/accgyro_bmi160.h"
#include "drivers/accgyro/accgyro_icm20689.h"
#include "drivers/accgyro/accgyro_fake.h"
#include "drivers/io.h"
#include "drivers/logging.h"
#include "fc/config.h"
#include "fc/runtime_config.h"
#include "io/beeper.h"
#include "io/statusindicator.h"
#include "scheduler/scheduler.h"
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
#include "sensors/sensors.h"
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
FASTRAM gyro_t gyro; // gyro sensor object
STATIC_UNIT_TESTED gyroDev_t gyroDev0; // Not in FASTRAM since it may hold DMA buffers
STATIC_FASTRAM int16_t gyroTemperature0;
typedef struct gyroCalibration_s {
int32_t g[XYZ_AXIS_COUNT];
stdev_t var[XYZ_AXIS_COUNT];
uint16_t calibratingG;
} gyroCalibration_t;
STATIC_FASTRAM_UNIT_TESTED gyroCalibration_t gyroCalibration;
STATIC_FASTRAM int32_t gyroADC[XYZ_AXIS_COUNT];
STATIC_FASTRAM filterApplyFnPtr softLpfFilterApplyFn;
STATIC_FASTRAM void *softLpfFilter[XYZ_AXIS_COUNT];
#ifdef USE_GYRO_NOTCH_1
STATIC_FASTRAM filterApplyFnPtr notchFilter1ApplyFn;
STATIC_FASTRAM void *notchFilter1[XYZ_AXIS_COUNT];
#endif
#ifdef USE_GYRO_NOTCH_2
STATIC_FASTRAM filterApplyFnPtr notchFilter2ApplyFn;
STATIC_FASTRAM void *notchFilter2[XYZ_AXIS_COUNT];
#endif
#if defined(USE_GYRO_BIQUAD_RC_FIR2)
// gyro biquad RC FIR2 filter
STATIC_FASTRAM filterApplyFnPtr gyroFilterStage2ApplyFn;
STATIC_FASTRAM void *stage2Filter[XYZ_AXIS_COUNT];
#endif
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 3);
PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
.gyro_lpf = GYRO_LPF_42HZ, // 42HZ value is defined for Invensense/TDK gyros
.gyro_soft_lpf_hz = 60,
.gyro_align = ALIGN_DEFAULT,
.gyroMovementCalibrationThreshold = 32,
.looptime = 1000,
.gyroSync = 0,
.gyro_to_use = 0,
.gyro_soft_notch_hz_1 = 0,
.gyro_soft_notch_cutoff_1 = 1,
.gyro_soft_notch_hz_2 = 0,
.gyro_soft_notch_cutoff_2 = 1,
.gyro_stage2_lowpass_hz = 0
);
STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHardware)
{
dev->gyroAlign = ALIGN_DEFAULT;
switch (gyroHardware) {
case GYRO_AUTODETECT:
FALLTHROUGH;
#ifdef USE_GYRO_MPU6050
case GYRO_MPU6050:
if (mpu6050GyroDetect(dev)) {
gyroHardware = GYRO_MPU6050;
#ifdef GYRO_MPU6050_ALIGN
dev->gyroAlign = GYRO_MPU6050_ALIGN;
#endif
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_L3G4200D
case GYRO_L3G4200D:
if (l3g4200dDetect(dev)) {
gyroHardware = GYRO_L3G4200D;
#ifdef GYRO_L3G4200D_ALIGN
dev->gyroAlign = GYRO_L3G4200D_ALIGN;
#endif
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_MPU3050
case GYRO_MPU3050:
if (mpu3050Detect(dev)) {
gyroHardware = GYRO_MPU3050;
#ifdef GYRO_MPU3050_ALIGN
dev->gyroAlign = GYRO_MPU3050_ALIGN;
#endif
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_L3GD20
case GYRO_L3GD20:
if (l3gd20Detect(dev)) {
gyroHardware = GYRO_L3GD20;
#ifdef GYRO_L3GD20_ALIGN
dev->gyroAlign = GYRO_L3GD20_ALIGN;
#endif
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_MPU6000
case GYRO_MPU6000:
if (mpu6000GyroDetect(dev)) {
gyroHardware = GYRO_MPU6000;
#ifdef GYRO_MPU6000_ALIGN
dev->gyroAlign = GYRO_MPU6000_ALIGN;
#endif
break;
}
FALLTHROUGH;
#endif
#if defined(USE_GYRO_MPU6500)
case GYRO_MPU6500:
if (mpu6500GyroDetect(dev)) {
gyroHardware = GYRO_MPU6500;
#ifdef GYRO_MPU6500_ALIGN
dev->gyroAlign = GYRO_MPU6500_ALIGN;
#endif
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_MPU9250
case GYRO_MPU9250:
if (mpu9250GyroDetect(dev)) {
gyroHardware = GYRO_MPU9250;
#ifdef GYRO_MPU9250_ALIGN
dev->gyroAlign = GYRO_MPU9250_ALIGN;
#endif
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_BMI160
case GYRO_BMI160:
if (bmi160GyroDetect(dev)) {
gyroHardware = GYRO_BMI160;
#ifdef GYRO_BMI160_ALIGN
dev->gyroAlign = GYRO_BMI160_ALIGN;
#endif
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_ICM20689
case GYRO_ICM20689:
if (icm20689GyroDetect(dev)) {
gyroHardware = GYRO_ICM20689;
#ifdef GYRO_ICM20689_ALIGN
dev->gyroAlign = GYRO_ICM20689_ALIGN;
#endif
break;
}
FALLTHROUGH;
#endif
#ifdef USE_FAKE_GYRO
case GYRO_FAKE:
if (fakeGyroDetect(dev)) {
gyroHardware = GYRO_FAKE;
break;
}
FALLTHROUGH;
#endif
default:
case GYRO_NONE:
gyroHardware = GYRO_NONE;
}
addBootlogEvent6(BOOT_EVENT_GYRO_DETECTION, BOOT_EVENT_FLAGS_NONE, gyroHardware, 0, 0, 0);
if (gyroHardware != GYRO_NONE) {
detectedSensors[SENSOR_INDEX_GYRO] = gyroHardware;
sensorsSet(SENSOR_GYRO);
}
return gyroHardware;
}
bool gyroInit(void)
{
memset(&gyro, 0, sizeof(gyro));
// Set inertial sensor tag (for dual-gyro selection)
#ifdef USE_DUAL_GYRO
gyroDev0.imuSensorToUse = gyroConfig()->gyro_to_use;
#else
gyroDev0.imuSensorToUse = 0;
#endif
if (gyroDetect(&gyroDev0, GYRO_AUTODETECT) == GYRO_NONE) {
return false;
}
// Driver initialisation
gyroDev0.lpf = gyroConfig()->gyro_lpf;
gyroDev0.requestedSampleIntervalUs = gyroConfig()->looptime;
gyroDev0.sampleRateIntervalUs = gyroConfig()->looptime;
gyroDev0.initFn(&gyroDev0);
// initFn will initialize sampleRateIntervalUs to actual gyro sampling rate (if driver supports it). Calculate target looptime using that value
gyro.targetLooptime = gyroConfig()->gyroSync ? gyroDev0.sampleRateIntervalUs : gyroConfig()->looptime;
if (gyroConfig()->gyro_align != ALIGN_DEFAULT) {
gyroDev0.gyroAlign = gyroConfig()->gyro_align;
}
gyroInitFilters();
return true;
}
void gyroInitFilters(void)
{
STATIC_FASTRAM biquadFilter_t gyroFilterLPF[XYZ_AXIS_COUNT];
softLpfFilterApplyFn = nullFilterApply;
#ifdef USE_GYRO_NOTCH_1
STATIC_FASTRAM biquadFilter_t gyroFilterNotch_1[XYZ_AXIS_COUNT];
notchFilter1ApplyFn = nullFilterApply;
#endif
#ifdef USE_GYRO_NOTCH_2
STATIC_FASTRAM biquadFilter_t gyroFilterNotch_2[XYZ_AXIS_COUNT];
notchFilter2ApplyFn = nullFilterApply;
#endif
#ifdef USE_GYRO_BIQUAD_RC_FIR2
STATIC_FASTRAM biquadFilter_t gyroFilterStage2[XYZ_AXIS_COUNT];
gyroFilterStage2ApplyFn = nullFilterApply;
if (gyroConfig()->gyro_stage2_lowpass_hz > 0) {
gyroFilterStage2ApplyFn = (filterApplyFnPtr)biquadFilterApply;
for (int axis = 0; axis < 3; axis++) {
stage2Filter[axis] = &gyroFilterStage2[axis];
biquadRCFIR2FilterInit(stage2Filter[axis], gyroConfig()->gyro_stage2_lowpass_hz, getGyroUpdateRate());
}
}
#endif
if (gyroConfig()->gyro_soft_lpf_hz) {
softLpfFilterApplyFn = (filterApplyFnPtr)biquadFilterApply;
for (int axis = 0; axis < 3; axis++) {
softLpfFilter[axis] = &gyroFilterLPF[axis];
biquadFilterInitLPF(softLpfFilter[axis], gyroConfig()->gyro_soft_lpf_hz, getGyroUpdateRate());
}
}
#ifdef USE_GYRO_NOTCH_1
if (gyroConfig()->gyro_soft_notch_hz_1) {
notchFilter1ApplyFn = (filterApplyFnPtr)biquadFilterApply;
for (int axis = 0; axis < 3; axis++) {
notchFilter1[axis] = &gyroFilterNotch_1[axis];
biquadFilterInitNotch(notchFilter1[axis], getGyroUpdateRate(), gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_cutoff_1);
}
}
#endif
#ifdef USE_GYRO_NOTCH_2
if (gyroConfig()->gyro_soft_notch_hz_2) {
notchFilter2ApplyFn = (filterApplyFnPtr)biquadFilterApply;
for (int axis = 0; axis < 3; axis++) {
notchFilter2[axis] = &gyroFilterNotch_2[axis];
biquadFilterInitNotch(notchFilter2[axis], getGyroUpdateRate(), gyroConfig()->gyro_soft_notch_hz_2, gyroConfig()->gyro_soft_notch_cutoff_2);
}
}
#endif
}
void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired)
{
gyroCalibration.calibratingG = calibrationCyclesRequired;
}
STATIC_UNIT_TESTED bool isCalibrationComplete(gyroCalibration_t *gyroCalibration)
{
return gyroCalibration->calibratingG == 0;
}
bool gyroIsCalibrationComplete(void)
{
return gyroCalibration.calibratingG == 0;
}
static bool isOnFinalGyroCalibrationCycle(gyroCalibration_t *gyroCalibration)
{
return gyroCalibration->calibratingG == 1;
}
static bool isOnFirstGyroCalibrationCycle(gyroCalibration_t *gyroCalibration)
{
return gyroCalibration->calibratingG == CALIBRATING_GYRO_CYCLES;
}
STATIC_UNIT_TESTED void performGyroCalibration(gyroDev_t *dev, gyroCalibration_t *gyroCalibration, uint8_t gyroMovementCalibrationThreshold)
{
for (int axis = 0; axis < 3; axis++) {
// Reset g[axis] at start of calibration
if (isOnFirstGyroCalibrationCycle(gyroCalibration)) {
gyroCalibration->g[axis] = 0;
devClear(&gyroCalibration->var[axis]);
}
// Sum up CALIBRATING_GYRO_CYCLES readings
gyroCalibration->g[axis] += dev->gyroADCRaw[axis];
devPush(&gyroCalibration->var[axis], dev->gyroADCRaw[axis]);
// gyroZero is set to zero until calibration complete
dev->gyroZero[axis] = 0;
if (isOnFinalGyroCalibrationCycle(gyroCalibration)) {
const float stddev = devStandardDeviation(&gyroCalibration->var[axis]);
// check deviation and start over if the model was moved
if (gyroMovementCalibrationThreshold && stddev > gyroMovementCalibrationThreshold) {
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
return;
}
// calibration complete, so set the gyro zero values
dev->gyroZero[axis] = (gyroCalibration->g[axis] + (CALIBRATING_GYRO_CYCLES / 2)) / CALIBRATING_GYRO_CYCLES;
}
}
if (isOnFinalGyroCalibrationCycle(gyroCalibration)) {
DEBUG_TRACE_SYNC("Gyro calibration complete (%d, %d, %d)", dev->gyroZero[0], dev->gyroZero[1], dev->gyroZero[2]);
schedulerResetTaskStatistics(TASK_SELF); // so calibration cycles do not pollute tasks statistics
}
gyroCalibration->calibratingG--;
}
#ifdef USE_ASYNC_GYRO_PROCESSING
STATIC_FASTRAM float accumulatedRates[XYZ_AXIS_COUNT];
STATIC_FASTRAM timeUs_t accumulatedRateTimeUs;
static void gyroUpdateAccumulatedRates(timeDelta_t gyroUpdateDeltaUs)
{
accumulatedRateTimeUs += gyroUpdateDeltaUs;
const float gyroUpdateDelta = gyroUpdateDeltaUs * 1e-6f;
for (int axis = 0; axis < 3; axis++) {
accumulatedRates[axis] += gyro.gyroADCf[axis] * gyroUpdateDelta;
}
}
#endif
/*
* Calculate rotation rate in rad/s in body frame
*/
void gyroGetMeasuredRotationRate(fpVector3_t *measuredRotationRate)
{
#ifdef USE_ASYNC_GYRO_PROCESSING
const float accumulatedRateTime = accumulatedRateTimeUs * 1e-6;
accumulatedRateTimeUs = 0;
for (int axis = 0; axis < 3; axis++) {
measuredRotationRate->v[axis] = DEGREES_TO_RADIANS(accumulatedRates[axis] / accumulatedRateTime);
accumulatedRates[axis] = 0.0f;
}
#else
for (int axis = 0; axis < 3; axis++) {
measuredRotationRate->v[axis] = DEGREES_TO_RADIANS(gyro.gyroADCf[axis]);
}
#endif
}
void gyroUpdate(timeDelta_t gyroUpdateDeltaUs)
{
// range: +/- 8192; +/- 2000 deg/sec
if (gyroDev0.readFn(&gyroDev0)) {
if (isCalibrationComplete(&gyroCalibration)) {
// Copy gyro value into int32_t (to prevent overflow) and then apply calibration and alignment
gyroADC[X] = (int32_t)gyroDev0.gyroADCRaw[X] - (int32_t)gyroDev0.gyroZero[X];
gyroADC[Y] = (int32_t)gyroDev0.gyroADCRaw[Y] - (int32_t)gyroDev0.gyroZero[Y];
gyroADC[Z] = (int32_t)gyroDev0.gyroADCRaw[Z] - (int32_t)gyroDev0.gyroZero[Z];
applySensorAlignment(gyroADC, gyroADC, gyroDev0.gyroAlign);
applyBoardAlignment(gyroADC);
} else {
performGyroCalibration(&gyroDev0, &gyroCalibration, gyroConfig()->gyroMovementCalibrationThreshold);
// Reset gyro values to zero to prevent other code from using uncalibrated data
gyro.gyroADCf[X] = 0.0f;
gyro.gyroADCf[Y] = 0.0f;
gyro.gyroADCf[Z] = 0.0f;
// still calibrating, so no need to further process gyro data
return;
}
} else {
// no gyro reading to process
return;
}
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
float gyroADCf = (float)gyroADC[axis] * gyroDev0.scale;
DEBUG_SET(DEBUG_GYRO, axis, lrintf(gyroADCf));
if (axis < 2) {
DEBUG_SET(DEBUG_STAGE2, axis, lrintf(gyroADCf));
}
#ifdef USE_GYRO_BIQUAD_RC_FIR2
gyroADCf = gyroFilterStage2ApplyFn(stage2Filter[axis], gyroADCf);
#endif
if (axis < 2) {
DEBUG_SET(DEBUG_STAGE2, axis + 2, lrintf(gyroADCf));
}
gyroADCf = softLpfFilterApplyFn(softLpfFilter[axis], gyroADCf);
DEBUG_SET(DEBUG_NOTCH, axis, lrintf(gyroADCf));
#ifdef USE_GYRO_NOTCH_1
gyroADCf = notchFilter1ApplyFn(notchFilter1[axis], gyroADCf);
#endif
#ifdef USE_GYRO_NOTCH_2
gyroADCf = notchFilter2ApplyFn(notchFilter2[axis], gyroADCf);
#endif
gyro.gyroADCf[axis] = gyroADCf;
}
#ifdef USE_ASYNC_GYRO_PROCESSING
// Accumulate gyro readings for better IMU accuracy
gyroUpdateAccumulatedRates(gyroUpdateDeltaUs);
#endif
}
bool gyroReadTemperature(void)
{
// Read gyro sensor temperature. temperatureFn returns temperature in [degC * 10]
if (gyroDev0.temperatureFn) {
return gyroDev0.temperatureFn(&gyroDev0, &gyroTemperature0);
}
return false;
}
int16_t gyroGetTemperature(void)
{
return gyroTemperature0;
}
int16_t gyroRateDps(int axis)
{
return lrintf(gyro.gyroADCf[axis] / gyroDev0.scale);
}
bool gyroSyncCheckUpdate(void)
{
if (!gyroDev0.intStatusFn)
return false;
return gyroDev0.intStatusFn(&gyroDev0);
}