diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 954f90031c..dc07f03c2d 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -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; diff --git a/libraries/AP_NavEKF/AP_NavEKF.h b/libraries/AP_NavEKF/AP_NavEKF.h index ca8ee517fa..45cec5ec7a 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.h +++ b/libraries/AP_NavEKF/AP_NavEKF.h @@ -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;