From 88840eb7591656c56609eecea818a0aa5853507e Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sat, 9 Feb 2013 10:11:26 +0800 Subject: [PATCH] Send FS state to gcs for AP --- ArduPlane/GCS_Mavlink.pde | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index d30052c608..675a418609 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/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