From 8e04fb4e8e6f3a1b634425739a3e518365206bfd Mon Sep 17 00:00:00 2001 From: Joshua Henderson Date: Wed, 2 Feb 2022 00:26:14 -0500 Subject: [PATCH] AP_InertialNav: nfc, fix to say relative to EKF origin --- libraries/AP_InertialNav/AP_InertialNav.cpp | 8 ++++---- libraries/AP_InertialNav/AP_InertialNav.h | 10 ++++------ 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/libraries/AP_InertialNav/AP_InertialNav.cpp b/libraries/AP_InertialNav/AP_InertialNav.cpp index 358a9047f9..283f8b7b41 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav.cpp @@ -52,7 +52,7 @@ nav_filter_status AP_InertialNav::get_filter_status() const } /** - * get_position_neu_cm - returns the current position relative to the home location in cm. + * get_position_neu_cm - returns the current position relative to the EKF origin in cm. * * @return */ @@ -62,7 +62,7 @@ const Vector3f &AP_InertialNav::get_position_neu_cm(void) const } /** - * get_position_xy_cm - returns the current x-y position relative to the home location in cm. + * get_position_xy_cm - returns the current x-y position relative to the EKF origin in cm. * * @return */ @@ -72,7 +72,7 @@ const Vector2f &AP_InertialNav::get_position_xy_cm() const } /** - * get_position_z_up_cm - returns the current z position relative to the home location, frame z-axis up, in cm. + * get_position_z_up_cm - returns the current z position relative to the EKF origin, frame z-axis up, in cm. * @return */ float AP_InertialNav::get_position_z_up_cm() const @@ -94,7 +94,7 @@ const Vector3f &AP_InertialNav::get_velocity_neu_cms() const } /** - * get_velocity_xy_cms - returns the current x-y velocity relative to the home location in cm. + * get_velocity_xy_cms - returns the current x-y velocity relative to the EKF origin in cm. * * @return */ diff --git a/libraries/AP_InertialNav/AP_InertialNav.h b/libraries/AP_InertialNav/AP_InertialNav.h index 552a6b4e02..9159a41809 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.h +++ b/libraries/AP_InertialNav/AP_InertialNav.h @@ -27,23 +27,21 @@ public: nav_filter_status get_filter_status() const; /** - * get_position_neu_cm - returns the current position relative to the home location in cm. - * - * the home location was set with AP_InertialNav::set_home_position(int32_t, int32_t) + * get_position_neu_cm - returns the current position relative to the EKF origin in cm. * * @return */ const Vector3f& get_position_neu_cm() const; /** - * get_position_xy_cm - returns the current x-y position relative to the home location in cm. + * get_position_xy_cm - returns the current x-y position relative to the EKF origin in cm. * * @return */ const Vector2f& get_position_xy_cm() const; /** - * get_position_z_up_cm - returns the current z position relative to the home location, frame z up, in cm. + * get_position_z_up_cm - returns the current z position relative to the EKF origin, frame z up, in cm. * @return */ float get_position_z_up_cm() const; @@ -59,7 +57,7 @@ public: const Vector3f& get_velocity_neu_cms() const; /** - * get_velocity_xy_cms - returns the current x-y velocity relative to the home location in cm. + * get_velocity_xy_cms - returns the current x-y velocity relative to the EKF origin in cm. * * @return */