mirror of https://github.com/ArduPilot/ardupilot
Notify: add arming failure tone
This commit is contained in:
parent
7bb981f2df
commit
f0fc0397d3
|
@ -42,6 +42,7 @@ public:
|
|||
uint16_t failsafe_radio : 1; // 1 if radio failsafe
|
||||
uint16_t failsafe_battery : 1; // 1 if battery failsafe
|
||||
uint16_t failsafe_gps : 1; // 1 if gps failsafe
|
||||
uint16_t arming_failed : 1; // 1 if copter failed to arm after user input
|
||||
|
||||
// additional flags
|
||||
uint16_t external_leds : 1; // 1 if external LEDs are enabled (normally only used for copter)
|
||||
|
|
|
@ -64,6 +64,13 @@ void ToneAlarm_PX4::update()
|
|||
if (_tonealarm_fd == -1) {
|
||||
return;
|
||||
}
|
||||
|
||||
if(flags.arming_failed != AP_Notify::flags.arming_failed) {
|
||||
flags.arming_failed = AP_Notify::flags.arming_failed;
|
||||
if(flags.arming_failed) {
|
||||
play_tune(TONE_ARMING_FAILURE_TUNE);
|
||||
}
|
||||
}
|
||||
|
||||
// check if arming status has changed
|
||||
if (flags.armed != AP_Notify::flags.armed) {
|
||||
|
|
|
@ -41,6 +41,7 @@ private:
|
|||
uint8_t failsafe_battery : 1; // 1 if battery failsafe
|
||||
uint8_t gps_glitching : 1; // 1 if gps position is not good
|
||||
uint8_t failsafe_gps : 1; // 1 if gps failsafe
|
||||
uint8_t arming_failed : 1; // 0 = failing checks, 1 = passed
|
||||
} flags;
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue