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

GPS and PPS time sync status #367

Open
amir-zviran opened this issue Nov 26, 2024 · 4 comments
Open

GPS and PPS time sync status #367

amir-zviran opened this issue Nov 26, 2024 · 4 comments
Labels
enhancement New feature or request

Comments

@amir-zviran
Copy link

Hi,

I'm using 3DM-CV7. I connect its PPS input to my GPS module, and sending it time reference messages on the /external_gps_time topic. I can see it is synced by looking at the timestamps of the messages, but I wonder if I can rely on that to tell whether the sync is working well.

I have a few questions:

  1. Will the timestamps of the messages change to the GPS time (i.e. the time reference time) even if it is not yet synced with the PPS signal?
  2. Is there a way to read the Time Sync Status (0xA0,0x02) register through the ROS driver?
  3. Is reading the time sync status enough to tell the sync is "complete", i.e. both the PPS signal is valid and the time is correctly set according to the time reference? Or I have to look at the time_valid field in the GPS Timestamp (0xFF,0xD3) register too?
  4. If I need to look at the GPS Timestamp (0xFF,0xD3) register, can I read it through the ROS driver?

Many thanks!
Amir

@github-actions github-actions bot added the New This issue is new, and should not be marked as stale label Nov 26, 2024
@amir-zviran
Copy link
Author

@robbiefish Can you help with this one?
Thanks!

@robbiefish robbiefish added enhancement New feature or request and removed New This issue is new, and should not be marked as stale labels Jan 9, 2025
@robbiefish
Copy link

Hi @amir-zviran

  1. Yes, it will change to GPS time as soon as it gets a valid GPS time. The reverse is also true. If PPS is acheived before GPS time, the fractional seconds will be updated correctly. Note that the newest version of the driver supports multiple different timestamp types. Please see this section of the config for more information, you will probably want timestamp_source: 1 to get the raw device time.
  2. Not currently no
  3. The Time Sync Status field will tell you if the fractional seconds are valid. You will need to check the time_valid field of the GPS timestamp register to see if the time is correctly set
  4. All MIP messages published by the ROS driver will have a header.gps_timestamp field that will contain this message. Note that it does not contain the time_valid field

With all of this being said, it looks like the current version of the driver is missing some of the information to do what you are trying to do. I think this is a valid use case, so I have made the feature/ros_time_sync_status and feature/ros2_time_sync_status branches that should provide all of the information you are looking for.

To look at the state of the time sync, set mip_system_time_sync_status_data_rate to a non-zero value, then subscribe to mip/system/time_sync_status. You can check time_sync to check that the fractional seconds are set properly, and header.gps_timestamp.time_valid to see if the time is valid.

I do not have a setup to test PPS here, so please let me know how this works for you

@amir-zviran
Copy link
Author

Hi @robbiefish ,

Thanks for the detailed reply and for adding this feature!

I tried it out and these are my findings:

  1. The time_sync flag and last_pps_rcvd field are working great :)
  2. The whole header of the time_sync_status message doesn't seem to be updated. It shows a constant timestamp, and the rest of the fields are all zeros/False:
header: 
  header: 
    seq: 0
    stamp: 
      secs: 315964782
      nsecs:         0
    frame_id: "imu_link"
  event_source: 0
  reference_timestamp: 0
  gps_timestamp: 
    tow: 0.0
    week_number: 0
    valid_flags: 
      tow: False
      week_number: False
      time_valid: False
time_sync: True
last_pps_rcvd: 0
  1. I changed to configuration to publish /mip/ekf/status, and looking at the header of this message, all the fields are being updated as expected, except for the time_valid field which remains False:
header: 
  seq: 0
  stamp: 
    secs: 1736762098
    nsecs: 207999944
  frame_id: "imu_link"
event_source: 0
reference_timestamp: 1712361000000
gps_timestamp: 
  tow: 122116.20798678901
  week_number: 2349
  valid_flags: 
    tow: True
    week_number: True
    time_valid: False

The timestamp in the header of the IMU samples (/imu/data/header) is also ok.

As a side note, I just moved from using ROS melodic to ROS noetic, and this is the first time I tested your driver on this version.
When using ROS noetic, I installed your driver using apt install, ending up with version 3.0.1. When using that, syncing the IMU time with my GPS required setting this flag in the config file:
filter_enable_external_gps_time_update : True
And then sending the time reference to this topic:
filter_external_gps_time_topic : "/external_gps_time"
With the new version on ROS noetic (4.5.0), with or without your latest changes, this doesn't work anymore. Digging into the code a bit, I realized I must set this flag:
subscribe_ext_time : True
And use the topic /ext/time for sending my time reference. This is what I used to test the above.
Is that the correct way to go? Is filter_enable_external_gps_time_update still being used anywhere?

Thanks a lot for all your help!

Best,
Amir

@amir-zviran
Copy link
Author

Hi @robbiefish ,

Can you have a look at that?

Thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement New feature or request
Projects
None yet
Development

No branches or pull requests

2 participants