Karl
January 15, 2025, 4:07am
1
I am working with the MAVLink UTM_GLOBAL_POSITION
message and have encountered an issue where the time
field is always reported as zero. All other fields in the message appear correct, including the latitude, longitude, and altitude data.
Interestingly, when I use the sensor_gps
command in a shell connected to the vehicle system, I can obtain the correct GPS time without issues.
I would appreciate any insights on why the time
field in the UTM_GLOBAL_POSITION
message remains zero despite the GPS providing a correct time.
Which PX4 version is this, and what GPS?
Karl
January 15, 2025, 4:25am
3
PX4 version : 1.14.3
GPS : here4
Thanks for that.
So this is where the time is sent out:
// Compute Unix epoch and set time field
timespec tv;
px4_clock_gettime(CLOCK_REALTIME, &tv);
uint64_t unix_epoch = (uint64_t)tv.tv_sec * 1000000 + tv.tv_nsec / 1000;
// If the time is before 2001-01-01, it's probably the default 2000
if (unix_epoch > 978307200000000) {
msg.time = unix_epoch;
msg.flags |= UTM_DATA_AVAIL_FLAGS_TIME_VALID;
}
You can see that it takes the time/date from the OS.
One thing to check would be to type date
in the MAVLink shell (QGC → Analyze tools).
Now, I assume your Here 4 is connected with DroneCAN, so then the question is why the time is not set in there. Looking at the code it should be:
// If we haven't already done so, set the system clock using GPS data
if (valid_pos_cov && !_system_clock_set) {
timespec ts{};
// get the whole microseconds
ts.tv_sec = report.time_utc_usec / 1000000ULL;
// get the remainder microseconds and convert to nanoseconds
ts.tv_nsec = (report.time_utc_usec % 1000000ULL) * 1000;
px4_clock_settime(CLOCK_REALTIME, &ts);
_system_clock_set = true;
}
Can you give me the output of listener sensor_gps
? That way we can check whether valid_pos_cov
is true or not.
Karl
January 24, 2025, 5:48am
5
Sure, this is the output of listener sensor_gps, everything include the time seems correct.
Indeed that all looks correct.
What’s the output of date
? Does it show the time and date?
1 Like
Karl
January 24, 2025, 7:41am
7
From the output of date, time field seems to start from the beginning of the UNIX epoch time.
That’s confusing, because the time should be set using px4_clock_settime.
What board are you using? Could it be that the RTC clock isn’t correctly set up?
Karl
February 5, 2025, 2:00am
9
We’re using a Cube Orange+ board. Could you guide me on how to ensure the RTC clock is correctly set up?