mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Notify: add events.compass_cal_canceled
This commit is contained in:
parent
adef826a42
commit
28ee63c855
@ -76,6 +76,7 @@ public:
|
||||
uint16_t initiated_compass_cal : 1; // 1 when user input to begin compass cal was accepted
|
||||
uint16_t compass_cal_saved : 1; // 1 when compass calibration was just saved
|
||||
uint16_t compass_cal_failed : 1; // 1 when compass calibration has just failed
|
||||
uint16_t compass_cal_canceled : 1; // 1 when compass calibration was just canceled
|
||||
};
|
||||
|
||||
// the notify flags are static to allow direct class access
|
||||
|
@ -146,6 +146,11 @@ void ToneAlarm_PX4::update()
|
||||
}
|
||||
flags.compass_cal_running = AP_Notify::flags.compass_cal_running;
|
||||
|
||||
if (AP_Notify::events.compass_cal_canceled) {
|
||||
play_tone(AP_NOTIFY_PX4_TONE_QUIET_NEU_FEEDBACK);
|
||||
return;
|
||||
}
|
||||
|
||||
if (AP_Notify::events.initiated_compass_cal) {
|
||||
play_tone(AP_NOTIFY_PX4_TONE_QUIET_NEU_FEEDBACK);
|
||||
return;
|
||||
|
Loading…
Reference in New Issue
Block a user