Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[uxrce_dds_client] Set PX4 clock from UTC #22290

Merged
merged 3 commits into from
Nov 23, 2023

Conversation

dakejahl
Copy link
Contributor

In systems with a companion computer without a GPS, it would be nice to use the timestamps from the DDS bridge to set the PX4 system time.

@dakejahl dakejahl force-pushed the pr-dds_set_system_time branch from 8b05309 to 5911516 Compare November 1, 2023 02:21
@dakejahl dakejahl marked this pull request as ready for review November 1, 2023 02:21
@dakejahl dakejahl force-pushed the pr-dds_set_system_time branch 5 times, most recently from 7198e27 to a16c83a Compare November 1, 2023 03:05
@dagar
Copy link
Member

dagar commented Nov 2, 2023

This is likely what we want most of the time, but annoyingly not all the time.

At a minimum can you add some tolerance (so that we don't fight with GPS or Mavlink time setting) and probably best to add a parameter so that this can be disabled if necessary.

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);
}

Note for GPS right now that UTC time is coming from the navigation solution that's already ~100 milliseconds old. I have notes/plans on how to do it all perfectly with the TIMEPULSE, extending to CAN nodes, etc, but so far it hasn't been a priority.

@dakejahl
Copy link
Contributor Author

dakejahl commented Nov 2, 2023

At a minimum can you add some tolerance (so that we don't fight with GPS or Mavlink time setting)

@dagar This logic occurs before the main loop and will only get executed once when the dds_client starts. Should I add it to the main loop such that it works the same way as GPS/Mavlink?

@Ryanf55
Copy link

Ryanf55 commented Nov 3, 2023

Is there a reason you chose not to use MicroXRCE DDS's built in time sync callback support in uxr_set_time_callback?
https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html

I am happy to open up a discussion with eProsima to see if it's intended for this use case.

@dagar
Copy link
Member

dagar commented Nov 3, 2023

At a minimum can you add some tolerance (so that we don't fight with GPS or Mavlink time setting)

@dagar This logic occurs before the main loop and will only get executed once when the dds_client starts. Should I add it to the main loop such that it works the same way as GPS/Mavlink?

Likely yes, but we could come back to that later if/when we're ready to tackle the larger story with GPS (TIMEPULSE, etc).

For now at least add the parameter so this can be disabled if it's not ideal for a particular setup?

@dakejahl
Copy link
Contributor Author

dakejahl commented Nov 3, 2023

@Ryanf55 it does use uxr_set_time_callback

@dagar okay I added a parameter to enable clock synchronization along with the same logic in GPS and Mavlink to only set the clock if dt > 5_s. I also refactored a little bit.. 😅

@dakejahl dakejahl force-pushed the pr-dds_set_system_time branch from 81b63b0 to ff094ca Compare November 16, 2023 00:13
…n. Refactored and cleaned up. Only set system time if it's off by more than 5 seconds (same as mavlink and gps).
@dakejahl dakejahl force-pushed the pr-dds_set_system_time branch from ff094ca to 630dc99 Compare November 16, 2023 00:42
@dakejahl
Copy link
Contributor Author

dakejahl commented Nov 16, 2023

Rebased and retested functional except for this issue which I think was introduced in the latest commits
#22382

@dakejahl dakejahl closed this Nov 16, 2023
@dakejahl dakejahl reopened this Nov 16, 2023
@dakejahl dakejahl changed the title Set system time from DDS [uxrce_dds_client] Set PX4 clock from UTC Nov 20, 2023
@dakejahl
Copy link
Contributor Author

@dagar asked about if this waits for the Timesync to converge -- the answer is "no", but neither does the current logic for setting the session->time_offset. Also I think it's really not important that the time is perfectly synchronized for this case anyway, we really just want to be close enough for the purpose of analyzing and organizing log files by time/date.

This PR stems from me trying to analyze logs from a system without GPS and all of the log files have the same garbage date which is the start of the epoch

@dagar
Copy link
Member

dagar commented Nov 23, 2023

All you'd need to do is make this public, then call _timesync.sync_converged(). We can do it later when tightening up the timesync in general (GPS, CAN nodes, etc).

/**
* Return true if the timesync algorithm converged to a good estimate,
* return false otherwise
*/
bool sync_converged() const { return _sequence >= CONVERGENCE_WINDOW; }

@dagar dagar merged commit 6cc3877 into PX4:main Nov 23, 2023
163 of 169 checks passed
timzarhansen pushed a commit to timzarhansen/PX4-Autopilot that referenced this pull request Sep 3, 2024
…IME (PX4#22290)

* Added parameter UXRCE_DDS_SYNCC to enable system clock synchronization. Refactored and cleaned up. Only set system time if it's off by more than 5 seconds (same as mavlink and gps).
@dakejahl dakejahl deleted the pr-dds_set_system_time branch November 20, 2024 02:56
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants