From 21caa8c686fdb00f25ec340316fd2fb0cfddc82d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 21 Jan 2022 10:42:41 +1100 Subject: [PATCH] GCS_MAVLink: rename AP_AHRS::get_position to get_location --- libraries/GCS_MAVLink/GCS_Common.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index e0631cae0a..fd691cc071 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -2765,7 +2765,7 @@ void GCS_MAVLINK::send_vfr_hud() AP_AHRS &ahrs = AP::ahrs(); // return values ignored; we send stale data - UNUSED_RESULT(ahrs.get_position(global_position_current_loc)); + UNUSED_RESULT(ahrs.get_location(global_position_current_loc)); mavlink_msg_vfr_hud_send( chan, @@ -4900,7 +4900,7 @@ void GCS_MAVLINK::send_global_position_int() { AP_AHRS &ahrs = AP::ahrs(); - UNUSED_RESULT(ahrs.get_position(global_position_current_loc)); // return value ignored; we send stale data + UNUSED_RESULT(ahrs.get_location(global_position_current_loc)); // return value ignored; we send stale data Vector3f vel; if (!ahrs.get_velocity_NED(vel)) { @@ -4997,7 +4997,7 @@ void GCS_MAVLINK::send_water_depth() const // get position const AP_AHRS &ahrs = AP::ahrs(); Location loc; - IGNORE_RETURN(ahrs.get_position(loc)); + IGNORE_RETURN(ahrs.get_location(loc)); for (uint8_t i=0; inum_sensors(); i++) { const AP_RangeFinder_Backend *s = rangefinder->get_backend(i); @@ -5917,7 +5917,7 @@ void GCS_MAVLINK::send_high_latency2() const { AP_AHRS &ahrs = AP::ahrs(); Location global_position_current; - UNUSED_RESULT(ahrs.get_position(global_position_current)); + UNUSED_RESULT(ahrs.get_location(global_position_current)); #if !defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY) const int8_t battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE); #endif