mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 02:04:00 -04:00
AP_NavEKF2: remove combined NED local position interface
This commit is contained in:
parent
e374ec634d
commit
b1717649b1
@ -673,19 +673,6 @@ int8_t NavEKF2::getPrimaryCoreIndex(void) const
|
|||||||
return primary;
|
return primary;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Return the last calculated NED position relative to the reference point (m).
|
|
||||||
// If a calculated solution is not available, use the best available data and return false
|
|
||||||
// If false returned, do not use for flight control
|
|
||||||
bool NavEKF2::getPosNED(int8_t instance, Vector3f &pos)
|
|
||||||
{
|
|
||||||
if (instance < 0 || instance >= num_cores) instance = primary;
|
|
||||||
if (!core) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return core[instance].getPosNED(pos);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Return the last calculated NE position relative to the reference point (m).
|
// Return the last calculated NE position relative to the reference point (m).
|
||||||
// If a calculated solution is not available, use the best available data and return false
|
// If a calculated solution is not available, use the best available data and return false
|
||||||
// If false returned, do not use for flight control
|
// If false returned, do not use for flight control
|
||||||
|
@ -62,12 +62,6 @@ public:
|
|||||||
// return -1 if no primary core selected
|
// return -1 if no primary core selected
|
||||||
int8_t getPrimaryCoreIndex(void) const;
|
int8_t getPrimaryCoreIndex(void) const;
|
||||||
|
|
||||||
// Return the last calculated NED position relative to the reference point (m) for the specified instance.
|
|
||||||
// An out of range instance (eg -1) returns data for the the primary instance
|
|
||||||
// If a calculated solution is not available, use the best available data and return false
|
|
||||||
// If false returned, do not use for flight control
|
|
||||||
bool getPosNED(int8_t instance, Vector3f &pos);
|
|
||||||
|
|
||||||
// Return the last calculated NE position relative to the reference point (m) for the specified instance.
|
// Return the last calculated NE position relative to the reference point (m) for the specified instance.
|
||||||
// An out of range instance (eg -1) returns data for the the primary instance
|
// An out of range instance (eg -1) returns data for the the primary instance
|
||||||
// If a calculated solution is not available, use the best available data and return false
|
// If a calculated solution is not available, use the best available data and return false
|
||||||
|
@ -209,46 +209,6 @@ void NavEKF2_core::getAccelZBias(float &zbias) const {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return the last calculated NED position relative to the reference point (m).
|
|
||||||
// if a calculated solution is not available, use the best available data and return false
|
|
||||||
bool NavEKF2_core::getPosNED(Vector3f &pos) const
|
|
||||||
{
|
|
||||||
// The EKF always has a height estimate regardless of mode of operation
|
|
||||||
pos.z = outputDataNew.position.z;
|
|
||||||
// There are three modes of operation, absolute position (GPS fusion), relative position (optical flow fusion) and constant position (no position estimate available)
|
|
||||||
nav_filter_status status;
|
|
||||||
getFilterStatus(status);
|
|
||||||
if (PV_AidingMode != AID_NONE) {
|
|
||||||
// This is the normal mode of operation where we can use the EKF position states
|
|
||||||
pos.x = outputDataNew.position.x;
|
|
||||||
pos.y = outputDataNew.position.y;
|
|
||||||
return true;
|
|
||||||
} else {
|
|
||||||
// In constant position mode the EKF position states are at the origin, so we cannot use them as a position estimate
|
|
||||||
if(validOrigin) {
|
|
||||||
if ((_ahrs->get_gps().status() >= AP_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 = _ahrs->get_gps().location();
|
|
||||||
Vector2f tempPosNE = location_diff(EKF_origin, gpsloc);
|
|
||||||
pos.x = tempPosNE.x;
|
|
||||||
pos.y = tempPosNE.y;
|
|
||||||
return false;
|
|
||||||
} else {
|
|
||||||
// If no GPS fix is available, all we can do is provide the last known position
|
|
||||||
pos.x = outputDataNew.position.x;
|
|
||||||
pos.y = outputDataNew.position.y;
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
// If the origin has not been set, then we have no means of providing a relative position
|
|
||||||
pos.x = 0.0f;
|
|
||||||
pos.y = 0.0f;
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Return the last estimated NE position relative to the reference point (m).
|
// Return the last estimated NE position relative to the reference point (m).
|
||||||
// Return true if the estimate is valid
|
// Return true if the estimate is valid
|
||||||
bool NavEKF2_core::getPosNE(Vector2f &posNE) const
|
bool NavEKF2_core::getPosNE(Vector2f &posNE) const
|
||||||
|
@ -66,11 +66,6 @@ public:
|
|||||||
// Intended to be used by the front-end to determine which is the primary EKF
|
// Intended to be used by the front-end to determine which is the primary EKF
|
||||||
float faultScore(void) const;
|
float faultScore(void) const;
|
||||||
|
|
||||||
// Return the last calculated NED position relative to the reference point (m).
|
|
||||||
// If a calculated solution is not available, use the best available data and return false
|
|
||||||
// If false returned, do not use for flight control
|
|
||||||
bool getPosNED(Vector3f &pos) const;
|
|
||||||
|
|
||||||
// Return the last calculated NE position relative to the reference point (m).
|
// Return the last calculated NE position relative to the reference point (m).
|
||||||
// If a calculated solution is not available, use the best available data and return false
|
// If a calculated solution is not available, use the best available data and return false
|
||||||
// If false returned, do not use for flight control
|
// If false returned, do not use for flight control
|
||||||
|
Loading…
Reference in New Issue
Block a user