From 7810314f7ca5edbe2693b621c40421dbb94efb44 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 27 Jul 2014 21:14:32 +1000 Subject: [PATCH] Rover: avoid integer underflow in mavlink txspace check --- APMrover2/GCS_Mavlink.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index b0f1dc674c..22e8a62c17 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -10,7 +10,7 @@ static bool in_mavlink_delay; static bool gcs_out_of_time; // check if a message will fit in the payload space available -#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false +#define CHECK_PAYLOAD_SIZE(id) if (txspace < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_## id ##_LEN) return false /* * !!NOTE!! @@ -377,7 +377,7 @@ static bool telemetry_delayed(mavlink_channel_t chan) // try to send a message, return false if it won't fit in the serial tx buffer bool GCS_MAVLINK::try_send_message(enum ap_message id) { - int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES; + uint16_t txspace = comm_get_txspace(chan); if (telemetry_delayed(chan)) { return false;