AP_AHRS: comment to clarify get-velocity-NED units

This commit is contained in:
Randy Mackay 2023-07-12 21:12:03 +09:00
parent b80ea6572c
commit 4b96c2f568
1 changed files with 2 additions and 0 deletions

View File

@ -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