AP_Notify: add gps glitching and failsafe flags
This commit is contained in:
parent
c596b27719
commit
54cb815fec
@ -85,6 +85,24 @@ void ToneAlarm_PX4::update()
|
||||
play_tune(TONE_BATTERY_WARNING_FAST_TUNE);
|
||||
}
|
||||
}
|
||||
|
||||
// check gps glitch
|
||||
if (flags.gps_glitching != AP_Notify::flags.gps_glitching) {
|
||||
flags.gps_glitching = AP_Notify::flags.gps_glitching;
|
||||
if (flags.gps_glitching) {
|
||||
// gps glitch warning tune
|
||||
play_tune(TONE_GPS_WARNING_TUNE);
|
||||
}
|
||||
}
|
||||
|
||||
// check gps failsafe
|
||||
if (flags.failsafe_gps != AP_Notify::flags.failsafe_gps) {
|
||||
flags.failsafe_gps = AP_Notify::flags.failsafe_gps;
|
||||
if (flags.failsafe_gps) {
|
||||
// gps glitch warning tune
|
||||
play_tune(TONE_GPS_WARNING_TUNE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
|
@ -39,6 +39,8 @@ private:
|
||||
struct tonealarm_type {
|
||||
uint8_t armed : 1; // 0 = disarmed, 1 = armed
|
||||
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
|
||||
} flags;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user