1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 00:35:34 +03:00

Make sensor calibration flags system STATEs; Check for calibration values for ACC and MAG; Block arming if calibration is not done for available sensor; Indicate ARMing blockers in armingFlags; Report armingFlags via MSP_STATUS_EX

This commit is contained in:
Konstantin Sharlaimov (DigitalEntity) 2016-12-08 22:02:59 +10:00
parent 6f17bdc146
commit 5e95d7d055
11 changed files with 282 additions and 269 deletions

View file

@ -384,14 +384,18 @@ void updateAccelerationReadings(void)
alignSensors(acc.accADC, acc.dev.accAlign);
}
void setAccelerationZero(flightDynamicsTrims_t * accZeroToUse)
void setAccelerationCalibrationValues(flightDynamicsTrims_t * accZeroToUse, flightDynamicsTrims_t * accGainToUse)
{
accZero = accZeroToUse;
}
void setAccelerationGain(flightDynamicsTrims_t * accGainToUse)
{
accGain = accGainToUse;
if ((accZero->raw[X] != 0) && (accZero->raw[Y] != 0) && (accZero->raw[Z] != 0) &&
(accGain->raw[X] != 4096) && (accGain->raw[Y] != 4096) &&(accGain->raw[Z] != 4096)) {
ENABLE_STATE(ACCELEROMETER_CALIBRATED);
}
else {
DISABLE_STATE(ACCELEROMETER_CALIBRATED);
}
}
void setAccelerationFilter(uint8_t initialAccLpfCutHz)