From d4cb7b8970318d136779f548fa6153eb135dd589 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 Apr 2016 14:08:24 +1000 Subject: [PATCH] AntennaTracker: use GCS_MAVLINK::packet_overhead_chan() --- AntennaTracker/GCS_Mavlink.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 4124083f73..4c36e343df 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -510,7 +510,8 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg) for (uint8_t i=0; i < num_gcs; i++) { if (gcs[i].initialised) { // request position - if (comm_get_txspace((mavlink_channel_t)i) - MAVLINK_NUM_NON_PAYLOAD_BYTES >= MAVLINK_MSG_ID_DATA_STREAM_LEN) { + if (comm_get_txspace((mavlink_channel_t)i) >= + GCS_MAVLINK::packet_overhead_chan((mavlink_channel_t)i) + MAVLINK_MSG_ID_DATA_STREAM_LEN) { mavlink_msg_request_data_stream_send( (mavlink_channel_t)i, msg->sysid, @@ -520,7 +521,8 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg) 1); // start streaming } // request air pressure - if (comm_get_txspace((mavlink_channel_t)i) - MAVLINK_NUM_NON_PAYLOAD_BYTES >= MAVLINK_MSG_ID_DATA_STREAM_LEN) { + if (comm_get_txspace((mavlink_channel_t)i) >= + GCS_MAVLINK::packet_overhead_chan((mavlink_channel_t)i) + MAVLINK_MSG_ID_DATA_STREAM_LEN) { mavlink_msg_request_data_stream_send( (mavlink_channel_t)i, msg->sysid,