AP_AHRS_NavEKF: add getGpsGlitchStatus

This commit is contained in:
Jonathan Challinger 2016-01-26 13:28:21 -08:00 committed by Randy Mackay
parent 8ded496f8b
commit 18240107f0
2 changed files with 10 additions and 0 deletions

View File

@ -1258,6 +1258,14 @@ void AP_AHRS_NavEKF::setTouchdownExpected(bool val)
}
}
bool AP_AHRS_NavEKF::getGpsGlitchStatus()
{
nav_filter_status ekf_status;
get_filter_status(ekf_status);
return ekf_status.flags.gps_glitching;
}
#endif // AP_AHRS_NAVEKF_AVAILABLE

View File

@ -215,6 +215,8 @@ public:
void setTakeoffExpected(bool val);
void setTouchdownExpected(bool val);
bool getGpsGlitchStatus();
private:
enum EKF_TYPE {EKF_TYPE_NONE=0,
#if AP_AHRS_WITH_EKF1