From 204abfd45e71d7e0eb9971d1f21d45036015484d Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 7 Jun 2016 17:13:10 -0700 Subject: [PATCH] Plane: set heartbeat.system_status to Critical for low-battery failsafe events --- ArduPlane/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 3621c465fe..c7860ee6bf 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -14,7 +14,7 @@ void Plane::send_heartbeat(mavlink_channel_t chan) uint8_t system_status; uint32_t custom_mode = control_mode; - if (failsafe.state != FAILSAFE_NONE) { + if (failsafe.state != FAILSAFE_NONE || failsafe.low_battery) { system_status = MAV_STATE_CRITICAL; } else if (plane.crash_state.is_crashed) { system_status = MAV_STATE_EMERGENCY;