From 7fa0b75d482d26744ee3f4a185b08f6eba660fbb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Feb 2023 09:58:38 +1100 Subject: [PATCH] AP_AHRS: 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 --- libraries/AP_AHRS/AP_AHRS.cpp | 4 ++-- libraries/AP_AHRS/AP_AHRS.h | 8 ++++---- libraries/AP_AHRS/AP_AHRS_Backend.h | 6 +++--- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 2 +- libraries/AP_AHRS/AP_AHRS_DCM.h | 2 +- libraries/AP_AHRS/AP_AHRS_Logging.cpp | 2 +- libraries/AP_AHRS/AP_AHRS_SIM.cpp | 2 +- libraries/AP_AHRS/AP_AHRS_SIM.h | 2 +- libraries/AP_AHRS/AP_AHRS_View.h | 2 +- 9 files changed, 15 insertions(+), 15 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index e1b5719385..4c8d6b2346 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -681,7 +681,7 @@ void AP_AHRS::reset() } // dead-reckoning support -bool AP_AHRS::get_location(struct Location &loc) const +bool AP_AHRS::get_location(Location &loc) const { switch (active_EKF_type()) { case EKFType::NONE: @@ -1158,7 +1158,7 @@ bool AP_AHRS::get_secondary_quaternion(Quaternion &quat) const } // return secondary position solution if available -bool AP_AHRS::get_secondary_position(struct Location &loc) const +bool AP_AHRS::get_secondary_position(Location &loc) const { EKFType secondary_ekf_type; if (!get_secondary_EKF_type(secondary_ekf_type)) { diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 8244fcbb43..f38e7056d9 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -89,7 +89,7 @@ public: void reset(); // dead-reckoning support - bool get_location(struct Location &loc) const; + bool get_location(Location &loc) const; // get latest altitude estimate above ground level in meters and validity flag bool get_hagl(float &hagl) const WARN_IF_UNUSED; @@ -174,7 +174,7 @@ public: bool get_secondary_quaternion(Quaternion &quat) const; // return secondary position solution if available - bool get_secondary_position(struct Location &loc) const; + bool get_secondary_position(Location &loc) const; // EKF has a better ground speed vector estimate Vector2f groundspeed_vector(); @@ -433,7 +433,7 @@ public: // get the home location. This is const to prevent any changes to // home without telling AHRS about the change - const struct Location &get_home(void) const { + const Location &get_home(void) const { return _home; } @@ -718,7 +718,7 @@ private: */ void load_watchdog_home(); bool _checked_watchdog_home; - struct Location _home; + Location _home; bool _home_is_set :1; bool _home_locked :1; diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index 3314787f5e..f5fe9c041b 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -111,7 +111,7 @@ public: // get our current position estimate. Return true if a position is available, // otherwise false. This call fills in lat, lng and alt - virtual bool get_location(struct Location &loc) const WARN_IF_UNUSED = 0; + virtual bool get_location(Location &loc) const WARN_IF_UNUSED = 0; // get latest altitude estimate above ground level in meters and validity flag virtual bool get_hagl(float &height) const WARN_IF_UNUSED { return false; } @@ -193,10 +193,10 @@ public: } // - virtual bool set_origin(const struct Location &loc) { + virtual bool set_origin(const Location &loc) { return false; } - virtual bool get_origin(struct Location &ret) const = 0; + virtual bool get_origin(Location &ret) const = 0; // return a position relative to origin in meters, North/East/Down // order. This will only be accurate if have_inertial_nav() is diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 0110650e72..5e053688ee 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -1022,7 +1022,7 @@ void AP_AHRS_DCM::estimate_wind(void) // return our current position estimate using // dead-reckoning or GPS -bool AP_AHRS_DCM::get_location(struct Location &loc) const +bool AP_AHRS_DCM::get_location(Location &loc) const { loc.lat = _last_lat; loc.lng = _last_lng; diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 15dbfec327..800e7b681c 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -61,7 +61,7 @@ public: } // dead-reckoning support - virtual bool get_location(struct Location &loc) const override; + virtual bool get_location(Location &loc) const override; // status reporting float get_error_rp() const { diff --git a/libraries/AP_AHRS/AP_AHRS_Logging.cpp b/libraries/AP_AHRS/AP_AHRS_Logging.cpp index de9262f055..62d7a3f451 100644 --- a/libraries/AP_AHRS/AP_AHRS_Logging.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Logging.cpp @@ -9,7 +9,7 @@ void AP_AHRS::Write_AHRS2() const { Vector3f euler; - struct Location loc; + Location loc; Quaternion quat; if (!get_secondary_attitude(euler) || !get_secondary_position(loc) || !get_secondary_quaternion(quat)) { return; diff --git a/libraries/AP_AHRS/AP_AHRS_SIM.cpp b/libraries/AP_AHRS/AP_AHRS_SIM.cpp index a14b251911..0714d15435 100644 --- a/libraries/AP_AHRS/AP_AHRS_SIM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_SIM.cpp @@ -4,7 +4,7 @@ #include "AP_AHRS.h" -bool AP_AHRS_SIM::get_location(struct Location &loc) const +bool AP_AHRS_SIM::get_location(Location &loc) const { if (_sitl == nullptr) { return false; diff --git a/libraries/AP_AHRS/AP_AHRS_SIM.h b/libraries/AP_AHRS/AP_AHRS_SIM.h index 037ac789a9..3caf1051b0 100644 --- a/libraries/AP_AHRS/AP_AHRS_SIM.h +++ b/libraries/AP_AHRS/AP_AHRS_SIM.h @@ -61,7 +61,7 @@ public: void reset() override { return; } // dead-reckoning support - virtual bool get_location(struct Location &loc) const override; + virtual bool get_location(Location &loc) const override; // get latest altitude estimate above ground level in meters and validity flag bool get_hagl(float &hagl) const override WARN_IF_UNUSED; diff --git a/libraries/AP_AHRS/AP_AHRS_View.h b/libraries/AP_AHRS/AP_AHRS_View.h index 109cbd1781..1ad748062f 100644 --- a/libraries/AP_AHRS/AP_AHRS_View.h +++ b/libraries/AP_AHRS/AP_AHRS_View.h @@ -85,7 +85,7 @@ public: wrappers around ahrs functions which pass-thru directly. See AP_AHRS.h for description of each function */ - bool get_location(struct Location &loc) const WARN_IF_UNUSED { + bool get_location(Location &loc) const WARN_IF_UNUSED { return ahrs.get_location(loc); }