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

[cscore] Use frame time in Linux UsbCameraImpl #7609

Merged
merged 27 commits into from
Jan 7, 2025

Conversation

mcm001
Copy link
Contributor

@mcm001 mcm001 commented Dec 30, 2024

Previously, we used wpi::Now in the USBCamera thread. We can instead use the frametime v4l hands us.

TODO:

  • Test on hardware with logging enabled and see what flags we get

@mcm001 mcm001 requested a review from a team as a code owner December 30, 2024 17:15
@github-actions github-actions bot added the component: cscore CameraServer library label Dec 30, 2024
@mcm001 mcm001 changed the title Use frame time in Linux UsbCameraImpl [cscore] Use frame time in Linux UsbCameraImpl Dec 30, 2024
@PeterJohnson
Copy link
Member

PeterJohnson commented Dec 30, 2024

At best, it will give you system time, which is a different time base than wpi::Now, so we will need a correction factor. I see you’ve implemented one, but yeah, we need to test with real hardware to see if it’s garbage or useful.

@mcm001
Copy link
Contributor Author

mcm001 commented Dec 30, 2024

"It" meaning v4l? I believe if V4L2_BUF_FLAG_TIMESTAMP_MONOTONIC is set it should give us montonic time, but we'll still need a correction factor anyways coz wpi::Now has a different offset (which -should- be implemented here)

@mcm001
Copy link
Contributor Author

mcm001 commented Dec 30, 2024

Re: discord -- "What I don’t know is whether the timestamp is done in the kernel for USB cameras or comes from the camera itself. If the former, it’s more likely to actually work (if the latter, there will be like 2 vendors who do it right and all the rest will be zero or garbage)"
This also scares me

@mcm001
Copy link
Contributor Author

mcm001 commented Dec 30, 2024

some sample output from my OV2311 at 1600x1200x50fps, mjpg:

CS: DEBUG: USB Camera 0: grabbing image (UsbCameraImpl.cpp:522)
CS: DEBUG: USB Camera 0: got image size=105000 index=1 (UsbCameraImpl.cpp:539)
CS: DEBUG: USB Camera 0: Flags 8192 (UsbCameraImpl.cpp:562)
CS: DEBUG: USB Camera 0: Got valid monotonic time for frame (UsbCameraImpl.cpp:567)
CS: DEBUG: USB Camera 0: Frame was 16179 uS old (UsbCameraImpl.cpp:581)
CS: DEBUG: USB Camera 0: End Of Frame false Start Of Exposure true (UsbCameraImpl.cpp:586)
CS: DEBUG: USB Camera 0: Copying data to 0x72bf082f12a0 from 0x72bf1c056000 (105000 bytes) (SourceImpl.cpp:479)
CS: DEBUG: converting image from 1600x1200 type 1 to 1600x1200 type 4 (Frame.cpp:749)
CS: DEBUG: serve_USB Camera 0: sending frame size=105000 addDHT=false (MjpegServerImpl.cpp:768)
CS: DEBUG: serve_USB Camera 0: waiting for frame (MjpegServerImpl.cpp:703)
Robot: latency 27.477 ms
CS: DEBUG: USB Camera 0: grabbing image (UsbCameraImpl.cpp:522)
CS: DEBUG: USB Camera 0: got image size=104912 index=2 (UsbCameraImpl.cpp:539)
CS: DEBUG: USB Camera 0: Flags 8192 (UsbCameraImpl.cpp:562)
CS: DEBUG: USB Camera 0: Got valid monotonic time for frame (UsbCameraImpl.cpp:567)
CS: DEBUG: USB Camera 0: Frame was 16114 uS old (UsbCameraImpl.cpp:581)
CS: DEBUG: USB Camera 0: End Of Frame false Start Of Exposure true (UsbCameraImpl.cpp:586)
CS: DEBUG: USB Camera 0: Copying data to 0x72bf0830b1f0 from 0x72bf12856000 (104912 bytes) (SourceImpl.cpp:479)
CS: DEBUG: converting image from 1600x1200 type 1 to 1600x1200 type 4 (Frame.cpp:749)
CS: DEBUG: serve_USB Camera 0: sending frame size=104912 addDHT=false (MjpegServerImpl.cpp:768)
CS: DEBUG: serve_USB Camera 0: waiting for frame (MjpegServerImpl.cpp:703)
Robot: latency 28.161 ms
CS: DEBUG: USB Camera 0: grabbing image (UsbCameraImpl.cpp:522)
CS: DEBUG: USB Camera 0: got image size=104992 index=3 (UsbCameraImpl.cpp:539)
CS: DEBUG: USB Camera 0: Flags 8192 (UsbCameraImpl.cpp:562)
CS: DEBUG: USB Camera 0: Got valid monotonic time for frame (UsbCameraImpl.cpp:567)
CS: DEBUG: USB Camera 0: Frame was 16193 uS old (UsbCameraImpl.cpp:581)
CS: DEBUG: USB Camera 0: End Of Frame false Start Of Exposure true (UsbCameraImpl.cpp:586)
CS: DEBUG: USB Camera 0: Copying data to 0x72bf082f12a0 from 0x72bf124ac000 (104992 bytes) (SourceImpl.cpp:479)
CS: DEBUG: converting image from 1600x1200 type 1 to 1600x1200 type 4 (Frame.cpp:749)
CS: DEBUG: serve_USB Camera 0: sending frame size=104992 addDHT=false (MjpegServerImpl.cpp:768)
CS: DEBUG: serve_USB Camera 0: waiting for frame (MjpegServerImpl.cpp:703)
Robot: latency 29.574 ms
CS: DEBUG: USB Camera 0: grabbing image (UsbCameraImpl.cpp:522)
CS: DEBUG: USB Camera 0: got image size=104880 index=0 (UsbCameraImpl.cpp:539)
CS: DEBUG: USB Camera 0: Flags 8192 (UsbCameraImpl.cpp:562)
CS: DEBUG: USB Camera 0: Got valid monotonic time for frame (UsbCameraImpl.cpp:567)
CS: DEBUG: USB Camera 0: Frame was 16150 uS old (UsbCameraImpl.cpp:581)
CS: DEBUG: USB Camera 0: End Of Frame false Start Of Exposure true (UsbCameraImpl.cpp:586)
CS: DEBUG: USB Camera 0: Copying data to 0x72bf0830b1f0 from 0x72bf24256000 (104880 bytes) (SourceImpl.cpp:479)
CS: DEBUG: serve_USB Camera 0: sending frame size=104880 addDHT=false (MjpegServerImpl.cpp:768)
CS: DEBUG: converting image from 1600x1200 type 1 to 1600x1200 type 4 (Frame.cpp:749)
CS: DEBUG: serve_USB Camera 0: waiting for frame (MjpegServerImpl.cpp:703)
Robot: latency 29.85 ms

The scene in question:
image

@mcm001 mcm001 requested a review from PeterJohnson as a code owner December 30, 2024 20:12
@github-actions github-actions bot added the component: wpiutil WPI utility library label Dec 30, 2024
@mcm001
Copy link
Contributor Author

mcm001 commented Dec 30, 2024

ov9782_2311_cscore_latency.txt
I did some more testing on an Orange Pi 5. I had an arducam OV9782 on /dev/video0 and an arducam ov2311 on /dev/video4. the 2311 was averaging something like 16-20ms, and the 9782 more like 28-32ms extra latency. Resolutions for both were 1600x1200 @ 50fps mjpeg. And some raw data:

Robot: camera 0: capture latency 41.45 ms from timesource 3, @ 29 fps
Robot: camera 4: capture latency 29.519 ms from timesource 3, @ 24 fps
Robot: camera 0: capture latency 37.179 ms from timesource 3, @ 36 fps
Robot: camera 4: capture latency 33.368 ms from timesource 3, @ 23 fps
Robot: camera 0: capture latency 37.404 ms from timesource 3, @ 30 fps
Robot: camera 4: capture latency 33.328 ms from timesource 3, @ 25 fps
Robot: camera 0: capture latency 37.387 ms from timesource 3, @ 33 fps
Robot: camera 0: capture latency 37.407 ms from timesource 3, @ 29 fps
Robot: camera 4: capture latency 29.645 ms from timesource 3, @ 24 fps
Robot: camera 0: capture latency 37.303 ms from timesource 3, @ 32 fps
Robot: camera 4: capture latency 29.362 ms from timesource 3, @ 26 fps
Robot: camera 0: capture latency 41.227 ms from timesource 3, @ 29 fps
Robot: camera 4: capture latency 29.589 ms from timesource 3, @ 24 fps
Robot: camera 0: capture latency 37.269 ms from timesource 3, @ 36 fps
Robot: camera 4: capture latency 29.585 ms from timesource 3, @ 25 fps
Robot: camera 0: capture latency 37.382 ms from timesource 3, @ 29 fps

@mcm001
Copy link
Contributor Author

mcm001 commented Dec 30, 2024

Just saw pybind11_stubgen - [ ERROR] In cscore._cscore.CvSink.lastFrameTimeSource : Can't find/import 'WPI_TimestampSource' - trying to include RawFrame, but does pybind support c enums?

@mcm001
Copy link
Contributor Author

mcm001 commented Dec 30, 2024

And the same test on a Pi. Note that this is at 30fps and 10fps, respectively, for the cameras, and we are in fact getting v4l timestamps in the monotonic clock timebase ;)
timestamps_pi3_ov9281_ov2311.txt

@auscompgeek
Copy link
Member

but does pybind support c enums?

It does. I don't think RobotPy currently exposes the RawFrame header.

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 1, 2025

Downstream fix for robotpy will be merged in robotpy/mostrobotpy#124

@PeterJohnson
Copy link
Member

This needs to be added to the Java/JNI layer.

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 1, 2025

Right now, Java's RawFrame doesn't store/expose time at all. Do you want me to add that? Or what makes the most sense?

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 2, 2025

fixed docs and default initialized time in RawFrame

@PeterJohnson
Copy link
Member

Have we confirmed this is okay on the Rio V4L? It’s a much older kernel version.

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 4, 2025

No, great to check - I may be able to squeeze that in tonight if nobody else hits it before then

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 4, 2025

fmt::println("frame time {} source {}", cvSink.LastFrameTime(), (int)cvSink.LastFrameTimeSource()); in apritlagsvision example actually grabs timestamps in monotonic time and gives me back exposure start time (3=SoE)! Time units are in microseconds, and latency is time from image capture (reported by Linux/V4L) to cvSink handing it to user code.

********** Robot program startup complete **********
Default DisabledPeriodic() method... Override me!
Default RobotPeriodic() method... Override me!
CS: USB Camera 0: Attempting to connect to USB camera on /dev/video0
CS: USB Camera 0: Connected to USB camera on /dev/video0
CS: USB Camera 0: set format 1 res 160x120
CS: USB Camera 0: Attempting to connect to USB camera on /dev/video0
CS: USB Camera 0: Connected to USB camera on /dev/video0
CS: USB Camera 0: set format 1 res 640x480
CS: USB Camera 0: set FPS to 30
frame time 1243074 source 3; latency 191379
frame time 1479137 source 3; latency 41147
NT: Got a NT4 connection from 10.17.36.12 port 39136
NT: CONNECTED NT4 client 'photonvision@1' (from 10.17.36.12:39136)
frame time 1539191 source 3; latency 51045
frame time 1603184 source 3; latency 47636
frame time 1667159 source 3; latency 41092
frame time 1727199 source 3; latency 44326
frame time 1791219 source 3; latency 40797
frame time 1855168 source 3; latency 39269
frame time 1901532 source 3; latency 20062
frame time 1897559 source 3; latency 24035
frame time 1901493 source 3; latency 20101
frame time 1901472 source 3; latency 20122
frame time 1897466 source 3; latency 24128
frame time 1901300 source 3; latency 20294
frame time 1901523 source 3; latency 20071
frame time 1901526 source 3; latency 20068
frame time 1901508 source 3; latency 20086

using an Arducam OV2311 on a roborio v2.

admin@roboRIO-1736-FRC:~/linuxathena# uname -a
Linux roboRIO-1736-FRC 4.14.146-rt67 #1 SMP PREEMPT RT Tue Sep 10 03:48:02 UTC 2024 armv7l GNU/Linux

@gerth2
Copy link
Contributor

gerth2 commented Jan 4, 2025

using an Arducam OV2311 on a roborio v1.

awkshully a v2

not sure if that matters.

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 4, 2025

Thanks again for donating the test bench! Best thing since sliced bread and that's coming from a bread alum

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 5, 2025

Looks like the test I added is flakey 💀

/~https://github.com/wpilibsuite/allwpilib/actions/runs/12616234632/job/35157247989

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 6, 2025

So re: test failure above -- I know that sink.grabFrame(sinkFrame) returned a non-zero time/error code, yet the test failure suggests that sinkFrame.getTimestamp() > 0 failed. Not sure how this could have happened?

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 6, 2025

From a local 100% clean allwpilib clone, on windows 11 and with the latest MSVC, I ran cscore tests with ./gradlew cscore:test --max-workers 6 -PciDebugOnly and it passed 5 times in a row. Not sure what's the difference between ci and my laptop.

*/
kFrameDequeue(1),
/** End of Frame. Same as V4L2_BUF_FLAG_TSTAMP_SRC_EOF, translated into wpi::Now's timebase. */
kV4lEoF(2),
Copy link
Member

@PeterJohnson PeterJohnson Jan 6, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The capitalization here is terrible... either the f needs to be lowercase, or it should be all caps. I'd recommend all caps.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So kV4lEof or kV4lEOF? Happy with either - I had o lowercase since that's how I'd write it out

Copy link
Member

@calcmogul calcmogul Jan 6, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The capitals would be on the first letter of words, so it would be kV4LEOF or kV4lEof. I also prefer the former.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

How's the new spelling in 5da9d3c ?

@mcm001
Copy link
Contributor Author

mcm001 commented Jan 6, 2025

@PeterJohnson PeterJohnson merged commit 2de03c9 into wpilibsuite:main Jan 7, 2025
45 checks passed
pjreiniger pushed a commit to bzlmodRio/allwpilib that referenced this pull request Jan 8, 2025
@mcm001 mcm001 deleted the cscore-frametime-linux branch January 8, 2025 15:28
mcm001 added a commit to PhotonVision/photonvision that referenced this pull request Jan 11, 2025
Now that wpilibsuite/allwpilib#7572 and
wpilibsuite/allwpilib#7609 have been merged:
- Adds a magic hidden button to enable the new frame grabber behavior by
adding a boolean topic at `/photonvision/use_new_cscore_frametime`.
Toggle this to true to maybe increase FPS at the cost of latency
variability
- Bumps WPILib to ingest
wpilibsuite/allwpilib#7609 , but doesn't
currently provide any user feedback about the time source. I don't think
that reporting this super matters?

---------

Co-authored-by: Jade <spacey-sooty@proton.me>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
component: cscore CameraServer library component: wpiutil WPI utility library
Projects
None yet
Development

Successfully merging this pull request may close these issues.

6 participants