mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
Buzzer: handle arming_failed as event
This commit is contained in:
parent
a991b4a823
commit
6cfd48d0c6
@ -49,6 +49,12 @@ void Buzzer::update()
|
||||
return;
|
||||
}
|
||||
|
||||
// check for arming failed event
|
||||
if (AP_Notify::events.arming_failed) {
|
||||
// arming failed buzz
|
||||
play_pattern(SINGLE_BUZZ);
|
||||
}
|
||||
|
||||
// reduce 50hz call down to 10hz
|
||||
_counter++;
|
||||
if (_counter < 5) {
|
||||
@ -192,16 +198,6 @@ void Buzzer::update()
|
||||
return;
|
||||
}
|
||||
|
||||
// check arming failed
|
||||
if (_flags.arming_failed != AP_Notify::flags.arming_failed) {
|
||||
_flags.arming_failed = AP_Notify::flags.arming_failed;
|
||||
if (_flags.arming_failed) {
|
||||
// arming failed buzz
|
||||
play_pattern(SINGLE_BUZZ);
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
// check gps glitch
|
||||
if (_flags.gps_glitching != AP_Notify::flags.gps_glitching) {
|
||||
_flags.gps_glitching = AP_Notify::flags.gps_glitching;
|
||||
|
@ -76,7 +76,6 @@ private:
|
||||
uint8_t failsafe_battery : 1; // 1 if battery failsafe has triggered
|
||||
uint8_t failsafe_gps : 1; // 1 if gps failsafe
|
||||
uint8_t baro_glitching : 1; // 1 if baro alt is glitching
|
||||
uint8_t arming_failed : 1; // 0 = failing checks, 1 = passed
|
||||
uint8_t ekf_bad : 1; // 1 if ekf position has gone bad
|
||||
} _flags;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user