diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 0dc939613f..92fb259556 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -259,7 +259,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) int16_t battery_current = -1; int8_t battery_remaining = -1; - if (battery.has_current()) { + if (battery.has_current() && battery.healthy()) { battery_remaining = battery.capacity_remaining_pct(); battery_current = battery.current_amps() * 100; }