mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
GCS_Common: don't attempt to shove timesync message into a full channel
This commit is contained in:
parent
6e7b9aa727
commit
1c6af7d777
@ -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.
|
||||
|
Loading…
Reference in New Issue
Block a user