diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde
index b7e66c9ba6..d0dd0961dd 100644
--- a/APMrover2/GCS_Mavlink.pde
+++ b/APMrover2/GCS_Mavlink.pde
@@ -27,6 +27,10 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
     uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
     uint8_t system_status = MAV_STATE_ACTIVE;
     uint32_t custom_mode = control_mode;
+    
+    if (failsafe != FAILSAFE_NONE) {
+        system_status = MAV_STATE_CRITICAL;
+    }
 
     // work out the base_mode. This value is not very useful
     // for APM, but we calculate it as best we can so a generic