Copter: fix to dcm-check to be continuous

dcm-check was triggering after 10 bad headings but these did not need to
be continuous meaning if the vehicle was flown long enough it would
almost certainly trigger a dcm-check failure and land
This commit is contained in:
Randy Mackay 2014-10-27 12:37:56 +09:00
parent 8041613c06
commit 3a8d4cdcda
1 changed files with 5 additions and 5 deletions

View File

@ -81,12 +81,12 @@ void ekf_dcm_check()
}
}
} else {
// if compass is flagged as bad
if (ekf_check_state.bad_compass) {
// reduce counter
// reduce counter
if (ekf_check_state.fail_count_compass > 0) {
ekf_check_state.fail_count_compass--;
// if counter reaches zero then clear flag
if (ekf_check_state.fail_count_compass == 0) {
// if compass is flagged as bad and the counter reaches zero then clear flag
if (ekf_check_state.bad_compass && ekf_check_state.fail_count_compass == 0) {
ekf_check_state.bad_compass = false;
// log recovery in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_EKFINAV_CHECK, ERROR_CODE_EKFINAV_CHECK_VARIANCE_CLEARED);