mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: constify get_completion_mask and remove use of auto
This commit is contained in:
parent
cf34abba87
commit
69a7a52e5f
|
@ -208,7 +208,7 @@ bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link)
|
|||
cal_status == COMPASS_CAL_RUNNING_STEP_ONE ||
|
||||
cal_status == COMPASS_CAL_RUNNING_STEP_TWO) {
|
||||
uint8_t completion_pct = calibrator.get_completion_percent();
|
||||
auto& completion_mask = calibrator.get_completion_mask();
|
||||
const CompassCalibrator::completion_mask_t& completion_mask = calibrator.get_completion_mask();
|
||||
const Vector3f direction;
|
||||
uint8_t attempt = _calibrator[compass_id].get_attempt();
|
||||
|
||||
|
|
|
@ -147,11 +147,6 @@ void CompassCalibrator::update_completion_mask()
|
|||
}
|
||||
}
|
||||
|
||||
CompassCalibrator::completion_mask_t& CompassCalibrator::get_completion_mask()
|
||||
{
|
||||
return _completion_mask;
|
||||
}
|
||||
|
||||
bool CompassCalibrator::check_for_timeout() {
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
if(running() && tnow - _last_sample_ms > 1000) {
|
||||
|
|
|
@ -50,7 +50,7 @@ public:
|
|||
enum Rotation get_original_orientation() const { return _orig_orientation; }
|
||||
|
||||
float get_completion_percent() const;
|
||||
completion_mask_t& get_completion_mask();
|
||||
const completion_mask_t& get_completion_mask() const { return _completion_mask; }
|
||||
enum compass_cal_status_t get_status() const { return _status; }
|
||||
float get_fitness() const { return sqrtf(_fitness); }
|
||||
float get_orientation_confidence() const { return _orientation_confidence; }
|
||||
|
|
Loading…
Reference in New Issue