PX4 timesync via for Voxl2
-
Where and how are incoming mavlink timesync request handled within the voxl-sdk?
I know PX4 uses timesync via mavlink to remap incoming odometry message sample timestamps. I wrote a voxl service to receive incoming mocap data and send it to PX4 the same way VIO data is in voxl-vision-hub. I have an ntp server syncing groundstation and vehicle clocks and a separate service to get monotonic boot time from voxl so i can remap the incoming mocap timestamps to be in the same frame as the vio data. I'm getting the following warning constantly in my log whenever i start sending mocap data as odom though:
[timesync] RTT too high for timesync: 86 ms
It looks like PX4 is tossing the sample timestamp whenever it sends this warning and I'm worried the transit latency is too high for PX4 to assume incoming mocap is realtime
My mocap server is a stripped down version of voxl-vision-hub with some added functionality for receiving data from the gcs and formatting the odom data. I'm wondering if I left out something that vvh is doing to handle the timesync, but I'm not sure.
Thanks!
-
-
@Moderator Thanks for the response. Follow up question, are the voxl-side timesync requests only used for updating gps timestamps?
After reading the code you linked and running mavlink-server in timesync debug mode I think that the only thing not working is the voxl timesync requests. It looks like when I start sending hil_gps or odometry mavlink messages to the autopilot pipe, one of the autopilot's responses to the voxl timesync requests is dropped or comes in after a new value for last_voxl_time_sent is generated. Then the timesync handler can't recover because it's getting responses that are 1 step behind moving forward (see below).
Since it looks like it continues to get reasonable values for now-ts1 for the autopilot requests, I don't think this is an issue depending on what voxl-side timesync is being used for. Not sure why I'm getting the RTT too high warning in my PX4 log though
output from mavlink server timesync debug mode at the point when I started sending odom/gps mavlink messages to the autopilot:
sending our own ts request at 408744677609 ap ms ahead of voxl: -0.2ms timesync: now-ts1 = 0.6ms sending our own ts request at 408845331615 ap ms ahead of voxl: -0.3ms timesync: now-ts1 = 0.9ms sending our own ts request at 408945169337 timesync: now-ts1 = 0.2ms sending our own ts request at 409044439310 timesync: now-ts1 = 0.3ms sending our own ts request at **409145346227** timesync: now-ts1 = 0.5ms sending our own ts request at **409244599326** unknown timesync request ts1 = **409145346227** tc1 = 409263819000 last_voxl_time_sent = 409244599326 timesync: now-ts1 = 0.3ms sending our own ts request at 409345147918 unknown timesync request ts1 = **409244599326** tc1 = 409406867000 last_voxl_time_sent = 409345147918 timesync: now-ts1 = 0.2ms sending our own ts request at 409445248290 unknown timesync request ts1 = 409345147918 tc1 = 409506047000 last_voxl_time_sent = 409445248290 timesync: now-ts1 = 0.2ms sending our own ts request at 409545084726 unknown timesync request ts1 = 409445248290 tc1 = 409608198000 last_voxl_time_sent = 409545084726 timesync: now-ts1 = 0.4ms sending our own ts request at 409645091472 unknown timesync request ts1 = 409545084726 tc1 = 409717154000 last_voxl_time_sent = 409645091472