mirror of https://github.com/ArduPilot/ardupilot
Notify: baro warning tone alarm
This commit is contained in:
parent
cd9e786935
commit
dcc74be4aa
|
@ -112,6 +112,15 @@ void ToneAlarm_PX4::update()
|
|||
}
|
||||
}
|
||||
|
||||
// check baro glitch
|
||||
if (flags.baro_glitching != AP_Notify::flags.baro_glitching) {
|
||||
flags.baro_glitching = AP_Notify::flags.baro_glitching;
|
||||
if (flags.baro_glitching) {
|
||||
// gps glitch warning tune
|
||||
play_tune(TONE_BARO_WARNING_TUNE);
|
||||
}
|
||||
}
|
||||
|
||||
// check parachute release
|
||||
if (flags.parachute_release != AP_Notify::flags.parachute_release) {
|
||||
flags.parachute_release = AP_Notify::flags.parachute_release;
|
||||
|
|
|
@ -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 baro_glitching : 1; // 1 if baro alt is glitching
|
||||
uint8_t arming_failed : 1; // 0 = failing checks, 1 = passed
|
||||
uint8_t parachute_release : 1; // 1 if parachute is being released
|
||||
uint8_t ekf_bad : 1; // 1 if ekf position has gone bad
|
||||
|
|
Loading…
Reference in New Issue