Rover: try_send_message caller checks telemetry_delayed

This commit is contained in:
Peter Barker 2018-12-18 09:24:00 +11:00 committed by Peter Barker
parent f8863971a2
commit 88dfb3220b

View File

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