mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_AHRS_NavEKF: add getGpsGlitchStatus
This commit is contained in:
parent
8ded496f8b
commit
18240107f0
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user