mirror of https://github.com/ArduPilot/ardupilot
ToneAlarm: handle arming_failed as event
This commit is contained in:
parent
bd1ae13fdb
commit
3361002379
|
@ -171,11 +171,8 @@ void ToneAlarm_PX4::update()
|
||||||
}
|
}
|
||||||
|
|
||||||
// notify the user when arming fails
|
// notify the user when arming fails
|
||||||
if (flags.arming_failed != AP_Notify::flags.arming_failed) {
|
if (AP_Notify::events.arming_failed) {
|
||||||
flags.arming_failed = AP_Notify::flags.arming_failed;
|
play_tone(AP_NOTIFY_PX4_TONE_QUIET_NEG_FEEDBACK);
|
||||||
if (flags.arming_failed) {
|
|
||||||
play_tone(AP_NOTIFY_PX4_TONE_QUIET_NEG_FEEDBACK);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// notify the user when RC contact is lost
|
// notify the user when RC contact is lost
|
||||||
|
|
|
@ -52,7 +52,6 @@ private:
|
||||||
uint8_t armed : 1; // 0 = disarmed, 1 = armed
|
uint8_t armed : 1; // 0 = disarmed, 1 = armed
|
||||||
uint8_t failsafe_battery : 1; // 1 if battery failsafe
|
uint8_t failsafe_battery : 1; // 1 if battery failsafe
|
||||||
uint8_t failsafe_gps : 1; // 1 if gps failsafe
|
uint8_t failsafe_gps : 1; // 1 if gps failsafe
|
||||||
uint8_t arming_failed : 1; // 0 = failing checks, 1 = passed
|
|
||||||
uint8_t parachute_release : 1; // 1 if parachute is being released
|
uint8_t parachute_release : 1; // 1 if parachute is being released
|
||||||
uint8_t pre_arm_check : 1; // 0 = failing checks, 1 = passed
|
uint8_t pre_arm_check : 1; // 0 = failing checks, 1 = passed
|
||||||
uint8_t failsafe_radio : 1; // 1 if radio failsafe
|
uint8_t failsafe_radio : 1; // 1 if radio failsafe
|
||||||
|
|
Loading…
Reference in New Issue