Copter: try_send_message caller checks telemetry_delayed

This commit is contained in:
Peter Barker 2018-12-18 09:24:05 +11:00 committed by Peter Barker
parent 88dfb3220b
commit bfc82fb1d8
1 changed files with 0 additions and 4 deletions

View File

@ -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