diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index 05b2d1f1ae..e22a769df0 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -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(); } } diff --git a/libraries/AP_Compass/CompassCalibrator.cpp b/libraries/AP_Compass/CompassCalibrator.cpp index bcd8124459..977ab0b6a2 100644 --- a/libraries/AP_Compass/CompassCalibrator.cpp +++ b/libraries/AP_Compass/CompassCalibrator.cpp @@ -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); } diff --git a/libraries/AP_Compass/CompassCalibrator.h b/libraries/AP_Compass/CompassCalibrator.h index 1db0f79a3a..6fb7f06143 100644 --- a/libraries/AP_Compass/CompassCalibrator.h +++ b/libraries/AP_Compass/CompassCalibrator.h @@ -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);