diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index a3c5a02a36..0241b80dd0 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -758,7 +758,7 @@ bool NavEKF2::InitialiseFilter(void) return true if a new core index has a better score than the current core */ -bool NavEKF2::coreBetterScore(uint8_t new_core, uint8_t current_core) +bool NavEKF2::coreBetterScore(uint8_t new_core, uint8_t current_core) const { const NavEKF2_core &oldCore = core[current_core]; const NavEKF2_core &newCore = core[new_core]; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index ee8e13f711..a0c243397d 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -555,7 +555,7 @@ private: // return true if a new core has a better score than an existing core, including // checks for alignment - bool coreBetterScore(uint8_t new_core, uint8_t current_core); + bool coreBetterScore(uint8_t new_core, uint8_t current_core) const; // logging functions shared by cores: void Log_Write_NKF1(uint8_t core, uint64_t time_us) const;