mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Compass: removed two unused functions
This commit is contained in:
parent
2a47337dc1
commit
d7bac39539
@ -14,9 +14,9 @@ class AP_Compass_HMC5843 : public AP_Compass_Backend
|
||||
private:
|
||||
float calibration[3];
|
||||
bool _initialised;
|
||||
virtual bool read_raw(void);
|
||||
bool read_raw(void);
|
||||
uint8_t _base_config;
|
||||
virtual bool re_initialise(void);
|
||||
bool re_initialise(void);
|
||||
bool read_register(uint8_t address, uint8_t *value);
|
||||
bool write_register(uint8_t address, uint8_t value);
|
||||
uint32_t _retry_time; // when unhealthy the millis() value to retry at
|
||||
|
@ -25,10 +25,6 @@ private:
|
||||
Vector3f _sum[COMPASS_MAX_INSTANCES];
|
||||
uint32_t _count[COMPASS_MAX_INSTANCES];
|
||||
uint64_t _last_timestamp[COMPASS_MAX_INSTANCES];
|
||||
|
||||
virtual bool read_raw(void) { return false;}
|
||||
virtual bool re_initialise(void) {return false;}
|
||||
|
||||
};
|
||||
|
||||
#endif // AP_Compass_PX4_H
|
||||
|
Loading…
Reference in New Issue
Block a user