Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 8 additions & 5 deletions src/modules/mavlink/mavlink_timesync.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

if (!onb_unix_valid && ofb_unix_valid) {
// 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 (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;

Expand Down
Loading