mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: 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
This commit is contained in:
parent
03f5c321b0
commit
38c6eb24cd
|
@ -1070,7 +1070,7 @@ bool NavEKF2::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 NavEKF2::getLLH(struct Location &loc) const
|
||||
bool NavEKF2::getLLH(Location &loc) const
|
||||
{
|
||||
if (!core) {
|
||||
return false;
|
||||
|
@ -1082,7 +1082,7 @@ bool NavEKF2::getLLH(struct Location &loc) const
|
|||
// An out of range instance (eg -1) returns data for the primary instance
|
||||
// All NED positions calculated by the filter are relative to this location
|
||||
// Returns false if the origin has not been set
|
||||
bool NavEKF2::getOriginLLH(struct Location &loc) const
|
||||
bool NavEKF2::getOriginLLH(Location &loc) const
|
||||
{
|
||||
if (!core) {
|
||||
return false;
|
||||
|
|
|
@ -129,13 +129,13 @@ 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 for the specified instance
|
||||
// An out of range instance (eg -1) returns data for the primary instance
|
||||
// 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
|
||||
|
@ -399,7 +399,7 @@ private:
|
|||
const float maxYawEstVelInnov = 2.0f; // Maximum acceptable length of the velocity innovation returned by the EKF-GSF yaw estimator (m/s)
|
||||
|
||||
// origin set by one of the cores
|
||||
struct Location common_EKF_origin;
|
||||
Location common_EKF_origin;
|
||||
bool common_origin_valid;
|
||||
|
||||
// time at start of current filter update
|
||||
|
|
|
@ -594,7 +594,7 @@ void NavEKF2_core::readGpsData()
|
|||
}
|
||||
|
||||
// Read the GPS location in WGS-84 lat,long,height coordinates
|
||||
const struct Location &gpsloc = gps.location();
|
||||
const Location &gpsloc = gps.location();
|
||||
|
||||
// Set the EKF origin and magnetic field declination if not previously set and GPS checks have passed
|
||||
if (gpsGoodToAlign && !validOrigin) {
|
||||
|
|
|
@ -220,7 +220,7 @@ bool NavEKF2_core::getPosNE(Vector2f &posNE) const
|
|||
if(validOrigin) {
|
||||
if ((dal.gps().status(dal.gps().primary_sensor()) >= 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 = dal.gps().location();
|
||||
const Location &gpsloc = dal.gps().location();
|
||||
const Vector2F tempPosNE = EKF_origin.get_distance_NE_ftype(gpsloc);
|
||||
posNE.x = tempPosNE.x;
|
||||
posNE.y = tempPosNE.y;
|
||||
|
@ -280,7 +280,7 @@ bool NavEKF2_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 NavEKF2_core::getLLH(struct Location &loc) const
|
||||
bool NavEKF2_core::getLLH(Location &loc) const
|
||||
{
|
||||
const auto &gps = dal.gps();
|
||||
Location origin;
|
||||
|
@ -302,7 +302,7 @@ bool NavEKF2_core::getLLH(struct Location &loc) const
|
|||
// in this mode we cannot use the EKF states to estimate position so will return the best available data
|
||||
if ((gps.status() >= AP_DAL_GPS::GPS_OK_FIX_2D)) {
|
||||
// we have a GPS position fix to return
|
||||
const struct Location &gpsloc = gps.location();
|
||||
const Location &gpsloc = gps.location();
|
||||
loc.lat = gpsloc.lat;
|
||||
loc.lng = gpsloc.lng;
|
||||
return true;
|
||||
|
@ -347,7 +347,7 @@ void NavEKF2_core::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGa
|
|||
|
||||
|
||||
// return the LLH location of the filters NED origin
|
||||
bool NavEKF2_core::getOriginLLH(struct Location &loc) const
|
||||
bool NavEKF2_core::getOriginLLH(Location &loc) const
|
||||
{
|
||||
if (validOrigin) {
|
||||
loc = EKF_origin;
|
||||
|
|
|
@ -52,7 +52,7 @@ void NavEKF2_core::calcGpsGoodToAlign(void)
|
|||
|
||||
// Check for significant change in GPS position if disarmed which indicates bad GPS
|
||||
// This check can only be used when the vehicle is stationary
|
||||
const struct Location &gpsloc = gps.location(); // Current location
|
||||
const Location &gpsloc = gps.location(); // Current location
|
||||
const ftype posFiltTimeConst = 10.0f; // time constant used to decay position drift
|
||||
// calculate time lapsed since last update and limit to prevent numerical errors
|
||||
ftype deltaTime = constrain_ftype(float(imuDataDelayed.time_ms - lastPreAlignGpsCheckTime_ms)*0.001f,0.01f,posFiltTimeConst);
|
||||
|
|
|
@ -164,12 +164,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
|
||||
|
@ -861,7 +861,7 @@ private:
|
|||
bool needMagBodyVarReset; // we need to reset mag body variances at next CovariancePrediction
|
||||
bool gpsNotAvailable; // bool true when valid GPS data is not available
|
||||
uint8_t last_gps_idx; // sensor ID of the GPS receiver used for the last fusion or reset
|
||||
struct Location EKF_origin; // LLH origin of the NED axis system
|
||||
Location EKF_origin; // LLH origin of the NED axis system
|
||||
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
|
||||
|
@ -948,7 +948,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 filterred vertical GPS velocity detected durng pre-flight GPS checks
|
||||
|
|
Loading…
Reference in New Issue