mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Compass: make is_calibrating const
This commit is contained in:
parent
d131cf01d3
commit
944b82a7be
@ -179,7 +179,7 @@ public:
|
||||
void cancel_calibration_all();
|
||||
|
||||
bool compass_cal_requires_reboot() const { return _cal_requires_reboot; }
|
||||
bool is_calibrating();
|
||||
bool is_calibrating() const;
|
||||
|
||||
// indicate which bit in LOG_BITMASK indicates we should log compass readings
|
||||
void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; }
|
||||
|
@ -315,7 +315,7 @@ bool Compass::send_mag_cal_report(const GCS_MAVLINK& link)
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Compass::is_calibrating()
|
||||
bool Compass::is_calibrating() const
|
||||
{
|
||||
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
|
||||
if (_calibrator[i] == nullptr) {
|
||||
|
Loading…
Reference in New Issue
Block a user