AP_Compass: only play compass cal cancel tone if a cal was running

This commit is contained in:
Jonathan Challinger 2015-09-02 11:20:15 -07:00 committed by Andrew Tridgell
parent 3b480bd6ec
commit 78af6d61de
1 changed files with 5 additions and 2 deletions

View File

@ -94,9 +94,12 @@ Compass::start_calibration_all(bool retry, bool autosave, float delay, bool auto
void
Compass::cancel_calibration(uint8_t i)
{
_calibrator[i].clear();
AP_Notify::events.compass_cal_canceled = 1;
AP_Notify::events.initiated_compass_cal = 0;
if (_calibrator[i].running() || _calibrator[i].get_status() == COMPASS_CAL_WAITING_TO_START) {
AP_Notify::events.compass_cal_canceled = 1;
}
_calibrator[i].clear();
}
void