From 240a9ccaf098fe53c3da2fb93507ba4070ff9b6a Mon Sep 17 00:00:00 2001 From: Kevin Hester Date: Fri, 6 Sep 2013 15:55:24 -1000 Subject: [PATCH] AC: if vehicle is !flying show hb state as MAV_STATE_STANDBY This helps GCSes determine the appropriate UI for the current vehicle mode. --- ArduCopter/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 53968b75bb..80e8c0d0f9 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -44,7 +44,7 @@ static void gcs_send_deferred(void) 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; + uint8_t system_status = ap.land_complete ? MAV_STATE_STANDBY : MAV_STATE_ACTIVE; uint32_t custom_mode = control_mode; if (ap.failsafe_radio == true) {