diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp
index 0c0514853e23398c12e89e6a34970302fbda76d0..529bed0bf9c1e0e29dc3620ed07b21a7b1b540e0 100644
--- a/libraries/AP_NavEKF/AP_NavEKF.cpp
+++ b/libraries/AP_NavEKF/AP_NavEKF.cpp
@@ -4503,6 +4503,8 @@ void  NavEKF::getFilterStatus(nav_filter_status &status) const
     status.flags.vert_pos = !hgtTimeout;            // vertical position estimate valid
     status.flags.terrain_alt = gndOffsetValid;		// terrain height estimate valid
     status.flags.const_pos_mode = constPosMode;     // constant position mode
+    status.flags.pred_horiz_pos_rel = status.flags.horiz_pos_rel;
+    status.flags.pred_horiz_pos_abs = status.flags.horiz_pos_abs;
 }
 
 // Check arm status and perform required checks and mode changes
diff --git a/libraries/AP_NavEKF/AP_Nav_Common.h b/libraries/AP_NavEKF/AP_Nav_Common.h
index 06bcae194c3d00193a1b90597fb2e7472c50ce34..015bdbd8188258ebd89258c41b15d3a9c040b238 100644
--- a/libraries/AP_NavEKF/AP_Nav_Common.h
+++ b/libraries/AP_NavEKF/AP_Nav_Common.h
@@ -21,16 +21,18 @@
 
 union nav_filter_status {
     struct {
-        uint8_t attitude        : 1; // 0 - true if attitude estimate is valid
-        uint8_t horiz_vel       : 1; // 1 - true if horizontal velocity estimate is valid
-        uint8_t vert_vel        : 1; // 2 - true if the vertical velocity estimate is valid
-        uint8_t horiz_pos_rel   : 1; // 3 - true if the relative horizontal position estimate is valid
-        uint8_t horiz_pos_abs   : 1; // 4 - true if the absolute horizontal position estimate is valid
-        uint8_t vert_pos        : 1; // 5 - true if the vertical position estimate is valid
-        uint8_t terrain_alt     : 1; // 6 - true if the terrain height estimate is valid
-        uint8_t const_pos_mode  : 1; // 7 - true if we are in const position mode
+        uint16_t attitude           : 1; // 0 - true if attitude estimate is valid
+        uint16_t horiz_vel          : 1; // 1 - true if horizontal velocity estimate is valid
+        uint16_t vert_vel           : 1; // 2 - true if the vertical velocity estimate is valid
+        uint16_t horiz_pos_rel      : 1; // 3 - true if the relative horizontal position estimate is valid
+        uint16_t horiz_pos_abs      : 1; // 4 - true if the absolute horizontal position estimate is valid
+        uint16_t vert_pos           : 1; // 5 - true if the vertical position estimate is valid
+        uint16_t terrain_alt        : 1; // 6 - true if the terrain height estimate is valid
+        uint16_t const_pos_mode     : 1; // 7 - true if we are in const position mode
+        uint16_t pred_horiz_pos_rel : 1; // 8 - true if filter expects it can produce a good relative horizontal position estimate - used before takeoff
+        uint16_t pred_horiz_pos_abs : 1; // 9 - true if filter expects it can produce a good absolute horizontal position estimate - used before takeoff
     } flags;
-    uint8_t value;
+    uint16_t value;
 };
 
 #endif // AP_Nav_Common