AP_NavEKF: make health() API const

This commit is contained in:
Andrew Tridgell 2014-01-04 11:16:19 +11:00
parent 47f541e143
commit 66dbaa6657
2 changed files with 2 additions and 2 deletions

View File

@ -68,7 +68,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
dtIMUAvgInv = 1.0f/dtIMUAvg;
}
bool NavEKF::healthy(void)
bool NavEKF::healthy(void) const
{
if (!statesInitialised) {
return false;

View File

@ -78,7 +78,7 @@ public:
void UpdateFilter(void);
// return true if the filter is healthy
bool healthy(void);
bool healthy(void) const;
// fill in latitude, longitude and height of the reference point
void getRefLLH(struct Location &loc) const;