AP_AHRS: clarify frame of get_location_from_origin_offset

... by renaming it get_location_from_origin_offset_NED
This commit is contained in:
Peter Barker 2024-06-06 20:56:27 +10:00 committed by Peter Barker
parent 7e5810a746
commit 7ea2e60b5a
2 changed files with 4 additions and 4 deletions

View File

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

View File

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