1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 12:25:20 +03:00

Fixed magAlign, reconfigureAlignment was being called before mag

detection.  Closes #101.
This commit is contained in:
Dominic Clifton 2014-10-28 16:09:44 +00:00
parent a65a937313
commit 3d7455d557

View file

@ -393,6 +393,16 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t
detectAcc(accHardwareToUse);
detectBaro();
#ifdef MAG
if (hmc5883lDetect()) {
#ifdef NAZE
magAlign = CW180_DEG;
#endif
} else {
sensorsClear(SENSOR_MAG);
}
#endif
reconfigureAlignment(sensorAlignmentConfig);
// Now time to init things, acc first
@ -401,14 +411,6 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t
// this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here.
gyro.init();
#ifdef MAG
if (hmc5883lDetect()) {
magAlign = CW180_DEG; // default NAZE alignment
} else {
sensorsClear(SENSOR_MAG);
}
#endif
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
if (sensors(SENSOR_MAG)) {
// calculate magnetic declination