timesync: extend timesync_status message with protocol source field and enum

This commit is contained in:
TSC21 2021-07-12 10:09:51 +02:00 committed by Nuno Marques
parent a930edf34b
commit a324e5465a
2 changed files with 10 additions and 4 deletions

View File

@ -1,5 +1,10 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 SOURCE_PROTOCOL_MAVLINK = 0
uint8 SOURCE_PROTOCOL_RTPS = 1
uint8 source_protocol # timesync source. Source can be MAVLink or the microRTPS bridge
uint64 remote_timestamp # remote system timestamp (microseconds)
int64 observed_offset # raw time offset directly observed from this timesync packet (microseconds)
int64 estimated_offset # smoothed time offset between companion system and PX4 (microseconds)
uint32 round_trip_time # round trip time of this timesync packet (microseconds)
int64 observed_offset # raw time offset directly observed from this timesync packet (microseconds)
int64 estimated_offset # smoothed time offset between companion system and PX4 (microseconds)
uint32 round_trip_time # round trip time of this timesync packet (microseconds)

View File

@ -141,6 +141,7 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg)
timesync_status_s tsync_status{};
tsync_status.timestamp = hrt_absolute_time();
tsync_status.source_protocol = timesync_status_s::SOURCE_PROTOCOL_MAVLINK;
tsync_status.remote_timestamp = tsync.tc1 / 1000ULL;
tsync_status.observed_offset = offset_us;
tsync_status.estimated_offset = (int64_t)_time_offset;