diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 806f029bfe..d2daee3af0 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -261,10 +261,6 @@ bool GCS_MAVLINK_Copter::vehicle_initialised() const { // try to send a message, return false if it wasn't sent bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) { - if (telemetry_delayed()) { - return false; - } - #if HIL_MODE != HIL_MODE_SENSORS // if we don't have at least 250 micros remaining before the main loop // wants to fire then don't send a mavlink message. We want to