From 88dfb3220bd09ec241131f8deec80533e1e933bd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 18 Dec 2018 09:24:00 +1100 Subject: [PATCH] Rover: try_send_message caller checks telemetry_delayed --- APMrover2/GCS_Mavlink.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 716cdcd0af..9ac55f454f 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -309,10 +309,6 @@ bool GCS_MAVLINK_Rover::vehicle_initialised() const // try to send a message, return false if it won't fit in the serial tx buffer bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) { - if (telemetry_delayed()) { - return false; - } - // if we don't have at least 0.2ms remaining before the main loop // wants to fire then don't send a mavlink message. We want to // prioritise the main flight control loop over communications