From ea2de1c11a5323c6b0ef08751b31df89910512ed Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 26 Apr 2019 17:13:52 +1000 Subject: [PATCH] Rover: allow GCS MAVLink base class to handle out-of-time for sending messages --- APMrover2/GCS_Mavlink.cpp | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 169133fba3..6ee7a4ec08 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -315,16 +315,6 @@ bool GCS_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 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 - if (!hal.scheduler->in_delay_callback() && - !AP_BoardConfig::in_sensor_config_error() && - rover.scheduler.time_available_usec() < 200) { - gcs().set_out_of_time(true); - return false; - } - switch (id) { case MSG_SERVO_OUT: