diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 153f6c5421..1f9f732faa 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1356,7 +1356,7 @@ bool NavEKF3::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const // If a calculated location isn't available, return a raw GPS measurement // The status will return true if a calculation or raw measurement is available // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control -bool NavEKF3::getLLH(struct Location &loc) const +bool NavEKF3::getLLH(Location &loc) const { if (!core) { return false; @@ -1367,7 +1367,7 @@ bool NavEKF3::getLLH(struct Location &loc) const // Return the latitude and longitude and height used to set the NED origin // All NED positions calculated by the filter are relative to this location // Returns false if the origin has not been set -bool NavEKF3::getOriginLLH(struct Location &loc) const +bool NavEKF3::getOriginLLH(Location &loc) const { if (!core) { return false; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index e43162f78d..9eac031ac1 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -139,12 +139,12 @@ public: // If a calculated location isn't available, return a raw GPS measurement // The status will return true if a calculation or raw measurement is available // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control - bool getLLH(struct Location &loc) const; + bool getLLH(Location &loc) const; // Return the latitude and longitude and height used to set the NED origin // All NED positions calculated by the filter are relative to this location // Returns false if the origin has not been set - bool getOriginLLH(struct Location &loc) const; + bool getOriginLLH(Location &loc) const; // set the latitude and longitude and height used to set the NED origin // All NED positions calculated by the filter will be relative to this location @@ -525,7 +525,7 @@ private: uint64_t coreLastTimePrimary_us[MAX_EKF_CORES]; // last time we were using this core as primary // origin set by one of the cores - struct Location common_EKF_origin; + Location common_EKF_origin; bool common_origin_valid; // update the yaw reset data to capture changes due to a lane switch diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index e79169015f..7df91bcf0c 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -645,7 +645,7 @@ void NavEKF3_core::readGpsData() calcGpsGoodForFlight(); // Read the GPS location in WGS-84 lat,long,height coordinates - const struct Location &gpsloc = gps.location(selected_gps); + const Location &gpsloc = gps.location(selected_gps); // Set the EKF origin and magnetic field declination if not previously set and GPS checks have passed if (gpsGoodToAlign && !validOrigin) { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp index eaec4df54e..c4240144b6 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp @@ -232,7 +232,7 @@ bool NavEKF3_core::getPosNE(Vector2f &posNE) const auto &gps = dal.gps(); if ((gps.status(selected_gps) >= AP_DAL_GPS::GPS_OK_FIX_2D)) { // If the origin has been set and we have GPS, then return the GPS position relative to the origin - const struct Location &gpsloc = gps.location(selected_gps); + const Location &gpsloc = gps.location(selected_gps); posNE = public_origin.get_distance_NE_ftype(gpsloc).tofloat(); return false; #if EK3_FEATURE_BEACON_FUSION @@ -304,7 +304,7 @@ bool NavEKF3_core::getHAGL(float &HAGL) const // If a calculated location isn't available, return a raw GPS measurement // The status will return true if a calculation or raw measurement is available // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control -bool NavEKF3_core::getLLH(struct Location &loc) const +bool NavEKF3_core::getLLH(Location &loc) const { Location origin; if (getOriginLLH(origin)) { @@ -351,7 +351,7 @@ bool NavEKF3_core::getLLH(struct Location &loc) const } } -bool NavEKF3_core::getGPSLLH(struct Location &loc) const +bool NavEKF3_core::getGPSLLH(Location &loc) const { const auto &gps = dal.gps(); if ((gps.status(selected_gps) >= AP_DAL_GPS::GPS_OK_FIX_3D)) { @@ -384,7 +384,7 @@ void NavEKF3_core::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGa // return the LLH location of the filters NED origin -bool NavEKF3_core::getOriginLLH(struct Location &loc) const +bool NavEKF3_core::getOriginLLH(Location &loc) const { if (validOrigin) { loc = public_origin; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp index 40f1b077df..47e4277361 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp @@ -48,7 +48,7 @@ void NavEKF3_core::calcGpsGoodToAlign(void) // This check can only be used when the vehicle is stationary const auto &gps = dal.gps(); - const struct Location &gpsloc = gps.location(preferred_gps); // Current location + const Location &gpsloc = gps.location(preferred_gps); // Current location const ftype posFiltTimeConst = 10.0; // time constant used to decay position drift // calculate time lapsed since last update and limit to prevent numerical errors ftype deltaTime = constrain_ftype(ftype(imuDataDelayed.time_ms - lastPreAlignGpsCheckTime_ms)*0.001f,0.01f,posFiltTimeConst); diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index 649f17c5db..ed9b4cff7e 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -209,12 +209,12 @@ public: // If a calculated location isn't available, return a raw GPS measurement // The status will return true if a calculation or raw measurement is available // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control - bool getLLH(struct Location &loc) const; + bool getLLH(Location &loc) const; // return the latitude and longitude and height used to set the NED origin // All NED positions calculated by the filter are relative to this location // Returns false if the origin has not been set - bool getOriginLLH(struct Location &loc) const; + bool getOriginLLH(Location &loc) const; // set the latitude and longitude and height used to set the NED origin // All NED positions calculated by the filter will be relative to this location @@ -1011,7 +1011,7 @@ private: void SelectDragFusion(); void SampleDragData(const imu_elements &imu); - bool getGPSLLH(struct Location &loc) const; + bool getGPSLLH(Location &loc) const; // Variables bool statesInitialised; // boolean true when filter states have been initialised @@ -1101,8 +1101,8 @@ private: bool needEarthBodyVarReset; // we need to reset mag earth variances at next CovariancePrediction bool inhibitDelAngBiasStates; // true when IMU delta angle bias states are inactive bool gpsIsInUse; // bool true when GPS data is being used to correct states estimates - struct Location EKF_origin; // LLH origin of the NED axis system, internal only - struct Location &public_origin; // LLH origin of the NED axis system, public functions + Location EKF_origin; // LLH origin of the NED axis system, internal only + Location &public_origin; // LLH origin of the NED axis system, public functions bool validOrigin; // true when the EKF origin is valid ftype gpsSpdAccuracy; // estimated speed accuracy in m/s returned by the GPS receiver ftype gpsPosAccuracy; // estimated position accuracy in m returned by the GPS receiver @@ -1194,7 +1194,7 @@ private: } vertCompFiltState; // variables used by the pre-initialisation GPS checks - struct Location gpsloc_prev; // LLH location of previous GPS measurement + Location gpsloc_prev; // LLH location of previous GPS measurement uint32_t lastPreAlignGpsCheckTime_ms; // last time in msec the GPS quality was checked during pre alignment checks ftype gpsDriftNE; // amount of drift detected in the GPS position during pre-flight GPs checks ftype gpsVertVelFilt; // amount of filtered vertical GPS velocity detected during pre-flight GPS checks