diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 19a961370036..67def31e0eb5 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1225,9 +1225,14 @@ class MavlinkStreamSystemTime : public MavlinkStream msg.time_boot_ms = hrt_absolute_time() / 1000; msg.time_unix_usec = (uint64_t)tv.tv_sec * 1000000 + tv.tv_nsec / 1000; - mavlink_msg_system_time_send_struct(_mavlink->get_channel(), &msg); + // If the time is before 2001-01-01, it's probably the default 2000 + // and we don't need to bother sending it because it's definitely wrong. + if (msg.time_unix_usec > 978307200000000) { + mavlink_msg_system_time_send_struct(_mavlink->get_channel(), &msg); + return true; + } - return true; + return false; } };