PX4-Autopilot/src/modules/mavlink/mavlink_timesync.cpp
Jacob Dahl 1d5e58b948
mavlink: set system clock from SYSTEM_TIME (#24807)
* mavlink: set system clock from SYSTEM_TIME message if behind by more than 60 seconds
2025-05-12 16:11:16 -08:00

112 lines
3.5 KiB
C++

/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mavlink_timesync.cpp
* Mavlink timesync implementation.
*
* @author Mohammed Kabir <mhkabir98@gmail.com>
*/
#include "mavlink_timesync.h"
#include "mavlink_main.h"
#include <stdlib.h>
MavlinkTimesync::MavlinkTimesync(Mavlink &mavlink) :
_mavlink(mavlink)
{
}
void
MavlinkTimesync::handle_message(const mavlink_message_t *msg)
{
switch (msg->msgid) {
case MAVLINK_MSG_ID_TIMESYNC: {
mavlink_timesync_t tsync = {};
mavlink_msg_timesync_decode(msg, &tsync);
const uint64_t now = hrt_absolute_time();
if (tsync.tc1 == 0) { // Message originating from remote system, timestamp and return it
mavlink_timesync_t rsync;
rsync.tc1 = now * 1000ULL;
rsync.ts1 = tsync.ts1;
mavlink_msg_timesync_send_struct(_mavlink.get_channel(), &rsync);
return;
} else if (tsync.tc1 > 0) { // Message originating from this system, compute time offset from it
_timesync.update(now, tsync.tc1, tsync.ts1);
}
break;
}
case MAVLINK_MSG_ID_SYSTEM_TIME: {
mavlink_system_time_t time;
mavlink_msg_system_time_decode(msg, &time);
timespec tv = {};
px4_clock_gettime(CLOCK_REALTIME, &tv);
// 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;
if (px4_clock_settime(CLOCK_REALTIME, &tv)) {
PX4_ERR("[timesync] Failed setting realtime clock");
}
}
break;
}
default:
break;
}
}