ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

What is the correct (standard) way of using sensor_msgs/TimeReference?

asked 2019-04-01 13:28:32 -0500

billtheplatypus gravatar image

I am writing a node that indirectly interfaces with a GPS receiver. I want to match the interface of the NMEA Navsat Driver, for convenience, but I don't fully understand how the sensor_msgs/TimeReference message is to be used, especially since there is a delay between receiving the GPS message and being able to publish it.

I would think that the correct way to use it is to adjust the header of the message to contain the ROS time when the GPS message was received, and put the GPS time in the message. Is this correct? Is this in line with what other nodes produce or use? If not, what is the preferred method?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-01-28 13:41:19 -0500

gvdhoorn gravatar image

updated 2020-01-28 13:56:47 -0500

Late, but:

I would think that the correct way to use it is to adjust the header of the message to contain the ROS time when the GPS message was received, and put the GPS time in the message.

I would say this is indeed correct.

Messag fields and comments (from sensor_msgs/TimeReference):

# Measurement from an external time source not actively synchronized with the system clock.

Header header    # stamp is system time for which measurement was valid
                 # frame_id is not used 

time   time_ref  # corresponding time from this external source
string source    # (optional) name of time source

So this states:

  • header.stamp: system time for which measurement was valid (ie: when you received the data).If you have some way of compensating for the time the data was in transit, sat in a buffer or was in any other way delayed, you could intelligently compensate for that time (fi how NTP compensates for travelling time), but I've not seen any nodes doing that
  • time_ref: time from this external source

Taking these two together: header.stamp tells us when the ROS node received the data from the external time source, and time_ref is the actual timestamp, decoded (if needed) from the data received from the time source.


Edit: there aren't that many packages using this message (or at least: not that I could find). Dataspeed is using it in their driver for Oxford GPS devices. This is how they initialise the message (from here):

sensor_msgs::TimeReference gps_time_ref_msg;
gps_time_ref_msg.source = "gps";
gps_time_ref_msg.header.stamp = stamp;
g_gps_utc_time = ros::Time(toUtcTime(packet->chan.chan0.gps_minutes, packet->time));
gps_time_ref_msg.time_ref = g_gps_utc_time;
pub_gps_time_ref.publish(gps_time_ref_msg);

Where stamp is the current ros::Time passed in at the beginning of the "update loop" (ie: when reading out the data coming from the Oxford GPS).

edit flag offensive delete link more

Comments

Thanks for responding, even this late. In our case the GPS signal is received by a microcontroller, before being sent to the computer with ROS. The MCU stamps the message, and the offset between the MCU and ROS time is known.

billtheplatypus gravatar image billtheplatypus  ( 2020-01-28 14:40:26 -0500 )edit

If you know the delays in your system then you could compensate the header.stamp for it.

gvdhoorn gravatar image gvdhoorn  ( 2020-01-29 03:26:26 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2019-04-01 13:28:32 -0500

Seen: 1,063 times

Last updated: Jan 28 '20