From 027336dbb88abdcf7f4e767e551698444ab36adb Mon Sep 17 00:00:00 2001 From: Josh Henderson Date: Sat, 11 Sep 2021 04:40:29 -0400 Subject: [PATCH] AP_InertialNav: rename to get_position_xy() & get_velocity_xy() --- libraries/AP_InertialNav/AP_InertialNav.cpp | 20 ++++++++++++++++++++ libraries/AP_InertialNav/AP_InertialNav.h | 14 ++++++++++++++ 2 files changed, 34 insertions(+) diff --git a/libraries/AP_InertialNav/AP_InertialNav.cpp b/libraries/AP_InertialNav/AP_InertialNav.cpp index b037d629fa..0848266679 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav.cpp @@ -61,6 +61,16 @@ const Vector3f &AP_InertialNav::get_position(void) const return _relpos_cm; } +/** + * get_position_xy - returns the current x-y position relative to the home location in cm. + * + * @return + */ +const Vector2f &AP_InertialNav::get_position_xy() const +{ + return _relpos_cm.xy(); +} + /** * get_velocity - returns the current velocity in cm/s * @@ -74,6 +84,16 @@ const Vector3f &AP_InertialNav::get_velocity() const return _velocity_cm; } +/** + * get_velocity_xy - returns the current x-y velocity relative to the home location in cm. + * + * @return + */ +const Vector2f &AP_InertialNav::get_velocity_xy() const +{ + return _velocity_cm.xy(); +} + /** * get_speed_xy - returns the current horizontal speed in cm/s * diff --git a/libraries/AP_InertialNav/AP_InertialNav.h b/libraries/AP_InertialNav/AP_InertialNav.h index 23d8ea33b2..e4004a274c 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.h +++ b/libraries/AP_InertialNav/AP_InertialNav.h @@ -35,6 +35,13 @@ public: */ const Vector3f& get_position() const; + /** + * get_position_xy - returns the current x-y position relative to the home location in cm. + * + * @return + */ + const Vector2f& get_position_xy() const; + /** * get_velocity - returns the current velocity in cm/s * @@ -45,6 +52,13 @@ public: */ const Vector3f& get_velocity() const; + /** + * get_velocity_xy - returns the current x-y velocity relative to the home location in cm. + * + * @return + */ + const Vector2f& get_velocity_xy() const; + /** * get_speed_xy - returns the current horizontal speed in cm/s *