diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 36b07d4893..8a27976882 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -434,9 +434,11 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) switch (id) { case MSG_EXTENDED_STATUS1: - CHECK_PAYLOAD_SIZE(SYS_STATUS); + if (PAYLOAD_SIZE(chan, SYS_STATUS) + + PAYLOAD_SIZE(chan, POWER_STATUS) > comm_get_txspace(chan)) { + return false; + } plane.send_sys_status(chan); - CHECK_PAYLOAD_SIZE2(POWER_STATUS); send_power_status(); break;