GCS_Common: don't attempt to shove timesync message into a full channel

This commit is contained in:
Peter Barker 2018-12-07 12:48:07 +11:00 committed by Andrew Tridgell
parent 6e7b9aa727
commit 1c6af7d777

View File

@ -2514,6 +2514,11 @@ void GCS_MAVLINK::handle_timesync(mavlink_message_t *msg)
return;
}
if (!HAVE_PAYLOAD_SPACE(chan, TIMESYNC)) {
// drop this timesync request entirely
return;
}
// create new timesync struct with tc1 field as system time in
// nanoseconds. The client timestamp is as close as possible to
// the time we received the TIMESYNC message.