Browse Source

AP_Compass: rename CompassCalibrator::clear to stop

master
Randy Mackay 5 years ago committed by Andrew Tridgell
parent
commit
80b4eaa87a
  1. 4
      libraries/AP_Compass/AP_Compass_Calibration.cpp
  2. 4
      libraries/AP_Compass/CompassCalibrator.cpp
  3. 2
      libraries/AP_Compass/CompassCalibrator.h

4
libraries/AP_Compass/AP_Compass_Calibration.cpp

@ -116,7 +116,7 @@ void Compass::_cancel_calibration(uint8_t i) @@ -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) @@ -172,7 +172,7 @@ bool Compass::_accept_calibration_mask(uint8_t mask)
if (!_accept_calibration(i)) {
success = false;
}
_calibrator[i].clear();
_calibrator[i].stop();
}
}

4
libraries/AP_Compass/CompassCalibrator.cpp

@ -73,10 +73,10 @@ CompassCalibrator::CompassCalibrator(): @@ -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);
}

2
libraries/AP_Compass/CompassCalibrator.h

@ -30,7 +30,7 @@ public: @@ -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);

Loading…
Cancel
Save