@Eric-Katzfey Thanks for your update. We tried it on one of our drones but we had some strange issues regarding invalid setpoints afterwards and we think it may be caused by a voxl-px4 version mismatch. We were running version 1.14.0-2.0.98 of voxl-px4 and the version you provided is 1.14.0-2.0.116. Would it be difficult to provide a patch for version 1.14.0-2.0.98?
We also had our first log of that it occurred again with our forked voxl-mavlink-server. The drone continued its flight now which is good. This is the changed function:
void mavlink_services_handle_system_time(mavlink_message_t* msg)
{
// collect and consolidate information
int64_t time_now_ns = my_time_realtime_ns();
int64_t time_now_s = time_now_ns / 1e9;
int64_t gps_time_us = mavlink_msg_system_time_get_time_unix_usec(msg);
int64_t gps_time_s = gps_time_us / 1e6;
// check gps time is valid
if(gps_time_s == 0) return;
bool within_10_seconds_original = abs(time_now_s - gps_time_s)<10;
bool within_10_seconds_correct = llabs(time_now_s - gps_time_s)<10;
if (within_10_seconds_original != within_10_seconds_correct) {
printf(
"WARNING! The check if we are within 10 seconds gives an incorrect result due to wrong usage of abs.\n"
"Original: %s, Correct: %s (time_now_s=%lld, gps_time_s=%lld, diff_original=%d, diff_correct=%lld)\n",
within_10_seconds_original ? "true" : "false",
within_10_seconds_correct ? "true" : "false",
(long long)time_now_s,
(long long)gps_time_s,
abs(time_now_s - gps_time_s), // truncated 32-bit diff
llabs(time_now_s - gps_time_s) // correct 64-bit diff
);
}
// if we are within 10 seconds, good enough
if(within_10_seconds_correct){
if(time_needs_setting){
printf("detected system time has already been set\n");
}
time_needs_setting = 0;
return;
}
else time_needs_setting = 1;
if(!time_needs_setting) return;
struct timespec ts_now;
ts_now.tv_sec = time_now_s;
ts_now.tv_nsec = 0;
struct timespec ts_gps;
ts_gps.tv_sec = gps_time_s;
ts_gps.tv_nsec = 0;
printf("WARNING! System wants to use GPS system time message to set UTC clock from %s to: %s",
asctime(gmtime(&ts_now.tv_sec)),
asctime(gmtime(&ts_gps.tv_sec)));
printf("We will ignore this system time message and we won't update the clock");
// if (clock_settime(CLOCK_REALTIME, &ts) < 0) {
// perror("Failed to set system time to GPS time");
// return;
// }
time_needs_setting = 0;
return;
}
And we got log lines like this:
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: We will ignore this system time message and we won't update the clockWARNING! System wants to use GPS system time message to set UTC clock from Fri Nov 7 09:07:29 2025
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: to: Fri Nov 7 09:07:29 2025
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: We will ignore this system time message and we won't update the clockWARNING! System wants to use GPS system time message to set UTC clock from Fri Nov 7 09:07:30 2025
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: to: Fri Nov 7 09:07:30 2025
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: We will ignore this system time message and we won't update the clockWARNING! System wants to use GPS system time message to set UTC clock from Fri Nov 7 09:07:31 2025
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: to: Fri Nov 7 09:07:31 2025
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: We will ignore this system time message and we won't update the clockWARNING! System wants to use GPS system time message to set UTC clock from Fri Nov 7 09:07:32 2025
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: to: Fri Nov 7 09:07:32 2025
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: We will ignore this system time message and we won't update the clockWARNING! System wants to use GPS system time message to set UTC clock from Fri Nov 7 09:07:33 2025
Nov 07 09:07:28 JOHN voxl-mavlink-server[2237]: to: Fri Nov 7 09:07:33 2025
but I don't yet understand why it is triggering this log because both timestamps seem to be identical. Maybe you have an idea?