From 266d384ca7d61a83fcd8a7a0cb72a1968ea711aa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 21 Jan 2022 10:42:41 +1100 Subject: [PATCH] ArduPlane: rename AP_AHRS::get_position to get_location --- ArduPlane/ArduPlane.cpp | 2 +- ArduPlane/GCS_Mavlink.cpp | 2 +- ArduPlane/commands.cpp | 2 +- ArduPlane/quadplane.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 13558fa2a8..52f8f32411 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -396,7 +396,7 @@ void Plane::update_GPS_50Hz(void) gps.update(); // get position from AHRS - have_position = ahrs.get_position(current_loc); + have_position = ahrs.get_location(current_loc); ahrs.get_relative_position_D_home(relative_altitude); relative_altitude *= -1.0f; } diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 638c061148..2916bcf556 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1340,7 +1340,7 @@ int16_t GCS_MAVLINK_Plane::high_latency_target_altitude() const { AP_AHRS &ahrs = AP::ahrs(); struct Location global_position_current; - UNUSED_RESULT(ahrs.get_position(global_position_current)); + UNUSED_RESULT(ahrs.get_location(global_position_current)); #if HAL_QUADPLANE_ENABLED const QuadPlane &quadplane = plane.quadplane; diff --git a/ArduPlane/commands.cpp b/ArduPlane/commands.cpp index d8f97342f4..c5bcee335b 100644 --- a/ArduPlane/commands.cpp +++ b/ArduPlane/commands.cpp @@ -122,7 +122,7 @@ void Plane::update_home() } if (ahrs.home_is_set() && !ahrs.home_is_locked()) { Location loc; - if(ahrs.get_position(loc) && gps.status() >= AP_GPS::GPS_OK_FIX_3D) { + if(ahrs.get_location(loc) && gps.status() >= AP_GPS::GPS_OK_FIX_3D) { // we take the altitude directly from the GPS as we are // about to reset the baro calibration. We can't use AHRS // altitude or we can end up perpetuating a bias in diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index e3a1e9d297..344a141ef1 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2542,7 +2542,7 @@ void QuadPlane::vtol_position_controller(void) } } if (plane.control_mode == &plane.mode_guided || vtol_loiter_auto) { - plane.ahrs.get_position(plane.current_loc); + plane.ahrs.get_location(plane.current_loc); int32_t target_altitude_cm; if (!plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME,target_altitude_cm)) { break;