mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF: added rejecting_airspeed flag in EKF status
This commit is contained in:
parent
7643c5d3f3
commit
a6142fa3dd
@ -38,6 +38,7 @@ union nav_filter_status {
|
||||
bool gps_glitching : 1; // 14 - true if GPS glitching is affecting navigation accuracy
|
||||
bool gps_quality_good : 1; // 15 - true if we can use GPS for navigation
|
||||
bool initalized : 1; // 16 - true if the EKF has ever been healthy
|
||||
bool rejecting_airspeed : 1; // 17 - true if we are rejecting airspeed data
|
||||
} flags;
|
||||
uint32_t value;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user