AP_AHRS: rename AP_AHRS::get_position to get_location

This commit is contained in:
Peter Barker 2022-01-21 10:42:40 +11:00 committed by Andrew Tridgell
parent e089f23c70
commit ff63b62b0c
7 changed files with 16 additions and 16 deletions

View File

@ -718,11 +718,11 @@ void AP_AHRS::reset()
} }
// dead-reckoning support // dead-reckoning support
bool AP_AHRS::get_position(struct Location &loc) const bool AP_AHRS::get_location(struct Location &loc) const
{ {
switch (active_EKF_type()) { switch (active_EKF_type()) {
case EKFType::NONE: case EKFType::NONE:
return dcm.get_position(loc); return dcm.get_location(loc);
#if HAL_NAVEKF2_AVAILABLE #if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO: case EKFType::TWO:
@ -763,7 +763,7 @@ bool AP_AHRS::get_position(struct Location &loc) const
// fall back to position from DCM // fall back to position from DCM
if (!always_use_EKF()) { if (!always_use_EKF()) {
return dcm.get_position(loc); return dcm.get_location(loc);
} }
return false; return false;
} }
@ -1170,7 +1170,7 @@ bool AP_AHRS::get_secondary_position(struct Location &loc) const
case EKFType::NONE: case EKFType::NONE:
// return DCM position // return DCM position
dcm.get_position(loc); dcm.get_location(loc);
return true; return true;
#if HAL_NAVEKF2_AVAILABLE #if HAL_NAVEKF2_AVAILABLE
@ -1539,7 +1539,7 @@ bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const
return false; return false;
} }
Location loc, orgn; Location loc, orgn;
if (!get_position(loc) || if (!get_location(loc) ||
!get_origin(orgn)) { !get_origin(orgn)) {
return false; return false;
} }
@ -1613,7 +1613,7 @@ bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const
#if AP_AHRS_SIM_ENABLED #if AP_AHRS_SIM_ENABLED
case EKFType::SIM: { case EKFType::SIM: {
Location loc, orgn; Location loc, orgn;
if (!get_position(loc) || if (!get_location(loc) ||
!get_origin(orgn)) { !get_origin(orgn)) {
return false; return false;
} }
@ -1624,7 +1624,7 @@ bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const
#if HAL_EXTERNAL_AHRS_ENABLED #if HAL_EXTERNAL_AHRS_ENABLED
case EKFType::EXTERNAL: { case EKFType::EXTERNAL: {
Location loc, orgn; Location loc, orgn;
if (!get_position(loc) || if (!get_location(loc) ||
!get_origin(orgn)) { !get_origin(orgn)) {
return false; return false;
} }
@ -1698,7 +1698,7 @@ bool AP_AHRS::get_relative_position_D_origin(float &posD) const
case EKFType::EXTERNAL: { case EKFType::EXTERNAL: {
Location orgn, loc; Location orgn, loc;
if (!get_origin(orgn) || if (!get_origin(orgn) ||
!get_position(loc)) { !get_location(loc)) {
return false; return false;
} }
posD = -(loc.alt - orgn.alt)*0.01; posD = -(loc.alt - orgn.alt)*0.01;

View File

@ -105,7 +105,7 @@ public:
void reset(); void reset();
// dead-reckoning support // dead-reckoning support
bool get_position(struct Location &loc) const; bool get_location(struct Location &loc) const;
// get latest altitude estimate above ground level in meters and validity flag // get latest altitude estimate above ground level in meters and validity flag
bool get_hagl(float &hagl) const WARN_IF_UNUSED; bool get_hagl(float &hagl) const WARN_IF_UNUSED;

View File

@ -116,7 +116,7 @@ public:
// get our current position estimate. Return true if a position is available, // get our current position estimate. Return true if a position is available,
// otherwise false. This call fills in lat, lng and alt // otherwise false. This call fills in lat, lng and alt
virtual bool get_position(struct Location &loc) const WARN_IF_UNUSED = 0; virtual bool get_location(struct Location &loc) const WARN_IF_UNUSED = 0;
// get latest altitude estimate above ground level in meters and validity flag // get latest altitude estimate above ground level in meters and validity flag
virtual bool get_hagl(float &height) const WARN_IF_UNUSED { return false; } virtual bool get_hagl(float &height) const WARN_IF_UNUSED { return false; }

View File

@ -1044,7 +1044,7 @@ void AP_AHRS_DCM::estimate_wind(void)
// return our current position estimate using // return our current position estimate using
// dead-reckoning or GPS // dead-reckoning or GPS
bool AP_AHRS_DCM::get_position(struct Location &loc) const bool AP_AHRS_DCM::get_location(struct Location &loc) const
{ {
loc.lat = _last_lat; loc.lat = _last_lat;
loc.lng = _last_lng; loc.lng = _last_lng;
@ -1239,7 +1239,7 @@ bool AP_AHRS_DCM::get_relative_position_NED_origin(Vector3f &posNED) const
return false; return false;
} }
Location loc; Location loc;
if (!AP_AHRS_DCM::get_position(loc)) { if (!AP_AHRS_DCM::get_location(loc)) {
return false; return false;
} }
posNED = origin.get_distance_NED(loc); posNED = origin.get_distance_NED(loc);

View File

@ -62,7 +62,7 @@ public:
} }
// dead-reckoning support // dead-reckoning support
virtual bool get_position(struct Location &loc) const override; virtual bool get_location(struct Location &loc) const override;
// status reporting // status reporting
float get_error_rp() const { float get_error_rp() const {

View File

@ -80,7 +80,7 @@ void AP_AHRS::Write_Origin(LogOriginType origin_type, const Location &loc) const
void AP_AHRS::Write_POS() const void AP_AHRS::Write_POS() const
{ {
Location loc; Location loc;
if (!get_position(loc)) { if (!get_location(loc)) {
return; return;
} }
float home, origin; float home, origin;

View File

@ -85,8 +85,8 @@ public:
wrappers around ahrs functions which pass-thru directly. See wrappers around ahrs functions which pass-thru directly. See
AP_AHRS.h for description of each function AP_AHRS.h for description of each function
*/ */
bool get_position(struct Location &loc) const WARN_IF_UNUSED { bool get_location(struct Location &loc) const WARN_IF_UNUSED {
return ahrs.get_position(loc); return ahrs.get_location(loc);
} }
Vector3f wind_estimate(void) { Vector3f wind_estimate(void) {