BrettRD / ros-gst-bridge

a bidirectional ros to gstreamer bridge and utilities for dynamic pipelines
Other
130 stars 31 forks source link

how do I preserve the ROS timestamp? #37

Open mutantbob opened 2 years ago

mutantbob commented 2 years ago

I have a bag containing test data that we want to route through gstreamer. There are two camera streams and an IMU stream. I wrote a very short python script to dump msg.header.stamp for one original camera topic, and a second topic that has the output of gst-launch-1.0 rosimagesrc ros-topic=/cam0/image_raw ! rosimagesink ros-topic=/bacon/image_raw . The time stamps appear to be slightly mangled.

# grep one /tmp/timings-b.txt |head -n 5
one builtin_interfaces.msg.Time(sec=1403636580, nanosec=413555500)
one builtin_interfaces.msg.Time(sec=1403636580, nanosec=463555500)
one builtin_interfaces.msg.Time(sec=1403636580, nanosec=513555500)
one builtin_interfaces.msg.Time(sec=1403636580, nanosec=563555500)
one builtin_interfaces.msg.Time(sec=1403636580, nanosec=613555500)
# grep two /tmp/timings-b.txt |head -n 5
two builtin_interfaces.msg.Time(sec=1403636580, nanosec=413293595)
two builtin_interfaces.msg.Time(sec=1403636580, nanosec=463293595)
two builtin_interfaces.msg.Time(sec=1403636580, nanosec=513293595)
two builtin_interfaces.msg.Time(sec=1403636580, nanosec=563293595)
two builtin_interfaces.msg.Time(sec=1403636580, nanosec=613293595)

This appears to be a difference of 261905.

I'm not sure why the timestamp is changing as it travels through gstreamer. Is there a way to preserve the timestamp as it travels through the bridge?

BrettRD commented 2 years ago

This is the result of a workaround, and I do want to fix it. The timestamps are out by however long it takes between two elements entering playback. each ROS element computes the offset between the pipeline clock and ROS time when playback starts.

Ideally, ROS elements would supply the clock and ask the pipeline for the playback offset.

Alternatively, the ROS elements should emit a bus message to synchronise their computed offsets

mutantbob commented 2 years ago

I started looking at the source code just now, and I wonder what would go wrong if the - base_time were removed (I'm looking at rosimagesrc.cpp line 533 in the source I have checked out. Is that the workaround you were talking about?

I am speculating that without this workaround, interactive playback/viewing would cut off the beginning of the images. Would a flag to choose between interactive and batch "time frame" help accommodate the two use cases (my batch use case -vs- an interactive use case)?

BrettRD commented 2 years ago

There are a couple of clocks running here GStreamer nominates a clock as a source of truth (potentially some sound card hardware), then at playback, the pipeline creates an offset so that pipeline playback always starts at time zero.

ROS time uses a different clock so there needs to be a sampling process to compare the ROS clock to the GStreamer base clock. https://github.com/BrettRD/ros-gst-bridge/blob/d794a86728c9119c0bb633c89c4fcfcc0c34f8b2/gst_bridge/src/gst_bridge.cpp#L24-L29 (this particular sampling function really needs deleting)

Once you have sampled the two clocks, you can get a close approximation to their offsets and convert a message time to a pipeline time. message time - ros_base_src->ros_clock_offset gets you a time on the gst base clock, message time - ros_base_src->ros_clock_offset - gst_element_get_base_time(GST_ELEMENT(src)) gets you a time on the playback clock.

The clock-sampling step is the workaround, and I pushed it into gst_bridge.cpp to reduce effort to ultimately rip it out.

The smallest fix is to make only one ros element per pipeline sample the clocks, and share the result with all other ros elements in only that pipeline. (different pipelines have different playback clocks derived from a base clock selected at playback start)

GStreamer has some excellent and sophisticated tools to compare multiple clocks, a far superior method is to wrap the rclcpp::clock in a GStreamer clock class, and use the Gstreamer clock sync tools to trim the clock offsets (and then also share the results between ros nodes in that pipeline to remove the last few ns)

workarounds upon workarounds, you can also use the ros base element property ros-start-time to tell the ros element what ros time corresponds to playback start, but re-reading the code it looks like I botched that and sampling noise gets in anyway.