mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: comment to clarify get-velocity-NED units
This commit is contained in:
parent
b80ea6572c
commit
4b96c2f568
|
@ -210,6 +210,8 @@ public:
|
|||
|
||||
bool have_inertial_nav() const;
|
||||
|
||||
// return a ground velocity in meters/second, North/East/Down
|
||||
// order. Must only be called if have_inertial_nav() is true
|
||||
bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED;
|
||||
|
||||
// return the relative position NED to either home or origin
|
||||
|
|
Loading…
Reference in New Issue