diff --git a/libraries/AP_Compass/AP_Compass_AK8963.h b/libraries/AP_Compass/AP_Compass_AK8963.h index e8d106bfacf58210333752ddd734d21ffff3c396..5a75a56b897a4435084f07d9ebbeeba78e9edf0a 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.h +++ b/libraries/AP_Compass/AP_Compass_AK8963.h @@ -35,13 +35,13 @@ public: virtual ~AP_Compass_AK8963(); - bool init() override; void read() override; private: AP_Compass_AK8963(Compass &compass, AP_AK8963_BusDriver *bus, enum Rotation rotation = ROTATION_NONE); + bool init(); void _make_factory_sensitivity_adjustment(Vector3f &field) const; void _make_adc_sensitivity_adjustment(Vector3f &field) const; diff --git a/libraries/AP_Compass/AP_Compass_BMM150.h b/libraries/AP_Compass/AP_Compass_BMM150.h index fd990aa65b65ecb1214bce87348a6e7a0de6a27b..de24c6d4da9e65e0b38fc44cae686d00bcaf9915 100644 --- a/libraries/AP_Compass/AP_Compass_BMM150.h +++ b/libraries/AP_Compass/AP_Compass_BMM150.h @@ -30,7 +30,6 @@ public: static AP_Compass_Backend *probe(Compass &compass, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev); - bool init() override; void read() override; static constexpr const char *name = "BMM150"; @@ -41,6 +40,7 @@ private: /** * Device periodic callback to read data from the sensor. */ + bool init(); bool _update(); bool _load_trim_values(); int16_t _compensate_xy(int16_t xy, uint32_t rhall, int32_t txy1, int32_t txy2); diff --git a/libraries/AP_Compass/AP_Compass_Backend.h b/libraries/AP_Compass/AP_Compass_Backend.h index 988f0bb630e9b21d6fcb804a02a248aed99e2674..84101a3966432e17a946d3db7fc926b7e7abb19f 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.h +++ b/libraries/AP_Compass/AP_Compass_Backend.h @@ -31,9 +31,6 @@ public: // override with a custom destructor if need be. virtual ~AP_Compass_Backend(void) {} - // initialize the magnetometers - virtual bool init(void) = 0; - // read sensor data virtual void read(void) = 0; diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.h b/libraries/AP_Compass/AP_Compass_HMC5843.h index 2534f98706cea1a9397c534c32855bddce55bd28..b2c44532e3245af0c7c018d4471f82e547693330 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.h +++ b/libraries/AP_Compass/AP_Compass_HMC5843.h @@ -28,13 +28,13 @@ public: virtual ~AP_Compass_HMC5843(); - bool init() override; void read() override; private: AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus, bool force_external, enum Rotation rotation); + bool init(); bool _check_whoami(); bool _calibrate(); bool _setup_sampling_mode(); diff --git a/libraries/AP_Compass/AP_Compass_LSM9DS1.h b/libraries/AP_Compass/AP_Compass_LSM9DS1.h index e204588cc8455d2acebcba851040e3800cbad02e..4b814ee3dd72b25adb4d89cd267ddea731f37f37 100644 --- a/libraries/AP_Compass/AP_Compass_LSM9DS1.h +++ b/libraries/AP_Compass/AP_Compass_LSM9DS1.h @@ -16,13 +16,13 @@ public: static constexpr const char *name = "LSM9DS1"; - bool init() override; void read() override; virtual ~AP_Compass_LSM9DS1() {} private: AP_Compass_LSM9DS1(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev); + bool init(); bool _check_id(void); bool _configure(void); bool _set_scale(void); diff --git a/libraries/AP_Compass/AP_Compass_QURT.h b/libraries/AP_Compass/AP_Compass_QURT.h index 193042e7bd3d1e0c2e6d76c84e7bc97ddaf6cbcc..c0dc1af72343bd146580c19945f70242c33d3263 100644 --- a/libraries/AP_Compass/AP_Compass_QURT.h +++ b/libraries/AP_Compass/AP_Compass_QURT.h @@ -6,7 +6,6 @@ class AP_Compass_QURT : public AP_Compass_Backend { public: - bool init(void) override; void read(void) override; AP_Compass_QURT(Compass &compass); @@ -15,6 +14,7 @@ public: static AP_Compass_Backend *detect(Compass &compass); private: + bool init(void); void timer_update(void); uint8_t instance;