diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 454bf0203e..8b7c1faa0c 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -3536,7 +3536,7 @@ bool AP_AHRS::get_velocity_NED(Vector3f &vec) const // return location corresponding to vector relative to the // vehicle's origin -bool AP_AHRS::get_location_from_origin_offset(Location &loc, const Vector3p &offset_ned) const +bool AP_AHRS::get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const { if (!get_origin(loc)) { return false; @@ -3548,7 +3548,7 @@ bool AP_AHRS::get_location_from_origin_offset(Location &loc, const Vector3p &off // return location corresponding to vector relative to the // vehicle's home location -bool AP_AHRS::get_location_from_home_offset(Location &loc, const Vector3p &offset_ned) const +bool AP_AHRS::get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const { if (!home_is_set()) { return false; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index d71912c9f5..16ec1009e0 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -277,8 +277,8 @@ public: // return location corresponding to vector relative to the // vehicle's origin - bool get_location_from_origin_offset(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED; - bool get_location_from_home_offset(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED; + bool get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED; + bool get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED; // Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops. // This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.