mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: HMC5883: reorganize header
This commit is contained in:
parent
37056e8738
commit
a46ca4c810
|
@ -15,43 +15,7 @@ class AP_HMC5843_SerialBus;
|
|||
|
||||
class AP_Compass_HMC5843 : public AP_Compass_Backend
|
||||
{
|
||||
private:
|
||||
static AP_Compass_Backend *_detect(Compass &compass,
|
||||
AP_HMC5843_SerialBus *bus);
|
||||
|
||||
AP_HMC5843_SerialBus *_bus;
|
||||
AP_HAL::Semaphore *_bus_sem = nullptr;
|
||||
|
||||
float _scaling[3] = {0};
|
||||
bool _initialised;
|
||||
bool read_raw(void);
|
||||
uint8_t _base_config;
|
||||
bool re_initialise(void);
|
||||
bool read_register(uint8_t address, uint8_t *value);
|
||||
bool write_register(uint8_t address, uint8_t value);
|
||||
|
||||
bool _calibrate(uint8_t calibration_gain,
|
||||
uint16_t expected_x,
|
||||
uint16_t expected_yz);
|
||||
bool _detect_version();
|
||||
|
||||
uint32_t _retry_time; // when unhealthy the millis() value to retry at
|
||||
|
||||
int16_t _mag_x;
|
||||
int16_t _mag_y;
|
||||
int16_t _mag_z;
|
||||
int16_t _mag_x_accum;
|
||||
int16_t _mag_y_accum;
|
||||
int16_t _mag_z_accum;
|
||||
uint8_t _accum_count;
|
||||
uint32_t _last_accum_time;
|
||||
|
||||
uint8_t _compass_instance;
|
||||
uint8_t _product_id;
|
||||
|
||||
float _gain_multiple;
|
||||
public:
|
||||
// detect the sensor
|
||||
static AP_Compass_Backend *detect_i2c(Compass &compass,
|
||||
AP_HAL::I2CDriver *i2c);
|
||||
static AP_Compass_Backend *detect_mpu6000(Compass &compass);
|
||||
|
@ -59,9 +23,46 @@ public:
|
|||
AP_Compass_HMC5843(Compass &compass, AP_HMC5843_SerialBus *bus);
|
||||
~AP_Compass_HMC5843();
|
||||
|
||||
bool init(void);
|
||||
void read(void);
|
||||
void accumulate(void);
|
||||
bool init();
|
||||
void read();
|
||||
void accumulate();
|
||||
|
||||
private:
|
||||
static AP_Compass_Backend *_detect(Compass &compass,
|
||||
AP_HMC5843_SerialBus *bus);
|
||||
|
||||
bool read_raw();
|
||||
bool re_initialise();
|
||||
bool read_register(uint8_t address, uint8_t *value);
|
||||
bool write_register(uint8_t address, uint8_t value);
|
||||
|
||||
bool _calibrate(uint8_t calibration_gain, uint16_t expected_x,
|
||||
uint16_t expected_yz);
|
||||
bool _detect_version();
|
||||
|
||||
AP_HMC5843_SerialBus *_bus;
|
||||
AP_HAL::Semaphore *_bus_sem;
|
||||
|
||||
float _scaling[3];
|
||||
float _gain_multiple;
|
||||
uint32_t _last_accum_time;
|
||||
|
||||
// when unhealthy the millis() value to retry at
|
||||
uint32_t _retry_time;
|
||||
|
||||
int16_t _mag_x;
|
||||
int16_t _mag_y;
|
||||
int16_t _mag_z;
|
||||
int16_t _mag_x_accum;
|
||||
int16_t _mag_y_accum;
|
||||
int16_t _mag_z_accum;
|
||||
uint8_t _accum_count;
|
||||
|
||||
uint8_t _base_config;
|
||||
uint8_t _compass_instance;
|
||||
uint8_t _product_id;
|
||||
|
||||
bool _initialised;
|
||||
};
|
||||
|
||||
class AP_HMC5843_SerialBus
|
||||
|
@ -115,7 +116,7 @@ public:
|
|||
bool start_measurements() override;
|
||||
|
||||
private:
|
||||
AuxiliaryBus *_bus = nullptr;
|
||||
AuxiliaryBusSlave *_slave = nullptr;
|
||||
bool _started = false;
|
||||
AuxiliaryBus *_bus;
|
||||
AuxiliaryBusSlave *_slave;
|
||||
bool _started;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue