mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-12 10:53:59 -04:00
AP_NavEKF2: Update publishing of primary core index
Changes made in response to review comments
This commit is contained in:
parent
1858da8307
commit
2dcaeb0304
@ -526,14 +526,13 @@ bool NavEKF2::healthy(void) const
|
|||||||
}
|
}
|
||||||
|
|
||||||
// returns the index of the primary core
|
// returns the index of the primary core
|
||||||
// return false if no primary core selected
|
// return -1 if no primary core selected
|
||||||
bool NavEKF2::getPrimaryCoreIndex(uint8_t index) const
|
int8_t NavEKF2::getPrimaryCoreIndex(void) const
|
||||||
{
|
{
|
||||||
if (!core) {
|
if (!core) {
|
||||||
return false;
|
return -1;
|
||||||
}
|
}
|
||||||
index = primary;
|
return primary;
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -58,8 +58,8 @@ public:
|
|||||||
bool healthy(void) const;
|
bool healthy(void) const;
|
||||||
|
|
||||||
// returns the index of the primary core
|
// returns the index of the primary core
|
||||||
// return false if no primary core selected
|
// return -1 if no primary core selected
|
||||||
bool getPrimaryCoreIndex(uint8_t index) const;
|
int8_t getPrimaryCoreIndex(void) const;
|
||||||
|
|
||||||
// Return the last calculated NED position relative to the reference point (m).
|
// 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 a calculated solution is not available, use the best available data and return false
|
||||||
|
Loading…
Reference in New Issue
Block a user