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

Incorrect timestamp #75

Closed
flajolet opened this issue Jun 30, 2017 · 8 comments
Closed

Incorrect timestamp #75

flajolet opened this issue Jun 30, 2017 · 8 comments

Comments

@flajolet
Copy link

flajolet commented Jun 30, 2017

Hi!

I ran a simple experiment to evaluate the accuracy of the timestamps issued by usb_cam when publishing the images. It seems that the timestamps are not necessarily very accurate. Does anybody know how to fix this?

SETUP:
I have a node publishing to a topic the current rostime which is then printed to the screen with rostopic echo. My usb camera is facing the screen and I use usb_cam to stream the images. The raw (compressed) images are written to a file with rosbag. The point of the setup is to compare the timestamp that can be seen on the image (acquisition time) with the timestamp of the corresponding image message when replaying the rosbag. The parameters input into usb_cam (width=1280, height=1024, fps=30, and pixel_format="mjpeg") are consistent with what is prescribed by v4l2-ctl --list-formats-ext.

RESULT:
There is systematically a significant offset (around 0.15s for this setup) between the timestamp and the actual time acquisition time as can be seen below. This offset varies as function of the resolution of the image and the selected fps.
screenshot from 2017-06-29 19 43 13

@lucasw
Copy link
Contributor

lucasw commented Jul 1, 2017

The timestamp is assigned right after grabbing the frame:

grab_image();
// stamp the image
msg->header.stamp = ros::Time::now();

https://github.com/ros-drivers/usb_cam/blob/develop/src/usb_cam.cpp#L1087

Instead it probably should be done right after the select indicates there is a new frame available in grab_image before it actually reads the image, so that time delay is eliminated. I'll try this out eventually and link to a branch here unless you want to do it first.

I wonder what is happening on the other side of that select - maybe it is close to the actually acquisition time or there could still be a lot of delay in it. And if that is true then maybe there is another method to get at the device to have it timestamp when the frame actually happened?

lucasw added a commit to lucasw/usb_cam that referenced this issue Jul 2, 2017
@lucasw
Copy link
Contributor

lucasw commented Jul 2, 2017

I haven't duplicated your webcam setup but all I could account for when moving the timestamping to immediately after the select was about 5-15ms depending on the resolution of the image.

@lucasw
Copy link
Contributor

lucasw commented Jul 2, 2017

The v4l2_buffer which exists for IO_METHOD_USERPTR and IO_METHOD_MMAP (the default for me) has a timestamp field which ought to be better than after select.

My buf.flags is 0x12003 which meansV4L2_BUF_FLAG_TSTAMP_SRC_SOE (start of exposure -if the length of exposure were available the middle of the exposure would be the best stamp.) is set, and V4L2_BUF_FLAG_TIMESTAMP_MONOTONIC- the clock value needs to be converted to the same time that ros time uses.

lucasw added a commit to lucasw/usb_cam that referenced this issue Jul 2, 2017
@lucasw
Copy link
Contributor

lucasw commented Jul 2, 2017

Try out my lucasw/usb_cam timestamp branch and see if that fixes the issue.

I observed an average 60 ms difference between the time select() returned and the timestamp inside the v4l2_buffer for a 640x480 image, that sounds very close to the time differences you are seeing.

@lucasw
Copy link
Contributor

lucasw commented Jul 2, 2017

I tried out the webcam recording the current ros time on a terminal method and I'm seeing time stamp differences like

image     v4l2 stamp
x.9156    x.9138
x.1169    x.1178
x.3182    x.3178
x.6199    x.6218
x.8216    x.8218
x.1232    x.1285
x.2239    x.2258

Without knowing the exposure time it could be rolling shutter that is responsible for time difference between the top and bottom of the frame, the above was captured at the bottom of the frame.

@flajolet
Copy link
Author

flajolet commented Jul 5, 2017

Thank you so much for your help! I ran the same experiment with the exact same setup on your branch and the offset is indeed much smaller (around 30ms to be more specific).

@flynneva
Copy link
Collaborator

@flajolet we've included this update into the new ros2 branch here on this repo.

if you have time do you think you could take a look at the new changes and see if you are still seeing the time offset? would be great to look at some data on the delay we are seeing with the current code.

@twdragon twdragon linked a pull request Nov 2, 2022 that will close this issue
@flynneva
Copy link
Collaborator

flynneva commented Apr 9, 2023

Closing as resolved

@flynneva flynneva closed this as completed Apr 9, 2023
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging a pull request may close this issue.

3 participants