mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
AP_Compass: fixed Compass::get_raw_field()
It seems as if it were a copy-paste error. A statis analyzer would definetely be angry.
This commit is contained in:
parent
375724b319
commit
bd7c313bee
@ -129,7 +129,7 @@ public:
|
|||||||
bool has_unfiltered_field() const { return has_unfiltered_field(get_primary()); }
|
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(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_raw_field(void) const { return get_raw_field(get_primary()); }
|
||||||
|
|
||||||
const Vector3f &get_unfiltered_field(uint8_t i) const { return _state[i].unfiltered_field; }
|
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()); }
|
const Vector3f &get_unfiltered_field(void) const { return get_unfiltered_field(get_primary()); }
|
||||||
|
Loading…
Reference in New Issue
Block a user