mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: add alias get_position to get_location
This commit is contained in:
parent
9aeab4978f
commit
9229fb6f9d
@ -106,6 +106,10 @@ public:
|
|||||||
|
|
||||||
// dead-reckoning support
|
// dead-reckoning support
|
||||||
bool get_location(struct Location &loc) const;
|
bool get_location(struct Location &loc) const;
|
||||||
|
// for scripting until aliases get sorted out:
|
||||||
|
bool get_position(struct Location &loc) const {
|
||||||
|
return get_location(loc);
|
||||||
|
}
|
||||||
|
|
||||||
// get latest altitude estimate above ground level in meters and validity flag
|
// get latest altitude estimate above ground level in meters and validity flag
|
||||||
bool get_hagl(float &hagl) const WARN_IF_UNUSED;
|
bool get_hagl(float &hagl) const WARN_IF_UNUSED;
|
||||||
|
Loading…
Reference in New Issue
Block a user