Browse Source

AP_Compass: make init() private

not called from frontend
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
4ba00720aa
  1. 2
      libraries/AP_Compass/AP_Compass_AK8963.h
  2. 2
      libraries/AP_Compass/AP_Compass_BMM150.h
  3. 3
      libraries/AP_Compass/AP_Compass_Backend.h
  4. 2
      libraries/AP_Compass/AP_Compass_HMC5843.h
  5. 2
      libraries/AP_Compass/AP_Compass_LSM9DS1.h
  6. 2
      libraries/AP_Compass/AP_Compass_QURT.h

2
libraries/AP_Compass/AP_Compass_AK8963.h

@ -35,13 +35,13 @@ public: @@ -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;

2
libraries/AP_Compass/AP_Compass_BMM150.h

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

3
libraries/AP_Compass/AP_Compass_Backend.h

@ -31,9 +31,6 @@ public: @@ -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;

2
libraries/AP_Compass/AP_Compass_HMC5843.h

@ -28,13 +28,13 @@ public: @@ -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();

2
libraries/AP_Compass/AP_Compass_LSM9DS1.h

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

2
libraries/AP_Compass/AP_Compass_QURT.h

@ -6,7 +6,6 @@ @@ -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: @@ -15,6 +14,7 @@ public:
static AP_Compass_Backend *detect(Compass &compass);
private:
bool init(void);
void timer_update(void);
uint8_t instance;

Loading…
Cancel
Save