GPS time vs. time_since_boot in MAVLink messages (PX4)

Hello everyone,

I am new to this forum and have already read several articles on this topic, but I couldn’t find a clear answer. Maybe someone here can help me.

I am reading IMU data via MAVLink (see MAVLink message) as well as GPS data (see MAVLink message). However, I am not receiving GPS time — only time_boot_ns.

This issue has been mentioned before ( SYSTEM TIME GPS time and boot time ), and as a solution, the message UTM_GLOBAL_POSITION ( see MAVLink message) was suggested.

However, what I actually want is for the system time to be synchronized with GPS time whenever a GPS is available. Additionally, all MAVLink messages (e.g., HIGHRES_IMU) should use this synchronized timestamp.

In other words, I do not want timestamps based on time_since_boot. Is there already a solution for this?

While looking into the PX4 code, I ended up with a few more questions:

GPS Driver (/src/drivers/gps/gps.cpp)

The GPS driver reads data from the GPS (see below) and publishes it via uORB.

_helper = new GPSDriverUBX(_interface, &GPS::callback, this, &_sensor_gps, _p_report_sat_info, settings); 

// Code

_sensor_gps_pub.publish(_sensor_gps);

UBX Driver (src/drivers/gps/devices/src/ubx.cpp)

Here, the driver sets the system time.

tm timeinfo{};
			timeinfo.tm_year	= _buf.payload_rx_nav_pvt.year - 1900;
			timeinfo.tm_mon		= _buf.payload_rx_nav_pvt.month - 1;
			timeinfo.tm_mday	= _buf.payload_rx_nav_pvt.day;
			timeinfo.tm_hour	= _buf.payload_rx_nav_pvt.hour;
			timeinfo.tm_min		= _buf.payload_rx_nav_pvt.min;
			timeinfo.tm_sec		= _buf.payload_rx_nav_pvt.sec;


			time_t epoch = mktime(&timeinfo);

			if (epoch > GPS_EPOCH_SECS) {
				// FMUv2+ boards have a hardware RTC, but GPS helps us to configure it
				// and control its drift. Since we rely on the HRT for our monotonic
				// clock, updating it from time to time is safe.

				timespec ts{};
				ts.tv_sec = epoch;
				ts.tv_nsec = _buf.payload_rx_nav_pvt.nano;

				setClock(ts);

				_gps_position->time_utc_usec = static_cast<uint64_t>(epoch) * 1000000ULL;
				_gps_position->time_utc_usec += _buf.payload_rx_nav_pvt.nano / 1000;

			} else {
				_gps_position->time_utc_usec = 0;
			}

However, this is only done if the drift is too large (see /src/drivers/gps/gps.cpp).

px4_clock_gettime(CLOCK_REALTIME, &rtc_system_time);
		timespec rtc_gps_time = *(timespec *)data1;
		int drift_time = abs(static_cast<long>(rtc_system_time.tv_sec - rtc_gps_time.tv_sec));

		if (drift_time >= SET_CLOCK_DRIFT_TIME_S) {
			// as of 2021 setting the time on Nuttx temporarily pauses interrupts
			// so only set the time if it is very wrong.
			// TODO: clock slewing of the RTC for small time differences
			px4_clock_settime(CLOCK_REALTIME, &rtc_gps_time);
		}


		break;
	}

After that:

The attribute time_utc_usec is set to the GPS time
The attribute timestamp is set to time_since_boot

				_gps_position->time_utc_usec = static_cast<uint64_t>(epoch) * 1000000ULL;
				_gps_position->time_utc_usec += _buf.payload_rx_nav_pvt.nano / 1000;

			} else {
				_gps_position->time_utc_usec = 0;

MAVLink Message: (src/modules/mavlink/streams/GPS_RAW_INT.hpp)

The MAVLink message GPS_RAW_INT subscribes to sensor_gps data.

It then sends the timestamp as follows:

if (_sensor_gps_sub.update(&gps)) {if (gps.time_utc_usec > 0) {msg.time_usec = gps.timestamp;

} else {
			msg.time_usec = gps.time_utc_usec;
}

Since time_utc_usec contains the GPS time and is > 0, gps.timestamp is used.
However, gps.timestamp corresponds to time_since_boot.

So does this mean that the MAVLink message never actually contains GPS time?

Or am I missing something? Can someone help me out?

There was a bug recently fixed:fix(mavlink): Fix gps raw int timestamp by ttechnick · Pull Request #26871 · PX4/PX4-Autopilot · GitHub

Or at least I believe this was a bug, feel free to correct me if I`m wrong.