SnapDragon Flight and UTC time

Am I right in concluding that the SnapDragon Flight does not support publish of the UTC time because the Hexagon does not recognize the mktime()? So in order to get the the UTC time we have to write our own mktime() for the Hexagon?

src/drivers/definitions.h

// TODO: this functionality is not available on the Snapdragon yet
#ifdef __PX4_QURT
#define NO_MKTIME
#endif

src/drivers/devices/src/ubx.cpp

#ifndef NO_MKTIME
			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_timeutc.nano / 1000;

			} else {
				_gps_position->time_utc_usec = 0;
			}

#else
			_gps_position->time_utc_usec = 0;
#endif

The Hexagon DSP has no knowledge of UTC time. In contrast, the AppsProc (ARM processor) will set UTC time from the value returned by a time server on the network, since there is no real-time clock on the board,

The time functions on the DSP, clock_gettime() and gettimeofday(), only return the current tick count since the timer on the DSP was enabled (CLOCK_MONOTONIC). I am not sure how you will populate the timeinfo structure in the sample code you provided with a valid UTC time if this code is running on the DSP.

Jim W.

Thanks for that information.

I guess I don’t need to get the UTC time into the DSP but rather to be able to populate the UTC time in the various uOrb messages. I’m interested in mapping so being able to time stamp these messages is critical. Should I just use time since system start?

vehicle_global_position.msg

# GPS position in WGS84 coordinates.
# the auto-generated field 'timestamp' is for the position & velocity (microseconds)
int32 lat			# Latitude in 1E-7 degrees
int32 lon			# Longitude in 1E-7 degrees 
int32 alt			# Altitude in 1E-3 meters above MSL, (millimetres)
int32 alt_ellipsoid 		# Altitude in 1E-3 meters bove Ellipsoid, (millimetres)

float32 s_variance_m_s		# GPS speed accuracy estimate, (metres/sec)
float32 c_variance_rad		# GPS course accuracy estimate, (radians) 
uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.   

float32 eph			# GPS horizontal position accuracy (metres)
float32 epv			# GPS vertical position accuracy (metres)

float32 hdop			# Horizontal dilution of precision
float32 vdop			# Vertical dilution of precision

int32 noise_per_ms		# GPS noise per millisecond
int32 jamming_indicator		# indicates jamming is occurring

float32 vel_m_s			# GPS ground speed, (metres/sec) 
float32 vel_n_m_s		# GPS North velocity, (metres/sec) 
float32 vel_e_m_s		# GPS East velocity, (metres/sec)
float32 vel_d_m_s		# GPS Down velocity, (metres/sec) 
float32 cog_rad			# Course over ground (NOT heading, but direction of movement), -PI..PI, (radians) 
bool vel_ned_valid		# True if NED velocity is valid 

int32 timestamp_time_relative	# timestamp + timestamp_time_relative = Time of the UTC timestamp since system start, (microseconds)
uint64 time_utc_usec		# Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0 

uint8 satellites_used		# Number of satellites used 

Should I just use time since system start?

Effectively that’s what used to populate the time fields for all of the uORB messages generated by code running on the aDSP. I don’t know enough about the GPS code to know exactly how the time value is used though, so I can’t say for sure if monotonic time is adequate.

Ok. Assuming everything is monotonic time now …

How close is the timestamp of the message to the time of the data in the message? In other words can the data in the message be older than the message timestamp?

In other words can the data in the message be older than the message timestamp.

It depends on how the code which populates the uORB data structure is implemented. From what I have seen, most PX4 code reads the time very close to the code which reads data from the sensor hardware. Nevertheless there will always be a discrepancy (older or newer) between the message data and the timestamp that depends on how the code is written.

Some sensors produce their own timestamp included with the sensor sample data, in which case, you would derive the offset (once at initialization) from monotonic time on the aDSP and use this to update the timestamp from each sensor sample.

Jim W.