From f0e17957f479dbd16e3ad409877f9ab4435f19e0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Feb 2023 09:58:40 +1100 Subject: [PATCH] ArduPlane: avoid using struct Location clang reports this could be a problem when compiling under some EABIs. Remove it from most places as it is just noise, replace with class where we want to avoid including Location.h --- ArduPlane/GCS_Mavlink.cpp | 2 +- ArduPlane/Plane.h | 6 +++--- ArduPlane/commands.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 4c5b3f6983..806bb12947 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1383,7 +1383,7 @@ uint64_t GCS_MAVLINK_Plane::capabilities() const int16_t GCS_MAVLINK_Plane::high_latency_target_altitude() const { AP_AHRS &ahrs = AP::ahrs(); - struct Location global_position_current; + Location global_position_current; UNUSED_RESULT(ahrs.get_location(global_position_current)); #if HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index e8409f15fd..ca7a8d407e 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -705,13 +705,13 @@ private: // 3D Location vectors // Location structure defined in AP_Common - const struct Location &home = ahrs.get_home(); + const Location &home = ahrs.get_home(); // The location of the previous waypoint. Used for track following and altitude ramp calculations Location prev_WP_loc {}; // The plane's current location - struct Location current_loc {}; + Location current_loc {}; // The location of the current/active waypoint. Used for altitude ramp, track following and loiter calculations. Location next_WP_loc {}; @@ -889,7 +889,7 @@ private: void load_parameters(void) override; // commands_logic.cpp - void set_next_WP(const struct Location &loc); + void set_next_WP(const Location &loc); void do_RTL(int32_t alt); bool verify_takeoff(); bool verify_loiter_unlim(const AP_Mission::Mission_Command &cmd); diff --git a/ArduPlane/commands.cpp b/ArduPlane/commands.cpp index bf1cffba14..e899dbbd63 100644 --- a/ArduPlane/commands.cpp +++ b/ArduPlane/commands.cpp @@ -7,7 +7,7 @@ /* * set_next_WP - sets the target location the vehicle should fly to */ -void Plane::set_next_WP(const struct Location &loc) +void Plane::set_next_WP(const Location &loc) { if (auto_state.next_wp_crosstrack) { // copy the current WP into the OldWP slot