2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 // Inertial Measurement Unit (IMU)
26 FILE_COMPILE_FOR_SPEED
28 #include "blackbox/blackbox.h"
30 #include "build/build_config.h"
31 #include "build/debug.h"
33 #include "common/axis.h"
34 #include "common/filter.h"
35 #include "common/log.h"
36 #include "common/maths.h"
37 #include "common/vector.h"
38 #include "common/quaternion.h"
40 #include "config/feature.h"
41 #include "config/parameter_group.h"
42 #include "config/parameter_group_ids.h"
44 #include "drivers/time.h"
46 #include "fc/config.h"
47 #include "fc/runtime_config.h"
49 #include "flight/hil.h"
50 #include "flight/imu.h"
51 #include "flight/mixer.h"
52 #include "flight/pid.h"
56 #include "sensors/acceleration.h"
57 #include "sensors/barometer.h"
58 #include "sensors/compass.h"
59 #include "sensors/gyro.h"
60 #include "sensors/sensors.h"
64 * In Cleanflight accelerometer is aligned in the following way:
68 * Our INAV uses different convention
69 * X-axis = North/Forward
74 // the limit (in degrees/second) beyond which we stop integrating
75 // omega_I. At larger spin rates the DCM PI controller can get 'dizzy'
76 // which results in false gyro drift. See
77 // http://gentlenav.googlecode.com/files/fastRotations.pdf
79 #define SPIN_RATE_LIMIT 20
80 #define MAX_ACC_SQ_NEARNESS 25 // 25% or G^2, accepted acceleration of (0.87 - 1.12G)
81 #define IMU_CENTRIFUGAL_LPF 1 // Hz
83 FASTRAM fpVector3_t imuMeasuredAccelBF
;
84 FASTRAM fpVector3_t imuMeasuredRotationBF
;
85 STATIC_FASTRAM
float smallAngleCosZ
;
87 STATIC_FASTRAM
bool isAccelUpdatedAtLeastOnce
;
88 STATIC_FASTRAM fpVector3_t vCorrectedMagNorth
; // Magnetic North vector in EF (true North rotated by declination)
90 FASTRAM fpQuaternion_t orientation
;
91 FASTRAM attitudeEulerAngles_t attitude
; // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
92 FASTRAM
float rMat
[3][3];
94 STATIC_FASTRAM imuRuntimeConfig_t imuRuntimeConfig
;
95 STATIC_FASTRAM pt1Filter_t rotRateFilter
;
97 STATIC_FASTRAM
bool gpsHeadingInitialized
;
99 PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t
, imuConfig
, PG_IMU_CONFIG
, 2);
101 PG_RESET_TEMPLATE(imuConfig_t
, imuConfig
,
102 .dcm_kp_acc
= 2500, // 0.25 * 10000
103 .dcm_ki_acc
= 50, // 0.005 * 10000
104 .dcm_kp_mag
= 10000, // 1.00 * 10000
105 .dcm_ki_mag
= 0, // 0.00 * 10000
107 .acc_ignore_rate
= 0,
108 .acc_ignore_slope
= 0
111 STATIC_UNIT_TESTED
void imuComputeRotationMatrix(void)
113 float q1q1
= orientation
.q1
* orientation
.q1
;
114 float q2q2
= orientation
.q2
* orientation
.q2
;
115 float q3q3
= orientation
.q3
* orientation
.q3
;
117 float q0q1
= orientation
.q0
* orientation
.q1
;
118 float q0q2
= orientation
.q0
* orientation
.q2
;
119 float q0q3
= orientation
.q0
* orientation
.q3
;
120 float q1q2
= orientation
.q1
* orientation
.q2
;
121 float q1q3
= orientation
.q1
* orientation
.q3
;
122 float q2q3
= orientation
.q2
* orientation
.q3
;
124 rMat
[0][0] = 1.0f
- 2.0f
* q2q2
- 2.0f
* q3q3
;
125 rMat
[0][1] = 2.0f
* (q1q2
+ -q0q3
);
126 rMat
[0][2] = 2.0f
* (q1q3
- -q0q2
);
128 rMat
[1][0] = 2.0f
* (q1q2
- -q0q3
);
129 rMat
[1][1] = 1.0f
- 2.0f
* q1q1
- 2.0f
* q3q3
;
130 rMat
[1][2] = 2.0f
* (q2q3
+ -q0q1
);
132 rMat
[2][0] = 2.0f
* (q1q3
+ -q0q2
);
133 rMat
[2][1] = 2.0f
* (q2q3
- -q0q1
);
134 rMat
[2][2] = 1.0f
- 2.0f
* q1q1
- 2.0f
* q2q2
;
137 void imuConfigure(void)
139 imuRuntimeConfig
.dcm_kp_acc
= imuConfig()->dcm_kp_acc
/ 10000.0f
;
140 imuRuntimeConfig
.dcm_ki_acc
= imuConfig()->dcm_ki_acc
/ 10000.0f
;
141 imuRuntimeConfig
.dcm_kp_mag
= imuConfig()->dcm_kp_mag
/ 10000.0f
;
142 imuRuntimeConfig
.dcm_ki_mag
= imuConfig()->dcm_ki_mag
/ 10000.0f
;
143 imuRuntimeConfig
.small_angle
= imuConfig()->small_angle
;
148 smallAngleCosZ
= cos_approx(degreesToRadians(imuRuntimeConfig
.small_angle
));
150 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
151 imuMeasuredAccelBF
.v
[axis
] = 0;
154 // Explicitly initialize FASTRAM statics
155 isAccelUpdatedAtLeastOnce
= false;
156 gpsHeadingInitialized
= false;
158 // Create magnetic declination matrix
159 const int deg
= compassConfig()->mag_declination
/ 100;
160 const int min
= compassConfig()->mag_declination
% 100;
161 imuSetMagneticDeclination(deg
+ min
/ 60.0f
);
163 quaternionInitUnit(&orientation
);
164 imuComputeRotationMatrix();
166 // Initialize rotation rate filter
167 pt1FilterReset(&rotRateFilter
, 0);
170 void imuSetMagneticDeclination(float declinationDeg
)
172 const float declinationRad
= -DEGREES_TO_RADIANS(declinationDeg
);
173 vCorrectedMagNorth
.x
= cos_approx(declinationRad
);
174 vCorrectedMagNorth
.y
= sin_approx(declinationRad
);
175 vCorrectedMagNorth
.z
= 0;
178 void imuTransformVectorBodyToEarth(fpVector3_t
* v
)
180 // From body frame to earth frame
181 quaternionRotateVectorInv(v
, v
, &orientation
);
183 // HACK: This is needed to correctly transform from NED (sensor frame) to NEU (navigation)
187 void imuTransformVectorEarthToBody(fpVector3_t
* v
)
189 // HACK: This is needed to correctly transform from NED (sensor frame) to NEU (navigation)
192 // From earth frame to body frame
193 quaternionRotateVector(v
, v
, &orientation
);
196 #if defined(USE_GPS) || defined(HIL)
197 STATIC_UNIT_TESTED
void imuComputeQuaternionFromRPY(int16_t initialRoll
, int16_t initialPitch
, int16_t initialYaw
)
199 if (initialRoll
> 1800) initialRoll
-= 3600;
200 if (initialPitch
> 1800) initialPitch
-= 3600;
201 if (initialYaw
> 1800) initialYaw
-= 3600;
203 const float cosRoll
= cos_approx(DECIDEGREES_TO_RADIANS(initialRoll
) * 0.5f
);
204 const float sinRoll
= sin_approx(DECIDEGREES_TO_RADIANS(initialRoll
) * 0.5f
);
206 const float cosPitch
= cos_approx(DECIDEGREES_TO_RADIANS(initialPitch
) * 0.5f
);
207 const float sinPitch
= sin_approx(DECIDEGREES_TO_RADIANS(initialPitch
) * 0.5f
);
209 const float cosYaw
= cos_approx(DECIDEGREES_TO_RADIANS(-initialYaw
) * 0.5f
);
210 const float sinYaw
= sin_approx(DECIDEGREES_TO_RADIANS(-initialYaw
) * 0.5f
);
212 orientation
.q0
= cosRoll
* cosPitch
* cosYaw
+ sinRoll
* sinPitch
* sinYaw
;
213 orientation
.q1
= sinRoll
* cosPitch
* cosYaw
- cosRoll
* sinPitch
* sinYaw
;
214 orientation
.q2
= cosRoll
* sinPitch
* cosYaw
+ sinRoll
* cosPitch
* sinYaw
;
215 orientation
.q3
= cosRoll
* cosPitch
* sinYaw
- sinRoll
* sinPitch
* cosYaw
;
217 imuComputeRotationMatrix();
221 static bool imuUseFastGains(void)
223 return !ARMING_FLAG(ARMED
) && millis() < 20000;
226 static float imuGetPGainScaleFactor(void)
228 if (imuUseFastGains()) {
236 static void imuResetOrientationQuaternion(const fpVector3_t
* accBF
)
238 const float accNorm
= sqrtf(vectorNormSquared(accBF
));
240 orientation
.q0
= accBF
->z
+ accNorm
;
241 orientation
.q1
= accBF
->y
;
242 orientation
.q2
= -accBF
->x
;
243 orientation
.q3
= 0.0f
;
245 quaternionNormalize(&orientation
, &orientation
);
248 static bool imuValidateQuaternion(const fpQuaternion_t
* quat
)
250 const float check
= fabs(quat
->q0
) + fabs(quat
->q1
) + fabs(quat
->q2
) + fabs(quat
->q3
);
252 if (!isnan(check
) && !isinf(check
)) {
256 const float normSq
= quaternionNormSqared(&orientation
);
257 if (normSq
> (1.0f
- 1e-6f
) && normSq
< (1.0f
+ 1e-6f
)) {
264 static void imuCheckAndResetOrientationQuaternion(const fpQuaternion_t
* quat
, const fpVector3_t
* accBF
)
266 // Check if some calculation in IMU update yield NAN or zero quaternion
267 if (imuValidateQuaternion(&orientation
)) {
271 flightLogEvent_IMUError_t imuErrorEvent
;
273 // Orientation is invalid. We need to reset it
274 if (imuValidateQuaternion(quat
)) {
275 // Previous quaternion valid. Reset to it
277 imuErrorEvent
.errorCode
= 1;
278 LOG_E(IMU
, "AHRS orientation quaternion error. Reset to last known good value");
281 // No valid reference. Best guess from accelerometer
282 imuResetOrientationQuaternion(accBF
);
283 imuErrorEvent
.errorCode
= 2;
284 LOG_E(IMU
, "AHRS orientation quaternion error. Best guess from ACC");
288 if (feature(FEATURE_BLACKBOX
)) {
289 blackboxLogEvent(FLIGHT_LOG_EVENT_IMU_FAILURE
, (flightLogEventData_t
*)&imuErrorEvent
);
294 static void imuMahonyAHRSupdate(float dt
, const fpVector3_t
* gyroBF
, const fpVector3_t
* accBF
, const fpVector3_t
* magBF
, bool useCOG
, float courseOverGround
, float accWScaler
, float magWScaler
)
296 STATIC_FASTRAM fpVector3_t vGyroDriftEstimate
= { 0 };
298 fpQuaternion_t prevOrientation
= orientation
;
299 fpVector3_t vRotation
= *gyroBF
;
301 /* Calculate general spin rate (rad/s) */
302 const float spin_rate_sq
= vectorNormSquared(&vRotation
);
304 /* Step 1: Yaw correction */
305 // Use measured magnetic field vector
306 if (magBF
|| useCOG
) {
307 static const fpVector3_t vForward
= { .v
= { 1.0f
, 0.0f
, 0.0f
} };
309 fpVector3_t vErr
= { .v
= { 0.0f
, 0.0f
, 0.0f
} };
311 if (magBF
&& vectorNormSquared(magBF
) > 0.01f
) {
314 // For magnetometer correction we make an assumption that magnetic field is perpendicular to gravity (ignore Z-component in EF).
315 // This way magnetic field will only affect heading and wont mess roll/pitch angles
317 // (hx; hy; 0) - measured mag field vector in EF (assuming Z-component is zero)
318 // This should yield direction to magnetic North (1; 0; 0)
319 quaternionRotateVectorInv(&vMag
, magBF
, &orientation
); // BF -> EF
321 // Ignore magnetic inclination
324 // We zeroed out vMag.z - make sure the whole vector didn't go to zero
325 if (vectorNormSquared(&vMag
) > 0.01f
) {
326 // Normalize to unit vector
327 vectorNormalize(&vMag
, &vMag
);
329 // Reference mag field vector heading is Magnetic North in EF. We compute that by rotating True North vector by declination and assuming Z-component is zero
330 // magnetometer error is cross product between estimated magnetic north and measured magnetic north (calculated in EF)
331 vectorCrossProduct(&vErr
, &vMag
, &vCorrectedMagNorth
);
333 // Rotate error back into body frame
334 quaternionRotateVector(&vErr
, &vErr
, &orientation
);
338 fpVector3_t vHeadingEF
;
340 // Use raw heading error (from GPS or whatever else)
341 while (courseOverGround
> M_PIf
) courseOverGround
-= (2.0f
* M_PIf
);
342 while (courseOverGround
< -M_PIf
) courseOverGround
+= (2.0f
* M_PIf
);
344 // William Premerlani and Paul Bizard, Direction Cosine Matrix IMU - Eqn. 22-23
345 // (Rxx; Ryx) - measured (estimated) heading vector (EF)
346 // (-cos(COG), sin(COG)) - reference heading vector (EF)
348 // Compute heading vector in EF from scalar CoG
349 fpVector3_t vCoG
= { .v
= { -cos_approx(courseOverGround
), sin_approx(courseOverGround
), 0.0f
} };
351 // Rotate Forward vector from BF to EF - will yield Heading vector in Earth frame
352 quaternionRotateVectorInv(&vHeadingEF
, &vForward
, &orientation
);
355 // We zeroed out vHeadingEF.z - make sure the whole vector didn't go to zero
356 if (vectorNormSquared(&vHeadingEF
) > 0.01f
) {
357 // Normalize to unit vector
358 vectorNormalize(&vHeadingEF
, &vHeadingEF
);
360 // error is cross product between reference heading and estimated heading (calculated in EF)
361 vectorCrossProduct(&vErr
, &vCoG
, &vHeadingEF
);
363 // Rotate error back into body frame
364 quaternionRotateVector(&vErr
, &vErr
, &orientation
);
368 // Compute and apply integral feedback if enabled
369 if (imuRuntimeConfig
.dcm_ki_mag
> 0.0f
) {
370 // Stop integrating if spinning beyond the certain limit
371 if (spin_rate_sq
< sq(DEGREES_TO_RADIANS(SPIN_RATE_LIMIT
))) {
374 // integral error scaled by Ki
375 vectorScale(&vTmp
, &vErr
, imuRuntimeConfig
.dcm_ki_mag
* dt
);
376 vectorAdd(&vGyroDriftEstimate
, &vGyroDriftEstimate
, &vTmp
);
380 // Calculate kP gain and apply proportional feedback
381 vectorScale(&vErr
, &vErr
, imuRuntimeConfig
.dcm_kp_mag
* magWScaler
);
382 vectorAdd(&vRotation
, &vRotation
, &vErr
);
386 /* Step 2: Roll and pitch correction - use measured acceleration vector */
388 static const fpVector3_t vGravity
= { .v
= { 0.0f
, 0.0f
, 1.0f
} };
389 fpVector3_t vEstGravity
, vAcc
, vErr
;
391 // Calculate estimated gravity vector in body frame
392 quaternionRotateVector(&vEstGravity
, &vGravity
, &orientation
); // EF -> BF
394 // Error is sum of cross product between estimated direction and measured direction of gravity
395 vectorNormalize(&vAcc
, accBF
);
396 vectorCrossProduct(&vErr
, &vAcc
, &vEstGravity
);
398 // Compute and apply integral feedback if enabled
399 if (imuRuntimeConfig
.dcm_ki_acc
> 0.0f
) {
400 // Stop integrating if spinning beyond the certain limit
401 if (spin_rate_sq
< sq(DEGREES_TO_RADIANS(SPIN_RATE_LIMIT
))) {
404 // integral error scaled by Ki
405 vectorScale(&vTmp
, &vErr
, imuRuntimeConfig
.dcm_ki_acc
* dt
);
406 vectorAdd(&vGyroDriftEstimate
, &vGyroDriftEstimate
, &vTmp
);
410 // Calculate kP gain and apply proportional feedback
411 vectorScale(&vErr
, &vErr
, imuRuntimeConfig
.dcm_kp_acc
* accWScaler
);
412 vectorAdd(&vRotation
, &vRotation
, &vErr
);
415 // Apply gyro drift correction
416 vectorAdd(&vRotation
, &vRotation
, &vGyroDriftEstimate
);
418 // Integrate rate of change of quaternion
420 fpQuaternion_t deltaQ
;
422 vectorScale(&vTheta
, &vRotation
, 0.5f
* dt
);
423 quaternionInitFromVector(&deltaQ
, &vTheta
);
424 const float thetaMagnitudeSq
= vectorNormSquared(&vTheta
);
426 // If calculated rotation is zero - don't update quaternion
427 if (thetaMagnitudeSq
>= 1e-20) {
428 // Calculate quaternion delta:
429 // Theta is a axis/angle rotation. Direction of a vector is axis, magnitude is angle/2.
430 // Proper quaternion from axis/angle involves computing sin/cos, but the formula becomes numerically unstable as Theta approaches zero.
431 // For near-zero cases we use the first 3 terms of the Taylor series expansion for sin/cos. We check if fourth term is less than machine precision -
432 // then we can safely use the "low angle" approximated version without loss of accuracy.
433 if (thetaMagnitudeSq
< sqrtf(24.0f
* 1e-6f
)) {
434 quaternionScale(&deltaQ
, &deltaQ
, 1.0f
- thetaMagnitudeSq
/ 6.0f
);
435 deltaQ
.q0
= 1.0f
- thetaMagnitudeSq
/ 2.0f
;
438 const float thetaMagnitude
= sqrtf(thetaMagnitudeSq
);
439 quaternionScale(&deltaQ
, &deltaQ
, sin_approx(thetaMagnitude
) / thetaMagnitude
);
440 deltaQ
.q0
= cos_approx(thetaMagnitude
);
443 // Calculate final orientation and renormalize
444 quaternionMultiply(&orientation
, &orientation
, &deltaQ
);
445 quaternionNormalize(&orientation
, &orientation
);
448 // Check for invalid quaternion and reset to previous known good one
449 imuCheckAndResetOrientationQuaternion(&prevOrientation
, accBF
);
451 // Pre-compute rotation matrix from quaternion
452 imuComputeRotationMatrix();
455 STATIC_UNIT_TESTED
void imuUpdateEulerAngles(void)
457 /* Compute pitch/roll angles */
458 attitude
.values
.roll
= RADIANS_TO_DECIDEGREES(atan2_approx(rMat
[2][1], rMat
[2][2]));
459 attitude
.values
.pitch
= RADIANS_TO_DECIDEGREES((0.5f
* M_PIf
) - acos_approx(-rMat
[2][0]));
460 attitude
.values
.yaw
= RADIANS_TO_DECIDEGREES(-atan2_approx(rMat
[1][0], rMat
[0][0]));
462 if (attitude
.values
.yaw
< 0)
463 attitude
.values
.yaw
+= 3600;
465 /* Update small angle state */
466 if (calculateCosTiltAngle() > smallAngleCosZ
) {
467 ENABLE_STATE(SMALL_ANGLE
);
469 DISABLE_STATE(SMALL_ANGLE
);
473 static float imuCalculateAccelerometerWeight(const float dT
)
475 // If centrifugal test passed - do the usual "nearness" style check
476 float accMagnitudeSq
= 0;
478 for (int axis
= 0; axis
< 3; axis
++) {
479 accMagnitudeSq
+= acc
.accADCf
[axis
] * acc
.accADCf
[axis
];
482 // Magnitude^2 in percent of G^2
483 const float nearness
= ABS(100 - (accMagnitudeSq
* 100));
484 const float accWeight_Nearness
= (nearness
> MAX_ACC_SQ_NEARNESS
) ? 0.0f
: 1.0f
;
486 // Experiment: if rotation rate on a FIXED_WING_LEGACY is higher than a threshold - centrifugal force messes up too much and we
487 // should not use measured accel for AHRS comp
488 // Centrifugal acceleration AccelC = Omega^2 * R = Speed^2 / R
490 // For a banked turn R = Speed^2 / (G * tan(Roll))
491 // Omega = G * tan(Roll) / Speed
492 // Knowing the typical airspeed is around ~20 m/s we can calculate roll angles that yield certain angular rate
493 // 1 deg => 0.49 deg/s
494 // 2 deg => 0.98 deg/s
495 // 5 deg => 2.45 deg/s
496 // 10 deg => 4.96 deg/s
497 // Therefore for a typical plane a sustained angular rate of ~2.45 deg/s will yield a banking error of ~5 deg
498 // Since we can't do proper centrifugal compensation at the moment we pass the magnitude of angular rate through an
499 // LPF with a low cutoff and if it's larger than our threshold - invalidate accelerometer
501 // Default - don't apply rate/ignore scaling
502 float accWeight_RateIgnore
= 1.0f
;
504 if (ARMING_FLAG(ARMED
) && STATE(FIXED_WING_LEGACY
) && imuConfig()->acc_ignore_rate
) {
505 const float rotRateMagnitude
= sqrtf(vectorNormSquared(&imuMeasuredRotationBF
));
506 const float rotRateMagnitudeFiltered
= pt1FilterApply4(&rotRateFilter
, rotRateMagnitude
, IMU_CENTRIFUGAL_LPF
, dT
);
508 if (imuConfig()->acc_ignore_slope
) {
509 const float rateSlopeMin
= DEGREES_TO_RADIANS((imuConfig()->acc_ignore_rate
- imuConfig()->acc_ignore_slope
));
510 const float rateSlopeMax
= DEGREES_TO_RADIANS((imuConfig()->acc_ignore_rate
+ imuConfig()->acc_ignore_slope
));
512 accWeight_RateIgnore
= scaleRangef(constrainf(rotRateMagnitudeFiltered
, rateSlopeMin
, rateSlopeMax
), rateSlopeMin
, rateSlopeMax
, 1.0f
, 0.0f
);
515 if (rotRateMagnitudeFiltered
> DEGREES_TO_RADIANS(imuConfig()->acc_ignore_rate
)) {
516 accWeight_RateIgnore
= 0.0f
;
521 return accWeight_Nearness
* accWeight_RateIgnore
;
524 static void imuCalculateEstimatedAttitude(float dT
)
527 const bool canUseMAG
= sensors(SENSOR_MAG
) && compassIsHealthy();
529 const bool canUseMAG
= false;
532 float courseOverGround
= 0;
537 if (STATE(FIXED_WING_LEGACY
)) {
538 bool canUseCOG
= isGPSHeadingValid();
540 // Prefer compass (if available)
543 gpsHeadingInitialized
= true; // GPS heading initialised from MAG, continue on GPS if compass fails
545 else if (canUseCOG
) {
546 if (gpsHeadingInitialized
) {
547 courseOverGround
= DECIDEGREES_TO_RADIANS(gpsSol
.groundCourse
);
551 // Re-initialize quaternion from known Roll, Pitch and GPS heading
552 imuComputeQuaternionFromRPY(attitude
.values
.roll
, attitude
.values
.pitch
, gpsSol
.groundCourse
);
553 gpsHeadingInitialized
= true;
555 // Force reset of heading hold target
556 resetHeadingHoldTarget(DECIDEGREES_TO_DEGREES(attitude
.values
.yaw
));
561 // Multicopters don't use GPS heading
567 // In absence of GPS MAG is the only option
573 fpVector3_t measuredMagBF
= { .v
= { mag
.magADC
[X
], mag
.magADC
[Y
], mag
.magADC
[Z
] } };
575 const float magWeight
= imuGetPGainScaleFactor() * 1.0f
;
576 const float accWeight
= imuGetPGainScaleFactor() * imuCalculateAccelerometerWeight(dT
);
577 const bool useAcc
= (accWeight
> 0.001f
);
579 imuMahonyAHRSupdate(dT
, &imuMeasuredRotationBF
,
580 useAcc
? &imuMeasuredAccelBF
: NULL
,
581 useMag
? &measuredMagBF
: NULL
,
582 useCOG
, courseOverGround
,
586 imuUpdateEulerAngles();
590 void imuHILUpdate(void)
593 attitude
.values
.roll
= hilToFC
.rollAngle
;
594 attitude
.values
.pitch
= hilToFC
.pitchAngle
;
595 attitude
.values
.yaw
= hilToFC
.yawAngle
;
597 /* Compute rotation quaternion for future use */
598 imuComputeQuaternionFromRPY(attitude
.values
.roll
, attitude
.values
.pitch
, attitude
.values
.yaw
);
600 /* Fake accADC readings */
601 accADCf
[X
] = hilToFC
.bodyAccel
[X
] / GRAVITY_CMSS
;
602 accADCf
[Y
] = hilToFC
.bodyAccel
[Y
] / GRAVITY_CMSS
;
603 accADCf
[Z
] = hilToFC
.bodyAccel
[Z
] / GRAVITY_CMSS
;
607 void imuUpdateAccelerometer(void)
610 if (sensors(SENSOR_ACC
) && !hilActive
) {
612 isAccelUpdatedAtLeastOnce
= true;
615 if (sensors(SENSOR_ACC
)) {
617 isAccelUpdatedAtLeastOnce
= true;
622 void imuCheckVibrationLevels(void)
624 fpVector3_t accVibeLevels
;
626 accGetVibrationLevels(&accVibeLevels
);
627 const uint32_t accClipCount
= accGetClipCount();
629 DEBUG_SET(DEBUG_VIBE
, 0, accVibeLevels
.x
* 100);
630 DEBUG_SET(DEBUG_VIBE
, 1, accVibeLevels
.y
* 100);
631 DEBUG_SET(DEBUG_VIBE
, 2, accVibeLevels
.z
* 100);
632 DEBUG_SET(DEBUG_VIBE
, 3, accClipCount
);
633 // DEBUG_VIBE values 4-7 are used by NAV estimator
636 void imuUpdateAttitude(timeUs_t currentTimeUs
)
639 static timeUs_t previousIMUUpdateTimeUs
;
640 const float dT
= (currentTimeUs
- previousIMUUpdateTimeUs
) * 1e-6;
641 previousIMUUpdateTimeUs
= currentTimeUs
;
643 if (sensors(SENSOR_ACC
) && isAccelUpdatedAtLeastOnce
) {
646 gyroGetMeasuredRotationRate(&imuMeasuredRotationBF
); // Calculate gyro rate in body frame in rad/s
647 accGetMeasuredAcceleration(&imuMeasuredAccelBF
); // Calculate accel in body frame in cm/s/s
648 imuCheckVibrationLevels();
649 imuCalculateEstimatedAttitude(dT
); // Update attitude estimate
653 imuUpdateMeasuredAcceleration();
656 gyroGetMeasuredRotationRate(&imuMeasuredRotationBF
); // Calculate gyro rate in body frame in rad/s
657 accGetMeasuredAcceleration(&imuMeasuredAccelBF
); // Calculate accel in body frame in cm/s/s
658 imuCheckVibrationLevels();
659 imuCalculateEstimatedAttitude(dT
); // Update attitude estimate
662 acc
.accADCf
[X
] = 0.0f
;
663 acc
.accADCf
[Y
] = 0.0f
;
664 acc
.accADCf
[Z
] = 0.0f
;
668 bool isImuReady(void)
670 return sensors(SENSOR_ACC
) && gyroIsCalibrationComplete();
673 bool isImuHeadingValid(void)
675 return (sensors(SENSOR_MAG
) && STATE(COMPASS_CALIBRATED
)) || (STATE(FIXED_WING_LEGACY
) && gpsHeadingInitialized
);
678 float calculateCosTiltAngle(void)
680 return 1.0f
- 2.0f
* sq(orientation
.q1
) - 2.0f
* sq(orientation
.q2
);