ROS node for streaming an image topic to a video capture device. Mostly based on this:
Setup a workspace:
cd ~/catkin_ws/src # or wherever catkin_ws is
git clone https://github.com/lucasw/image_to_v4l2loopback
cd ..
catkin build image_to_v4l2loopback
Stream node needs to write to a video capture device, which varies depending on your system.
Uses v4l2-loopback:
Secure boot uefi will prevent the modprobe from working, try https://askubuntu.com/questions/762254/why-do-i-get-required-key-not-available-when-install-3rd-party-kernel-modules
sudo apt install mokutil
sudo mokutil --disable-validation
sudo reboot
# don't bother this version is too old
# sudo apt-get install v4l2loopback-*
But the ubuntu v4l2loopback is old if it doesn't work, try
git clone git@github.com:umlaeute/v4l2loopback
cd v4l2loopback
make
sudo insmod v4l2loopback.ko exclusive_caps=1 video_nr=1 card_label="Fake"
See https://github.com/umlaeute/v4l2loopback for more instructions
sudo modprobe v4l2loopback video_nr=1
v4l2-ctl -D -d /dev/video1
Driver Info (not using libv4l2):
Driver name : v4l2 loopback
Card type : Dummy video device (0x0000)
Bus info : v4l2loopback:0
Driver version: 0.8.0
Capabilities : 0x05000003
Video Capture
Video Output
Read/Write
Streaming
Typically just:
rosrun image_to_v4l2loopback stream _device:=/dev/video1 _width:=640 _height:=480 _fourcc:=YV12 image:=/my_camera/image
That resolution will then be locked in, need to rmmod and restart the module then set the resolution again.
where:
/dev/video1
target device640x480
target sizeYV12
target pixel format/my_camera/image
the sourcesensor_msgs/Image
topic re-mapped toimage
For more:
rosrun image_to_v4l2loopback stream --help
cheese works, but guvcview does not.
Google hangouts says no camera found.
zoom-client works.
v4l2-ctl -D -d /dev/video1
Driver Info (not using libv4l2):
Driver name : v4l2 loopback
Card type : Dummy video device (0x0000)
Bus info : v4l2loopback:0
Driver version: 0.8.0
Capabilities : 0x05000003
Video Capture
Video Output
Read/Write
Streaming
ROS_VIRTUAL_CAM_STREAM_TEST_DEVICE=/dev/video1 catkin_make run_tests
If you want coverage:
catkin_make -DCMAKE_BUILD_TYPE=Debug -DCOVERAGE=ON
ROS_VIRTUAL_CAM_STREAM_TEST_DEVICE=/dev/video1 catkin_make run_tests
lcov --path . --directory . --capture --output-file coverage.info
lcov --remove coverage.info 'tests/*' '/usr/*' '/opt/*' --output-file coverage.info
lcov --list coverage.info