mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_Compass: add interface for raw and unfiltered field
This commit is contained in:
parent
b2fff2021f
commit
b990eaed68
@ -106,6 +106,26 @@ public:
|
||||
const Vector3f &get_field(uint8_t i) const { return _state[i].field; }
|
||||
const Vector3f &get_field(void) const { return get_field(get_primary()); }
|
||||
|
||||
// raw/unfiltered measurement interface
|
||||
|
||||
|
||||
uint32_t raw_meas_time_us(uint8_t i) const { return _state[i].raw_meas_time_us; }
|
||||
uint32_t raw_meas_time_us() const { return _state[get_primary()].raw_meas_time_us; }
|
||||
uint32_t unfiltered_meas_time_us(uint8_t i) const { return _state[i].raw_meas_time_us; }
|
||||
uint32_t unfiltered_meas_time_us() const { return _state[get_primary()].raw_meas_time_us; }
|
||||
|
||||
bool has_raw_field(uint8_t i) const { return _state[i].has_raw_field; }
|
||||
bool has_raw_field() const { return has_raw_field(get_primary()); }
|
||||
|
||||
bool has_unfiltered_field(uint8_t i) const { return _state[i].has_unfiltered_field; }
|
||||
bool has_unfiltered_field() const { return has_unfiltered_field(get_primary()); }
|
||||
|
||||
const Vector3f &get_raw_field(uint8_t i) const { return _state[i].raw_field; }
|
||||
const Vector3f &get_raw_field(void) const { return get_unfiltered_field(get_primary()); }
|
||||
|
||||
const Vector3f &get_unfiltered_field(uint8_t i) const { return _state[i].unfiltered_field; }
|
||||
const Vector3f &get_unfiltered_field(void) const { return get_unfiltered_field(get_primary()); }
|
||||
|
||||
/// Return the health of a compass
|
||||
bool healthy(uint8_t i) const { return _state[i].healthy; }
|
||||
bool healthy(void) const { return healthy(get_primary()); }
|
||||
@ -319,6 +339,14 @@ private:
|
||||
// when we last got data
|
||||
uint32_t last_update_ms;
|
||||
uint32_t last_update_usec;
|
||||
|
||||
uint32_t raw_meas_time_us;
|
||||
bool has_raw_field;
|
||||
bool has_unfiltered_field;
|
||||
bool updated_raw_field;
|
||||
bool updated_unfiltered_field;
|
||||
Vector3f raw_field;
|
||||
Vector3f unfiltered_field;
|
||||
} _state[COMPASS_MAX_INSTANCES];
|
||||
|
||||
// if we want HIL only
|
||||
|
Loading…
Reference in New Issue
Block a user