From 0baee6f82b38f48912490a1611578ca23a7fdbe8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 30 May 2018 20:26:19 +1000 Subject: [PATCH] GCS_MAVLINK: avoid pushing partial RC_CHANNEL message into uart In the case we do not send RC_CHANNELS_RAW, we will not check to see if RC_CHANNELS will fit. RC_CHANNELS is larger than RC_CHANNELS_RAW, so the check in the caller is insufficient. --- libraries/GCS_MAVLink/GCS_Common.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 4e2cf5a9bd..c2027bd50f 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1014,10 +1014,10 @@ void GCS_MAVLINK::send_radio_in() values[6], values[7], receiver_rssi); - if (!HAVE_PAYLOAD_SPACE(chan, RC_CHANNELS)) { - // can't fit RC_CHANNELS - return; - } + } + if (!HAVE_PAYLOAD_SPACE(chan, RC_CHANNELS)) { + // can't fit RC_CHANNELS + return; } mavlink_msg_rc_channels_send( chan,