mavlink: set system clock from SYSTEM_TIME (#24807)

* mavlink: set system clock from SYSTEM_TIME message if behind by more than 60 seconds
This commit is contained in:
Jacob Dahl
2025-05-12 16:11:16 -08:00
committed by GitHub
parent f01aade729
commit 1d5e58b948
+7 -4
View File
@@ -86,11 +86,14 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg)
timespec tv = {};
px4_clock_gettime(CLOCK_REALTIME, &tv);
// date -d @1234567890: Sat Feb 14 02:31:30 MSK 2009
bool onb_unix_valid = (unsigned long long)tv.tv_sec > PX4_EPOCH_SECS;
bool ofb_unix_valid = time.time_unix_usec > PX4_EPOCH_SECS * 1000000ULL;
// Set the system time if we are lagging behind by more than a minute
time_t seconds_behind = 60;
time_t local_time = tv.tv_sec;
time_t remote_time = time.time_unix_usec / 1000000;
bool update = (remote_time > PX4_EPOCH_SECS) && (remote_time > local_time + seconds_behind);
if (!onb_unix_valid && ofb_unix_valid) {
if (update) {
PX4_INFO("Setting system clock from SYSTEM_TIME sent by %d/%d", msg->sysid, msg->compid);
tv.tv_sec = time.time_unix_usec / 1000000ULL;
tv.tv_nsec = (time.time_unix_usec % 1000000ULL) * 1000ULL;