Browse Source

AP_NavEKF: make health() API const

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
66dbaa6657
  1. 2
      libraries/AP_NavEKF/AP_NavEKF.cpp
  2. 2
      libraries/AP_NavEKF/AP_NavEKF.h

2
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -68,7 +68,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) : @@ -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;

2
libraries/AP_NavEKF/AP_NavEKF.h

@ -78,7 +78,7 @@ public: @@ -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;

Loading…
Cancel
Save