From 3d8588a636a681dc38936bbe336e68f2f56d9078 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 4 Dec 2018 16:08:09 +1100 Subject: [PATCH] Copter: send both SYS_STATUS or POWER_STATUS or neither --- ArduCopter/GCS_Mavlink.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 3b7dedc9a3..eece97f614 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -277,9 +277,11 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) // send extended status only once vehicle has been initialised // to avoid unnecessary errors being reported to user if (copter.ap.initialised) { - CHECK_PAYLOAD_SIZE(SYS_STATUS); + if (PAYLOAD_SIZE(chan, SYS_STATUS) + + PAYLOAD_SIZE(chan, POWER_STATUS) > comm_get_txspace(chan)) { + return false; + } copter.send_sys_status(chan); - CHECK_PAYLOAD_SIZE(POWER_STATUS); send_power_status(); } break;