AP_Compass: rename CompassCalibrator::clear to stop

This commit is contained in:
Randy Mackay 2019-11-19 15:03:12 +09:00 committed by Andrew Tridgell
parent 6c8ee8fa67
commit d9fde84ccb
3 changed files with 5 additions and 5 deletions

View File

@ -116,7 +116,7 @@ void Compass::_cancel_calibration(uint8_t i)
AP_Notify::events.compass_cal_canceled = 1;
}
_cal_saved[i] = false;
_calibrator[i].clear();
_calibrator[i].stop();
}
void Compass::_cancel_calibration_mask(uint8_t mask)
@ -172,7 +172,7 @@ bool Compass::_accept_calibration_mask(uint8_t mask)
if (!_accept_calibration(i)) {
success = false;
}
_calibrator[i].clear();
_calibrator[i].stop();
}
}

View File

@ -73,10 +73,10 @@ CompassCalibrator::CompassCalibrator():
_tolerance(COMPASS_CAL_DEFAULT_TOLERANCE),
_sample_buffer(nullptr)
{
clear();
stop();
}
void CompassCalibrator::clear()
void CompassCalibrator::stop()
{
set_status(COMPASS_CAL_NOT_STARTED);
}

View File

@ -30,7 +30,7 @@ public:
// start or stop the calibration
void start(bool retry, float delay, uint16_t offset_max, uint8_t compass_idx);
void clear();
void stop();
// update the state machine and calculate offsets, diagonals and offdiagonals
void update(bool &failure);