AP_NavEKF2: Publish the primary EKF index

This commit is contained in:
Paul Riseborough 2015-11-06 12:13:43 +11:00 committed by Andrew Tridgell
parent 04165a60a7
commit b24507d33c
2 changed files with 16 additions and 0 deletions

View File

@ -517,6 +517,18 @@ bool NavEKF2::healthy(void) const
return core[primary].healthy();
}
// returns the index of the primary core
// return false if no primary core selected
bool NavEKF2::getPrimaryCoreIndex(uint8_t index) const
{
if (!core) {
return false;
}
index = primary;
return true;
}
// 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

View File

@ -57,6 +57,10 @@ public:
// Check basic filter health metrics and return a consolidated health status
bool healthy(void) const;
// returns the index of the primary core
// return false if no primary core selected
bool getPrimaryCoreIndex(uint8_t index) 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