mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_NavEKF: make health() API const
This commit is contained in:
parent
47f541e143
commit
66dbaa6657
@ -68,7 +68,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
|
|||||||
dtIMUAvgInv = 1.0f/dtIMUAvg;
|
dtIMUAvgInv = 1.0f/dtIMUAvg;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool NavEKF::healthy(void)
|
bool NavEKF::healthy(void) const
|
||||||
{
|
{
|
||||||
if (!statesInitialised) {
|
if (!statesInitialised) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -78,7 +78,7 @@ public:
|
|||||||
void UpdateFilter(void);
|
void UpdateFilter(void);
|
||||||
|
|
||||||
// return true if the filter is healthy
|
// return true if the filter is healthy
|
||||||
bool healthy(void);
|
bool healthy(void) const;
|
||||||
|
|
||||||
// fill in latitude, longitude and height of the reference point
|
// fill in latitude, longitude and height of the reference point
|
||||||
void getRefLLH(struct Location &loc) const;
|
void getRefLLH(struct Location &loc) const;
|
||||||
|
Loading…
Reference in New Issue
Block a user