Fix debug mode DEBUG_ATTITUDE (#13570)
[betaflight.git] / src / main / flight / imu.c
blob8f4e41d72bed3d5e3aeab5440ed7a4f6037d09b4
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 // Inertial Measurement Unit (IMU)
23 #include <stdbool.h>
24 #include <stdint.h>
25 #include <stdlib.h>
26 #include <math.h>
28 #include "platform.h"
30 #include "build/build_config.h"
31 #include "build/debug.h"
33 #include "common/axis.h"
34 #include "common/vector.h"
36 #include "pg/pg.h"
37 #include "pg/pg_ids.h"
39 #include "drivers/time.h"
41 #include "fc/runtime_config.h"
43 #include "flight/gps_rescue.h"
44 #include "flight/imu.h"
45 #include "flight/mixer.h"
46 #include "flight/pid.h"
47 #include "fc/rc.h"
49 #include "io/gps.h"
51 #include "scheduler/scheduler.h"
53 #include "sensors/acceleration.h"
54 #include "sensors/barometer.h"
55 #include "sensors/compass.h"
56 #include "sensors/gyro.h"
57 #include "sensors/sensors.h"
59 #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
60 #include <stdio.h>
61 #include <pthread.h>
63 static pthread_mutex_t imuUpdateLock;
65 #if defined(SIMULATOR_IMU_SYNC)
66 static uint32_t imuDeltaT = 0;
67 static bool imuUpdated = false;
68 #endif
70 #define IMU_LOCK pthread_mutex_lock(&imuUpdateLock)
71 #define IMU_UNLOCK pthread_mutex_unlock(&imuUpdateLock)
73 #else
75 #define IMU_LOCK
76 #define IMU_UNLOCK
78 #endif
80 // the limit (in degrees/second) beyond which we stop integrating
81 // omega_I. At larger spin rates the DCM PI controller can get 'dizzy'
82 // which results in false gyro drift. See
83 // https://drive.google.com/file/d/0ByvTkVQo3tqXQUVCVUNyZEgtRGs/view?usp=sharing&resourcekey=0-Mo4254cxdWWx2Y4mGN78Zw
85 #define SPIN_RATE_LIMIT 20
87 #define ATTITUDE_RESET_QUIET_TIME 250000 // 250ms - gyro quiet period after disarm before attitude reset
88 #define ATTITUDE_RESET_GYRO_LIMIT 15 // 15 deg/sec - gyro limit for quiet period
89 #define ATTITUDE_RESET_ACTIVE_TIME 500000 // 500ms - Time to wait for attitude to converge at high gain
90 #define GPS_COG_MIN_GROUNDSPEED 100 // 1.0m/s - min groundspeed for GPS Heading reinitialisation etc
91 bool canUseGPSHeading = true;
93 static float throttleAngleScale;
94 static int throttleAngleValue;
95 static float smallAngleCosZ = 0;
97 static imuRuntimeConfig_t imuRuntimeConfig;
99 float rMat[3][3];
100 static fpVector2_t north_ef;
102 #if defined(USE_ACC)
103 STATIC_UNIT_TESTED bool attitudeIsEstablished = false;
104 #endif
106 // quaternion of sensor frame relative to earth frame
107 STATIC_UNIT_TESTED quaternion q = QUATERNION_INITIALIZE;
108 STATIC_UNIT_TESTED quaternionProducts qP = QUATERNION_PRODUCTS_INITIALIZE;
109 // headfree quaternions
110 quaternion headfree = QUATERNION_INITIALIZE;
111 quaternion offset = QUATERNION_INITIALIZE;
113 // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
114 attitudeEulerAngles_t attitude = EULER_INITIALIZE;
116 PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 3);
118 #ifdef USE_RACE_PRO
119 #define DEFAULT_SMALL_ANGLE 180
120 #else
121 #define DEFAULT_SMALL_ANGLE 25
122 #endif
124 PG_RESET_TEMPLATE(imuConfig_t, imuConfig,
125 .imu_dcm_kp = 2500, // 1.0 * 10000
126 .imu_dcm_ki = 0, // 0.003 * 10000
127 .small_angle = DEFAULT_SMALL_ANGLE,
128 .imu_process_denom = 2,
129 .mag_declination = 0
132 static void imuQuaternionComputeProducts(quaternion *quat, quaternionProducts *quatProd)
134 quatProd->ww = quat->w * quat->w;
135 quatProd->wx = quat->w * quat->x;
136 quatProd->wy = quat->w * quat->y;
137 quatProd->wz = quat->w * quat->z;
138 quatProd->xx = quat->x * quat->x;
139 quatProd->xy = quat->x * quat->y;
140 quatProd->xz = quat->x * quat->z;
141 quatProd->yy = quat->y * quat->y;
142 quatProd->yz = quat->y * quat->z;
143 quatProd->zz = quat->z * quat->z;
146 STATIC_UNIT_TESTED void imuComputeRotationMatrix(void)
148 imuQuaternionComputeProducts(&q, &qP);
150 rMat[0][0] = 1.0f - 2.0f * qP.yy - 2.0f * qP.zz;
151 rMat[0][1] = 2.0f * (qP.xy + -qP.wz);
152 rMat[0][2] = 2.0f * (qP.xz - -qP.wy);
154 rMat[1][0] = 2.0f * (qP.xy - -qP.wz);
155 rMat[1][1] = 1.0f - 2.0f * qP.xx - 2.0f * qP.zz;
156 rMat[1][2] = 2.0f * (qP.yz + -qP.wx);
158 rMat[2][0] = 2.0f * (qP.xz + -qP.wy);
159 rMat[2][1] = 2.0f * (qP.yz - -qP.wx);
160 rMat[2][2] = 1.0f - 2.0f * qP.xx - 2.0f * qP.yy;
162 #if defined(SIMULATOR_BUILD) && !defined(USE_IMU_CALC) && !defined(SET_IMU_FROM_EULER)
163 rMat[1][0] = -2.0f * (qP.xy - -qP.wz);
164 rMat[2][0] = -2.0f * (qP.xz + -qP.wy);
165 #endif
168 static float calculateThrottleAngleScale(uint16_t throttle_correction_angle)
170 return (1800.0f / M_PIf) * (900.0f / throttle_correction_angle);
173 void imuConfigure(uint16_t throttle_correction_angle, uint8_t throttle_correction_value)
175 // current default for imu_dcm_kp is 2500; our 'normal' or baseline value for imuDcmKp is 0.25
176 imuRuntimeConfig.imuDcmKp = imuConfig()->imu_dcm_kp / 10000.0f;
177 imuRuntimeConfig.imuDcmKi = imuConfig()->imu_dcm_ki / 10000.0f;
178 // magnetic declination has negative sign (positive clockwise when seen from top)
179 const float imuMagneticDeclinationRad = DEGREES_TO_RADIANS(imuConfig()->mag_declination / 10.0f);
180 north_ef.x = cos_approx(imuMagneticDeclinationRad);
181 north_ef.y = -sin_approx(imuMagneticDeclinationRad);
183 smallAngleCosZ = cos_approx(degreesToRadians(imuConfig()->small_angle));
185 throttleAngleScale = calculateThrottleAngleScale(throttle_correction_angle);
187 throttleAngleValue = throttle_correction_value;
190 void imuInit(void)
192 #ifdef USE_GPS
193 canUseGPSHeading = true;
194 #else
195 canUseGPSHeading = false;
196 #endif
198 imuComputeRotationMatrix();
200 #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
201 if (pthread_mutex_init(&imuUpdateLock, NULL) != 0) {
202 printf("Create imuUpdateLock error!\n");
204 #endif
207 #if defined(USE_ACC)
208 static float invSqrt(float x)
210 return 1.0f / sqrtf(x);
213 // g[xyz] - gyro reading, in rad/s
214 // useAcc, a[xyz] - accelerometer reading, direction only, normalized internally
215 // headingErrMag - heading error (in earth frame) derived from magnetometter, rad/s around Z axis (* dcmKpGain)
216 // headingErrCog - heading error (in earth frame) derived from CourseOverGround, rad/s around Z axis (* dcmKpGain)
217 // dcmKpGain - gain applied to all error sources
218 STATIC_UNIT_TESTED void imuMahonyAHRSupdate(float dt,
219 float gx, float gy, float gz,
220 bool useAcc, float ax, float ay, float az,
221 float headingErrMag, float headingErrCog,
222 const float dcmKpGain)
224 static float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki
226 // Calculate general spin rate (rad/s)
227 const float spin_rate = sqrtf(sq(gx) + sq(gy) + sq(gz));
229 float ex = 0, ey = 0, ez = 0;
231 // Add error from magnetometer and Cog
232 // just rotate input value to body frame
233 ex += rMat[Z][X] * (headingErrCog + headingErrMag);
234 ey += rMat[Z][Y] * (headingErrCog + headingErrMag);
235 ez += rMat[Z][Z] * (headingErrCog + headingErrMag);
237 DEBUG_SET(DEBUG_ATTITUDE, 3, (headingErrCog * 100));
238 DEBUG_SET(DEBUG_ATTITUDE, 7, lrintf(dcmKpGain * 100.0f));
240 // Use measured acceleration vector
241 float recipAccNorm = sq(ax) + sq(ay) + sq(az);
242 if (useAcc && recipAccNorm > 0.01f) {
243 // Normalise accelerometer measurement; useAcc is true when all smoothed acc axes are within 20% of 1G
244 recipAccNorm = invSqrt(recipAccNorm);
246 ax *= recipAccNorm;
247 ay *= recipAccNorm;
248 az *= recipAccNorm;
250 // Error is sum of cross product between estimated direction and measured direction of gravity
251 ex += (ay * rMat[2][2] - az * rMat[2][1]);
252 ey += (az * rMat[2][0] - ax * rMat[2][2]);
253 ez += (ax * rMat[2][1] - ay * rMat[2][0]);
256 // Compute and apply integral feedback if enabled
257 if (imuRuntimeConfig.imuDcmKi > 0.0f) {
258 // Stop integrating if spinning beyond the certain limit
259 if (spin_rate < DEGREES_TO_RADIANS(SPIN_RATE_LIMIT)) {
260 const float dcmKiGain = imuRuntimeConfig.imuDcmKi;
261 integralFBx += dcmKiGain * ex * dt; // integral error scaled by Ki
262 integralFBy += dcmKiGain * ey * dt;
263 integralFBz += dcmKiGain * ez * dt;
265 } else {
266 integralFBx = 0.0f; // prevent integral windup
267 integralFBy = 0.0f;
268 integralFBz = 0.0f;
271 // Apply proportional and integral feedback
272 gx += dcmKpGain * ex + integralFBx;
273 gy += dcmKpGain * ey + integralFBy;
274 gz += dcmKpGain * ez + integralFBz;
276 // Integrate rate of change of quaternion
277 gx *= (0.5f * dt);
278 gy *= (0.5f * dt);
279 gz *= (0.5f * dt);
281 quaternion buffer;
282 buffer.w = q.w;
283 buffer.x = q.x;
284 buffer.y = q.y;
285 buffer.z = q.z;
287 q.w += (-buffer.x * gx - buffer.y * gy - buffer.z * gz);
288 q.x += (+buffer.w * gx + buffer.y * gz - buffer.z * gy);
289 q.y += (+buffer.w * gy - buffer.x * gz + buffer.z * gx);
290 q.z += (+buffer.w * gz + buffer.x * gy - buffer.y * gx);
292 // Normalise quaternion
293 float recipNorm = invSqrt(sq(q.w) + sq(q.x) + sq(q.y) + sq(q.z));
294 q.w *= recipNorm;
295 q.x *= recipNorm;
296 q.y *= recipNorm;
297 q.z *= recipNorm;
299 // Pre-compute rotation matrix from quaternion
300 imuComputeRotationMatrix();
302 attitudeIsEstablished = true;
305 STATIC_UNIT_TESTED void imuUpdateEulerAngles(void)
307 quaternionProducts buffer;
309 if (FLIGHT_MODE(HEADFREE_MODE)) {
310 imuQuaternionComputeProducts(&headfree, &buffer);
312 attitude.values.roll = lrintf(atan2_approx((+2.0f * (buffer.wx + buffer.yz)), (+1.0f - 2.0f * (buffer.xx + buffer.yy))) * (1800.0f / M_PIf));
313 attitude.values.pitch = lrintf(((0.5f * M_PIf) - acos_approx(+2.0f * (buffer.wy - buffer.xz))) * (1800.0f / M_PIf));
314 attitude.values.yaw = lrintf((-atan2_approx((+2.0f * (buffer.wz + buffer.xy)), (+1.0f - 2.0f * (buffer.yy + buffer.zz))) * (1800.0f / M_PIf)));
315 } else {
316 attitude.values.roll = lrintf(atan2_approx(rMat[2][1], rMat[2][2]) * (1800.0f / M_PIf));
317 attitude.values.pitch = lrintf(((0.5f * M_PIf) - acos_approx(-rMat[2][0])) * (1800.0f / M_PIf));
318 attitude.values.yaw = lrintf((-atan2_approx(rMat[1][0], rMat[0][0]) * (1800.0f / M_PIf)));
321 if (attitude.values.yaw < 0) {
322 attitude.values.yaw += 3600;
326 static bool imuIsAccelerometerHealthy(float *accAverage)
328 float accMagnitudeSq = 0;
329 for (int axis = 0; axis < 3; axis++) {
330 const float a = accAverage[axis];
331 accMagnitudeSq += a * a;
334 accMagnitudeSq = accMagnitudeSq * sq(acc.dev.acc_1G_rec);
336 // Accept accel readings only in range 0.9g - 1.1g
337 return (0.81f < accMagnitudeSq) && (accMagnitudeSq < 1.21f);
340 // Calculate the dcmKpGain to use. When armed, the gain is imuRuntimeConfig.imuDcmKp, i.e., the default value
341 // When disarmed after initial boot, the scaling is 10 times higher for the first 20 seconds to speed up initial convergence.
342 // After disarming we want to quickly reestablish convergence to deal with the attitude estimation being incorrect due to a crash.
343 // - wait for a 250ms period of low gyro activity to ensure the craft is not moving
344 // - use a large dcmKpGain value for 500ms to allow the attitude estimate to quickly converge
345 // - reset the gain back to the standard setting
346 static float imuCalcKpGain(timeUs_t currentTimeUs, bool useAcc, float *gyroAverage)
348 static enum {
349 stArmed,
350 stRestart,
351 stQuiet,
352 stReset,
353 stDisarmed
354 } arState = stDisarmed;
356 static timeUs_t stateTimeout;
358 const bool armState = ARMING_FLAG(ARMED);
360 if (!armState) {
361 // If gyro activity exceeds the threshold then restart the quiet period.
362 // Also, if the attitude reset has been complete and there is subsequent gyro activity then
363 // start the reset cycle again. This addresses the case where the pilot rights the craft after a crash.
364 if ( (fabsf(gyroAverage[X]) > ATTITUDE_RESET_GYRO_LIMIT) // gyro axis limit exceeded
365 || (fabsf(gyroAverage[Y]) > ATTITUDE_RESET_GYRO_LIMIT)
366 || (fabsf(gyroAverage[Z]) > ATTITUDE_RESET_GYRO_LIMIT)
367 || !useAcc // acc reading out of range
369 arState = stRestart;
372 switch (arState) {
373 default: // should not happen, safeguard only
374 case stArmed:
375 case stRestart:
376 stateTimeout = currentTimeUs + ATTITUDE_RESET_QUIET_TIME;
377 arState = stQuiet;
378 // fallthrough
379 case stQuiet:
380 if (cmpTimeUs(currentTimeUs, stateTimeout) >= 0) {
381 stateTimeout = currentTimeUs + ATTITUDE_RESET_ACTIVE_TIME;
382 arState = stReset;
384 // low gain (default value of 0.25) during quiet phase
385 return imuRuntimeConfig.imuDcmKp;
386 case stReset:
387 if (cmpTimeUs(currentTimeUs, stateTimeout) >= 0) {
388 arState = stDisarmed;
390 // high gain, 100x greater than normal, or 25, after quiet period
391 return imuRuntimeConfig.imuDcmKp * 100.0f;
392 case stDisarmed:
393 // Scale the kP to converge 10x faster when disarmed, ie 2.5
394 return imuRuntimeConfig.imuDcmKp * 10.0f;
396 } else {
397 arState = stArmed;
398 return imuRuntimeConfig.imuDcmKp;
402 #ifdef USE_GPS
404 // IMU groundspeed gain heuristic.
405 // GPS_RESCUE_MODE overrides this
406 static float imuCalcGroundspeedGain(float dt)
408 // 1. suppress ez_ef at low groundspeed, and boost at high groundspeed, via
409 // groundspeedGain, calculated in `imuCalculateEstimatedAttitude`, range 0 - 10.0
410 // groundspeedGain is the primary multiplier of ez_ef
411 // Otherwise, groundspeedGain is determined by GPS COG groundspeed / GPS_COG_MIN_GROUNDSPEED
414 // in normal flight, IMU should:
415 // - heavily average GPS heading values at low speed, since they are random, almost
416 // - respond more quickly at higher speeds.
417 // GPS typically returns quite good heading estimates at or above 0.5- 1.0 m/s, quite solid by 2m/s
418 // groundspeedGain will be 0 at 0.0m/s, rising slowly towards 1.0 at 1.0 m/s, and reaching max of 10.0 at 10m/s
419 const float speedRatio = (float)gpsSol.groundSpeed / GPS_COG_MIN_GROUNDSPEED;
420 float speedBasedGain = speedRatio > 1.0f ? fminf(speedRatio, 10.0f) : sq(speedRatio);
422 const bool isWing = isFixedWing(); // different weighting for airplane aerodynamic
424 // 2. suppress heading correction during and after yaw inputs, down to zero at 100% yaw
425 const float yawStickDeflectionInv = 1.0f - getRcDeflectionAbs(FD_YAW);
426 float stickDeflectionFactor = power5(yawStickDeflectionInv);
427 // negative peak detector with decay over a 2.5s time constant, to sustain the suppression
428 static float stickSuppressionPrev = 0.0f;
429 const float k = 0.4f * dt; // k = 0.004 at 100Hz, dt in seconds, 2.5s time constant
430 const float stickSuppression = stickSuppressionPrev + k * (stickDeflectionFactor - stickSuppressionPrev);
431 stickSuppressionPrev = fminf(stickSuppression, stickDeflectionFactor);
433 // 3. suppress heading correction unless roll is centered, from 1.0 to zero if Roll is more than 12 degrees from flat
434 // this is to prevent adaptation to GPS while flying sideways, or with a significant sideways element
435 const float absRollAngle = fabsf(attitude.values.roll * .1f); // degrees
436 float rollMax = isWing ? 25.0f : 12.0f; // 25 degrees for wing, 12 degrees for quad
437 // note: these value are 'educated guesses' - for quads it must be very tight
438 // for wings, which can't fly sideways, it can be wider
439 const float rollSuppression = (absRollAngle < rollMax) ? (rollMax - absRollAngle) / rollMax : 0.0f;
441 // 4. attenuate heading correction by pitch angle, will be zero if flat or negative (ie flying tail first)
442 // allow faster adaptation for quads at higher pitch angles; returns 1.0 at 45 degrees
443 // but not if a wing, because they typically are flat when flying.
444 // need to test if anything special is needed for pitch with wings, for now do nothing.
445 float pitchSuppression = 1.0f;
446 if (!isWing) {
447 const float pitchAngle = attitude.values.pitch * .1f; // degrees, negative is backwards
448 pitchSuppression = pitchAngle / 45.0f; // 1.0 at 45 degrees, 2.0 at 90 degrees
449 pitchSuppression = (pitchSuppression >= 0) ? pitchSuppression : 0.0f; // zero if flat or pitched backwards
452 // NOTE : these suppressions make sense with normal pilot inputs and normal flight
453 // They are not used in GPS Rescue, and probably should be bypassed in position hold, etc,
455 return speedBasedGain * stickSuppression * rollSuppression * pitchSuppression;
458 // *** Calculate heading error derived from IMU heading vs GPS heading ***
459 // assumes that quad/plane is flying forward (gain factors attenuate situations when this is not true)
460 // courseOverGround - in rad, 0 = north, clockwise
461 // return value rotation around earth Z axis, pointing in directipon of smaller error, [rad/s]
462 STATIC_UNIT_TESTED float imuCalcCourseErr(float courseOverGround)
464 // Compute COG heading unit vector in earth frame (ef) from scalar GPS CourseOverGround
465 // Earth frame X is pointing north and sin/cos argument is anticlockwise. (|cog_ef| == 1.0)
466 const fpVector2_t cog_ef = {.x = cos_approx(-courseOverGround), .y = sin_approx(-courseOverGround)};
468 // Compute and normalise craft Earth frame heading vector from body X axis
469 fpVector2_t heading_ef = {.x = rMat[X][X], .y = rMat[Y][X]};
470 vector2Normalize(&heading_ef, &heading_ef); // XY only, normalised to magnitude 1.0
472 // cross (vector product) = |heading| * |cog| * sin(angle) = 1 * 1 * sin(angle)
473 // cross value reflects error angle of quad X axis vs GPS groundspeed
474 // cross sign depends on the rotation change from input to output vectors by right hand rule
475 // operand order is arranged such that rotation is in direction of zero error
476 // abs value of cross is zero when parallel, max of 1.0 at 90 degree error
477 // cross value is used for ez_ef when error is less than 90 degrees
478 // decreasing cross value after 90 degrees, and zero cross value at 180 degree error,
479 // would prevent error correction, so the maximum angular error value of 1.0 is used for this interval
480 const float cross = vector2Cross(&heading_ef, &cog_ef);
482 // dot product = |heading| * |cog| * cos(angle) = 1 * 1 * cos(angle)
483 // max when aligned, zero at 90 degrees of vector difference, negative for error > 90 degrees
484 const float dot = vector2Dot(&heading_ef, &cog_ef);
486 // error around Z axis in Earth frame
487 // for error angles less than 90 degrees (dot > 0), use cross value to compute ez_ef
488 // over 90 deg, use sign(cross)
489 // when well aligned, return ~ 0 (sin(error)), for error >= 90 degrees, return +-1.0
490 return (dot > 0) ? cross : (cross < 0 ? -1.0f : 1.0f);
493 #endif
495 #if defined(USE_MAG) && defined(USE_GPS_RESCUE)
496 // refactored from old debug code, to be removed/optimized eventually
497 static void imuDebug_GPS_RESCUE_HEADING(void)
499 // Encapsulate additional operations in a block so that it is only executed when the according debug mode is used
500 // Only re-calculate magYaw when there is a new Mag data reading, to avoid spikes
501 if (debugMode == DEBUG_GPS_RESCUE_HEADING && mag.isNewMagADCFlag) {
502 fpVector3_t mag_bf = {{mag.magADC[X], mag.magADC[Y], mag.magADC[Z]}};
503 fpVector3_t mag_ef;
504 matrixVectorMul(&mag_ef, (const fpMat33_t*)&rMat, &mag_bf); // BF->EF true north
506 fpMat33_t rMatZTrans;
507 yawToRotationMatrixZ(&rMatZTrans, -atan2_approx(rMat[1][0], rMat[0][0]));
508 fpVector3_t mag_ef_yawed;
509 matrixVectorMul(&mag_ef_yawed, &rMatZTrans, &mag_ef); // EF->EF yawed
510 // Magnetic yaw is the angle between true north and the X axis of the body frame
511 int16_t magYaw = lrintf((atan2_approx(mag_ef_yawed.y, mag_ef_yawed.x) * (1800.0f / M_PIf)));
512 if (magYaw < 0) {
513 magYaw += 3600;
515 DEBUG_SET(DEBUG_GPS_RESCUE_HEADING, 4, magYaw); // mag heading in degrees * 10
516 // reset new mag data flag to false to initiate monitoring for new Mag data.
517 // note that if the debug doesn't run, this reset will not occur, and we won't waste cycles on the comparison
518 mag.isNewMagADCFlag = false;
521 #endif // defined(USE_MAG) && defined(USE_GPS_RESCUE)
523 #ifdef USE_MAG
524 // Calculate heading error derived from magnetometer
525 // return value rotation around earth Z axis, pointing in directipon of smaller error, [rad/s]
526 STATIC_UNIT_TESTED float imuCalcMagErr(void)
528 // Use measured magnetic field vector
529 fpVector3_t mag_bf = {{mag.magADC[X], mag.magADC[Y], mag.magADC[Z]}};
530 float magNormSquared = vectorNormSquared(&mag_bf);
532 if (magNormSquared > 0.01f) {
533 // project magnetometer reading into Earth frame
534 fpVector3_t mag_ef;
535 matrixVectorMul(&mag_ef, (const fpMat33_t*)&rMat, &mag_bf); // BF->EF true north
536 // Normalise magnetometer measurement
537 vectorScale(&mag_ef, &mag_ef, 1.0f / sqrtf(magNormSquared));
539 // For magnetometer correction we make an assumption that magnetic field is perpendicular to gravity (ignore Z-component in EF).
540 // This way magnetic field will only affect heading and wont mess roll/pitch angles
541 fpVector2_t mag2d_ef = {.x = mag_ef.x, .y = mag_ef.y};
542 // mag2d_ef - measured mag field vector in EF (2D ground plane projection)
543 // north_ef - reference mag field vector heading due North in EF (2D ground plane projection).
544 // Adjusted for magnetic declination (in imuConfigure)
546 // magnetometer error is cross product between estimated magnetic north and measured magnetic north (calculated in EF)
547 // increase gain on large misalignment
548 const float dot = vector2Dot(&mag2d_ef, &north_ef);
549 const float cross = vector2Cross(&mag2d_ef, &north_ef);
550 return (dot > 0) ? cross : (cross < 0 ? -1.0f : 1.0f) * vector2Norm(&mag2d_ef);
551 } else {
552 // invalid magnetometer data
553 return 0.0f;
557 #endif
559 #if defined(USE_GPS)
560 static void imuComputeQuaternionFromRPY(quaternionProducts *quatProd, int16_t initialRoll, int16_t initialPitch, int16_t initialYaw)
562 if (initialRoll > 1800) {
563 initialRoll -= 3600;
566 if (initialPitch > 1800) {
567 initialPitch -= 3600;
570 if (initialYaw > 1800) {
571 initialYaw -= 3600;
574 const float cosRoll = cos_approx(DECIDEGREES_TO_RADIANS(initialRoll) * 0.5f);
575 const float sinRoll = sin_approx(DECIDEGREES_TO_RADIANS(initialRoll) * 0.5f);
577 const float cosPitch = cos_approx(DECIDEGREES_TO_RADIANS(initialPitch) * 0.5f);
578 const float sinPitch = sin_approx(DECIDEGREES_TO_RADIANS(initialPitch) * 0.5f);
580 const float cosYaw = cos_approx(DECIDEGREES_TO_RADIANS(-initialYaw) * 0.5f);
581 const float sinYaw = sin_approx(DECIDEGREES_TO_RADIANS(-initialYaw) * 0.5f);
583 const float q0 = cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw;
584 const float q1 = sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw;
585 const float q2 = cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw;
586 const float q3 = cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw;
588 quatProd->xx = sq(q1);
589 quatProd->yy = sq(q2);
590 quatProd->zz = sq(q3);
592 quatProd->xy = q1 * q2;
593 quatProd->xz = q1 * q3;
594 quatProd->yz = q2 * q3;
596 quatProd->wx = q0 * q1;
597 quatProd->wy = q0 * q2;
598 quatProd->wz = q0 * q3;
600 imuComputeRotationMatrix();
602 attitudeIsEstablished = true;
604 #endif
606 #if defined(SIMULATOR_BUILD) && !defined(USE_IMU_CALC)
607 static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
609 // unused static functions
610 UNUSED(imuMahonyAHRSupdate);
611 UNUSED(imuIsAccelerometerHealthy);
612 UNUSED(canUseGPSHeading);
613 UNUSED(imuCalcKpGain);
614 UNUSED(imuCalcMagErr);
616 UNUSED(currentTimeUs);
618 #else
620 static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
622 #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_IMU_SYNC)
623 // Simulator-based timing
624 // printf("[imu]deltaT = %u, imuDeltaT = %u, currentTimeUs = %u, micros64_real = %lu\n", deltaT, imuDeltaT, currentTimeUs, micros64_real());
625 const timeDelta_t deltaT = imuDeltaT;
626 #else
627 static timeUs_t previousIMUUpdateTime = 0;
628 const timeDelta_t deltaT = currentTimeUs - previousIMUUpdateTime;
629 previousIMUUpdateTime = currentTimeUs;
630 #endif
631 const float dt = deltaT * 1e-6f;
633 // *** magnetometer based error estimate ***
634 bool useMag = false; // mag will suppress GPS correction
635 float magErr = 0;
637 #ifdef USE_MAG
638 if (sensors(SENSOR_MAG)
639 && compassIsHealthy()
640 #ifdef USE_GPS_RESCUE
641 && !gpsRescueDisableMag()
642 #endif
644 useMag = true;
645 magErr = imuCalcMagErr();
647 #endif
649 #if defined(USE_MAG) && defined(USE_GPS_RESCUE)
650 // fill in GPS rescue debug value (leftover from code refactoring)
651 imuDebug_GPS_RESCUE_HEADING();
652 #endif
654 // *** GoC based error estimate ***
655 float cogErr = 0;
656 #if defined(USE_GPS)
657 if (!useMag
658 && sensors(SENSOR_GPS)
659 && STATE(GPS_FIX) && gpsSol.numSat > GPS_MIN_SAT_COUNT) {
660 static bool gpsHeadingInitialized = false; // TODO - remove
661 if (gpsHeadingInitialized) {
662 float groundspeedGain; // IMU yaw gain to be applied in imuMahonyAHRSupdate from ground course,
663 if (FLIGHT_MODE(GPS_RESCUE_MODE)) {
664 // GPS_Rescue adjusts groundspeedGain during a rescue in a range 0 - 4.5,
665 // depending on GPS Rescue state and groundspeed relative to speed to home.
666 groundspeedGain = gpsRescueGetImuYawCogGain();
667 } else {
668 // 0.0 - 10.0, heuristic based on GPS speed and stick state
669 groundspeedGain = imuCalcGroundspeedGain(dt);
671 DEBUG_SET(DEBUG_ATTITUDE, 2, lrintf(groundspeedGain * 100.0f));
672 float courseOverGround = DECIDEGREES_TO_RADIANS(gpsSol.groundCourse);
673 cogErr = imuCalcCourseErr(courseOverGround) * groundspeedGain;
674 } else if (gpsSol.groundSpeed > GPS_COG_MIN_GROUNDSPEED) {
675 // Reset the reference and reinitialize quaternion factors when GPS groundspeed > GPS_COG_MIN_GROUNDSPEED
676 imuComputeQuaternionFromRPY(&qP, attitude.values.roll, attitude.values.pitch, gpsSol.groundCourse);
677 gpsHeadingInitialized = true;
680 #else
681 UNUSED(useMag);
682 #endif
685 float gyroAverage[XYZ_AXIS_COUNT];
686 for (int axis = 0; axis < XYZ_AXIS_COUNT; ++axis) {
687 gyroAverage[axis] = gyroGetFilteredDownsampled(axis);
690 const bool useAcc = imuIsAccelerometerHealthy(acc.accADC); // all smoothed accADC values are within 20% of 1G
692 imuMahonyAHRSupdate(dt,
693 DEGREES_TO_RADIANS(gyroAverage[X]), DEGREES_TO_RADIANS(gyroAverage[Y]), DEGREES_TO_RADIANS(gyroAverage[Z]),
694 useAcc, acc.accADC[X], acc.accADC[Y], acc.accADC[Z],
695 magErr, cogErr,
696 imuCalcKpGain(currentTimeUs, useAcc, gyroAverage));
698 imuUpdateEulerAngles();
701 #endif
703 static int calculateThrottleAngleCorrection(void)
706 * Use 0 as the throttle angle correction if we are inverted, vertical or with a
707 * small angle < 0.86 deg
708 * TODO: Define this small angle in config.
710 if (getCosTiltAngle() <= 0.015f) {
711 return 0;
713 int angle = lrintf(acos_approx(getCosTiltAngle()) * throttleAngleScale);
714 if (angle > 900)
715 angle = 900;
716 return lrintf(throttleAngleValue * sin_approx(angle / (900.0f * M_PIf / 2.0f)));
719 void imuUpdateAttitude(timeUs_t currentTimeUs)
721 if (sensors(SENSOR_ACC) && acc.isAccelUpdatedAtLeastOnce) {
722 IMU_LOCK;
723 #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_IMU_SYNC)
724 if (imuUpdated == false) {
725 IMU_UNLOCK;
726 return;
728 imuUpdated = false;
729 #endif
730 imuCalculateEstimatedAttitude(currentTimeUs);
731 IMU_UNLOCK;
733 // Update the throttle correction for angle and supply it to the mixer
734 int throttleAngleCorrection = 0;
735 if (throttleAngleValue && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && ARMING_FLAG(ARMED)) {
736 throttleAngleCorrection = calculateThrottleAngleCorrection();
738 mixerSetThrottleAngleCorrection(throttleAngleCorrection);
740 } else {
741 acc.accADC[X] = 0;
742 acc.accADC[Y] = 0;
743 acc.accADC[Z] = 0;
744 schedulerIgnoreTaskStateTime();
747 DEBUG_SET(DEBUG_ATTITUDE, 0, attitude.values.roll);
748 DEBUG_SET(DEBUG_ATTITUDE, 1, attitude.values.pitch);
750 #endif // USE_ACC
752 float getCosTiltAngle(void)
754 return rMat[2][2];
757 void getQuaternion(quaternion *quat)
759 quat->w = q.w;
760 quat->x = q.x;
761 quat->y = q.y;
762 quat->z = q.z;
765 #ifdef SIMULATOR_BUILD
766 void imuSetAttitudeRPY(float roll, float pitch, float yaw)
768 IMU_LOCK;
770 attitude.values.roll = roll * 10;
771 attitude.values.pitch = pitch * 10;
772 attitude.values.yaw = yaw * 10;
774 IMU_UNLOCK;
777 void imuSetAttitudeQuat(float w, float x, float y, float z)
779 IMU_LOCK;
781 q.w = w;
782 q.x = x;
783 q.y = y;
784 q.z = z;
786 imuComputeRotationMatrix();
788 attitudeIsEstablished = true;
790 imuUpdateEulerAngles();
792 IMU_UNLOCK;
794 #endif
795 #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_IMU_SYNC)
796 void imuSetHasNewData(uint32_t dt)
798 IMU_LOCK;
800 imuUpdated = true;
801 imuDeltaT = dt;
803 IMU_UNLOCK;
805 #endif
807 bool imuQuaternionHeadfreeOffsetSet(void)
809 if ((abs(attitude.values.roll) < 450) && (abs(attitude.values.pitch) < 450)) {
810 const float yaw = -atan2_approx((+2.0f * (qP.wz + qP.xy)), (+1.0f - 2.0f * (qP.yy + qP.zz)));
812 offset.w = cos_approx(yaw/2);
813 offset.x = 0;
814 offset.y = 0;
815 offset.z = sin_approx(yaw/2);
817 return true;
818 } else {
819 return false;
823 void imuQuaternionMultiplication(quaternion *q1, quaternion *q2, quaternion *result)
825 const float A = (q1->w + q1->x) * (q2->w + q2->x);
826 const float B = (q1->z - q1->y) * (q2->y - q2->z);
827 const float C = (q1->w - q1->x) * (q2->y + q2->z);
828 const float D = (q1->y + q1->z) * (q2->w - q2->x);
829 const float E = (q1->x + q1->z) * (q2->x + q2->y);
830 const float F = (q1->x - q1->z) * (q2->x - q2->y);
831 const float G = (q1->w + q1->y) * (q2->w - q2->z);
832 const float H = (q1->w - q1->y) * (q2->w + q2->z);
834 result->w = B + (- E - F + G + H) / 2.0f;
835 result->x = A - (+ E + F + G + H) / 2.0f;
836 result->y = C + (+ E - F + G - H) / 2.0f;
837 result->z = D + (+ E - F - G + H) / 2.0f;
840 void imuQuaternionHeadfreeTransformVectorEarthToBody(t_fp_vector_def *v)
842 quaternionProducts buffer;
844 imuQuaternionMultiplication(&offset, &q, &headfree);
845 imuQuaternionComputeProducts(&headfree, &buffer);
847 const float x = (buffer.ww + buffer.xx - buffer.yy - buffer.zz) * v->X + 2.0f * (buffer.xy + buffer.wz) * v->Y + 2.0f * (buffer.xz - buffer.wy) * v->Z;
848 const float y = 2.0f * (buffer.xy - buffer.wz) * v->X + (buffer.ww - buffer.xx + buffer.yy - buffer.zz) * v->Y + 2.0f * (buffer.yz + buffer.wx) * v->Z;
849 const float z = 2.0f * (buffer.xz + buffer.wy) * v->X + 2.0f * (buffer.yz - buffer.wx) * v->Y + (buffer.ww - buffer.xx - buffer.yy + buffer.zz) * v->Z;
851 v->X = x;
852 v->Y = y;
853 v->Z = z;
856 bool isUpright(void)
858 #ifdef USE_ACC
859 return !sensors(SENSOR_ACC) || (attitudeIsEstablished && getCosTiltAngle() > smallAngleCosZ);
860 #else
861 return true;
862 #endif