Skip to content

Instantly share code, notes, and snippets.

@lucasw
Last active February 21, 2023 23:24
Show Gist options
  • Save lucasw/85dc92c9f5146e9d5175a33b49ef4a90 to your computer and use it in GitHub Desktop.
Save lucasw/85dc92c9f5146e9d5175a33b49ef4a90 to your computer and use it in GitHub Desktop.
USB/V4L/UVC Cameras with ROS

USB 'web' cameras vs. ethernet and network cameras

Cost and feature/performance trade-offs

Built-in laptop camera

$ lsusb
Bus 002 Device 004: ID 0a5c:5800 Broadcom Corp. BCM5880 Secure Applications Processor
Bus 002 Device 002: ID 8087:8000 Intel Corp. 
Bus 002 Device 001: ID 1d6b:0002 Linux Foundation 2.0 root hub
Bus 001 Device 003: ID 0c45:64d0 Microdia 
Bus 001 Device 002: ID 8087:8008 Intel Corp. 
Bus 001 Device 001: ID 1d6b:0002 Linux Foundation 2.0 root hub
Bus 004 Device 001: ID 1d6b:0003 Linux Foundation 3.0 root hub
Bus 003 Device 001: ID 1d6b:0002 Linux Foundation 2.0 root hub
Bus 001 Device 003: ID 0c45:64d0 Microdia
$ dmesg | grep -i 64d0 -C 10
...
[    1.618163] usb 1-1.5: New USB device found, idVendor=0c45, idProduct=64d0
[    1.618906] usb 1-1.5: New USB device strings: Mfr=2, Product=1, SerialNumber=0
[    1.619619] usb 1-1.5: Product: Laptop_Integrated_Webcam_HD
[    1.620203] usb 1-1.5: Manufacturer: CN0767N97248751KB15VA01
...
[    8.650505] Linux video capture interface: v2.00
[    8.737694] uvcvideo: Found UVC 1.00 device Laptop_Integrated_Webcam_HD (0c45:64d0)
[    8.776856] input: Laptop_Integrated_Webcam_HD as /devices/pci0000:00/0000:00:1a.0/usb1/1-1/1-1.5/1-1.5:1.0/input/input17
[    8.776894] usbcore: registered new interface driver uvcvideo
[    8.776895] USB Video Class driver (1.1.1)
~$ guvcview /dev/video0
GUVCVIEW: version 2.0.2
V4L2_CORE: (UVCIOC_CTRL_MAP) Error: No such file or directory
V4L2_CORE: (UVCIOC_CTRL_MAP) Error: No such file or directory
V4L2_CORE: (UVCIOC_CTRL_MAP) Error: No such file or directory
V4L2_CORE: (UVCIOC_CTRL_MAP) Error: No such file or directory
V4L2_CORE: (UVCIOC_CTRL_MAP) Error: No such file or directory
V4L2_CORE: (UVCIOC_CTRL_MAP) Error: No such file or directory
V4L2_CORE: (UVCIOC_CTRL_MAP) Error: No such file or directory
V4L2_CORE: (UVCIOC_CTRL_MAP) Error: No such file or directory
V4L2_CORE: (UVCIOC_CTRL_MAP) Error: No such file or directory
ALSA lib pcm_dsnoop.c:606:(snd_pcm_dsnoop_open) unable to open slave
ALSA lib pcm_dmix.c:1029:(snd_pcm_dmix_open) unable to open slave
ALSA lib pcm.c:2266:(snd_pcm_open_noupdate) Unknown PCM cards.pcm.rear
ALSA lib pcm.c:2266:(snd_pcm_open_noupdate) Unknown PCM cards.pcm.center_lfe
ALSA lib pcm.c:2266:(snd_pcm_open_noupdate) Unknown PCM cards.pcm.side
ALSA lib pcm_dmix.c:1029:(snd_pcm_dmix_open) unable to open slave
Cannot connect to server socket err = No such file or directory
Cannot connect to server request channel
jack server is not running or cannot be started
JackShmReadWritePtr::~JackShmReadWritePtr - Init not done for 4294967295, skipping unlock
JackShmReadWritePtr::~JackShmReadWritePtr - Init not done for 4294967295, skipping unlock

Logitech HD Pro Webcam C930e

$90 from Amazon.

Autofocus or digitally controllable focus- great macro capability also.

Also has built-in microphone, more on that later.

Tripod screw mount on bottom (earlier < 920 versions didn't have this).

Can remove plastic shell to reduce size.

Plug in camera

[ 4243.454838] usb 3-3: new high-speed USB device number 3 using xhci_hcd
[ 4244.692237] usb 3-3: New USB device found, idVendor=046d, idProduct=0843
[ 4244.692241] usb 3-3: New USB device strings: Mfr=0, Product=2, SerialNumber=1
[ 4244.692242] usb 3-3: Product: Logitech Webcam C930e
[ 4244.692243] usb 3-3: SerialNumber: 7B1F226E
[ 4244.692740] uvcvideo: Found UVC 1.00 device Logitech Webcam C930e (046d:0843)
[ 4244.693130] input: Logitech Webcam C930e as /devices/pci0000:00/0000:00:14.0/usb3/3-3/3-3:1.0/input/input19
$ lsusb
...
Bus 003 Device 003: ID 046d:0843 Logitech, Inc. Webcam C930e
...

v4l2ucp

The problem with usb_cam and other ros drivers is that they have to hard-code options and controls as ros params, even dynamic reconfigure isn't that dynamic- it is still hard-coded underneath. But cameras have a v4l api that allows any camera to have any sort of control- that has to be exposed into ros after the node launches.

For that I created a variant on v4l2ucp that creates all controls as ros topics: https://github.com/lucasw/v4l2ucp

You could write your own gui to interact with those topics, or use rostopic pub, but dynamic reconfigure is nicer- so using a dynamic dynamic reconfigure tool that interfaces with rostopics the same way my v4l2ucp creates them is needed: https://github.com/lucasw/dynamic_reconfigure_tools/blob/master/dynamic_reconfigure_tools/scripts/dr_topics.py

(I've found it is possible to create dynamic reconfigure configurations at runtime in python, but not in C++, though there is another ddr project out there that may have a solution that was presented in a 2016 ROSCon lightning talk)

Finally you can use the standard rqt dynamic reconfigure plugin or my rqt_dr_single which is configure to work with a single dr server and remember it when reloaded.

$ rosrun v4l2ucp v4l2ucp _device:=/dev/video1 __ns:=/usb_cam
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/mainWindow.cpp]:[54] [uvcvideo]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/mainWindow.cpp]:[55] [Logitech Webcam C930e]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/mainWindow.cpp]:[56] [usb-0000:00:14.0-3]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/mainWindow.cpp]:[59] [4.4.87]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/mainWindow.cpp]:[61] [0x85200001]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[271] [Power Line Frequency Disabled]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[271] [Power Line Frequency 50 Hz]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[271] [Power Line Frequency 60 Hz]
[ERROR] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[277] [Exposure, Auto Unable to get menu item0]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[271] [Exposure, Auto Manual Mode]
[ERROR] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[277] [Exposure, Auto Unable to get menu item2]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[271] [Exposure, Auto Aperture Priority Mode]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[271] [LED1 Mode Off]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[271] [LED1 Mode On]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[271] [LED1 Mode Blink]
[ INFO] [/v4l2ucp] [/home/lucasw/catkin_ws/src/v4l2ucp/v4l2ucp/src/v4l2controls.cpp]:[271] [LED1 Mode Auto]
rostopic list
...
/usb_cam/configured
/usb_cam/controls/BacklightCompensation
/usb_cam/controls/Brightness
/usb_cam/controls/Contrast
/usb_cam/controls/ExposureAbsolute
/usb_cam/controls/ExposureAuto
/usb_cam/controls/ExposureAutoPriority
/usb_cam/controls/FocusAuto
/usb_cam/controls/Focusabsolute
/usb_cam/controls/Gain
/usb_cam/controls/LED1Frequency
/usb_cam/controls/LED1Mode
/usb_cam/controls/PanAbsolute
/usb_cam/controls/PowerLineFrequency
/usb_cam/controls/Saturation
/usb_cam/controls/Sharpness
/usb_cam/controls/TiltAbsolute
/usb_cam/controls/WhiteBalanceTemperature
/usb_cam/controls/WhiteBalanceTemperatureAuto
/usb_cam/controls/ZoomAbsolute
/usb_cam/feedback/BacklightCompensation
/usb_cam/feedback/Brightness
/usb_cam/feedback/Contrast
/usb_cam/feedback/ExposureAbsolute
/usb_cam/feedback/ExposureAuto
/usb_cam/feedback/ExposureAutoPriority
/usb_cam/feedback/FocusAuto
/usb_cam/feedback/Focusabsolute
/usb_cam/feedback/Gain
/usb_cam/feedback/LED1Frequency
/usb_cam/feedback/LED1Mode
/usb_cam/feedback/PanAbsolute
/usb_cam/feedback/PowerLineFrequency
/usb_cam/feedback/Saturation
/usb_cam/feedback/Sharpness
/usb_cam/feedback/TiltAbsolute
/usb_cam/feedback/WhiteBalanceTemperature
/usb_cam/feedback/WhiteBalanceTemperatureAuto
/usb_cam/feedback/ZoomAbsolute
rosparam list
...
/usb_cam/controls/BacklightCompensation/default
/usb_cam/controls/BacklightCompensation/max
/usb_cam/controls/BacklightCompensation/min
/usb_cam/controls/BacklightCompensation/name
/usb_cam/controls/BacklightCompensation/topic
/usb_cam/controls/BacklightCompensation/type
/usb_cam/controls/Brightness/default
/usb_cam/controls/Brightness/max
/usb_cam/controls/Brightness/min
/usb_cam/controls/Brightness/name
/usb_cam/controls/Brightness/topic
/usb_cam/controls/Brightness/type
/usb_cam/controls/Contrast/default
/usb_cam/controls/Contrast/max
/usb_cam/controls/Contrast/min
/usb_cam/controls/Contrast/name
/usb_cam/controls/Contrast/topic
/usb_cam/controls/Contrast/type
/usb_cam/controls/ExposureAbsolute/default
/usb_cam/controls/ExposureAbsolute/max
/usb_cam/controls/ExposureAbsolute/min
/usb_cam/controls/ExposureAbsolute/name
/usb_cam/controls/ExposureAbsolute/topic
/usb_cam/controls/ExposureAbsolute/type
/usb_cam/controls/ExposureAuto/default
/usb_cam/controls/ExposureAuto/max
/usb_cam/controls/ExposureAuto/min
/usb_cam/controls/ExposureAuto/name
/usb_cam/controls/ExposureAuto/topic
/usb_cam/controls/ExposureAuto/type
/usb_cam/controls/ExposureAutoPriority/default
/usb_cam/controls/ExposureAutoPriority/max
/usb_cam/controls/ExposureAutoPriority/min
/usb_cam/controls/ExposureAutoPriority/name
/usb_cam/controls/ExposureAutoPriority/topic
/usb_cam/controls/ExposureAutoPriority/type
/usb_cam/controls/FocusAuto/default
/usb_cam/controls/FocusAuto/max
/usb_cam/controls/FocusAuto/min
/usb_cam/controls/FocusAuto/name
/usb_cam/controls/FocusAuto/topic
/usb_cam/controls/FocusAuto/type
/usb_cam/controls/Focusabsolute/default
/usb_cam/controls/Focusabsolute/max
/usb_cam/controls/Focusabsolute/min
/usb_cam/controls/Focusabsolute/name
/usb_cam/controls/Focusabsolute/topic
/usb_cam/controls/Focusabsolute/type
/usb_cam/controls/Gain/default
/usb_cam/controls/Gain/max
...
/usb_cam/controls/WhiteBalanceTemperature/name
/usb_cam/controls/WhiteBalanceTemperature/topic
/usb_cam/controls/WhiteBalanceTemperature/type
/usb_cam/controls/WhiteBalanceTemperatureAuto/default
/usb_cam/controls/WhiteBalanceTemperatureAuto/max
/usb_cam/controls/WhiteBalanceTemperatureAuto/min
/usb_cam/controls/WhiteBalanceTemperatureAuto/name
/usb_cam/controls/WhiteBalanceTemperatureAuto/topic
/usb_cam/controls/WhiteBalanceTemperatureAuto/type
/usb_cam/controls/ZoomAbsolute/default
/usb_cam/controls/ZoomAbsolute/max
/usb_cam/controls/ZoomAbsolute/min
/usb_cam/controls/ZoomAbsolute/name
/usb_cam/controls/ZoomAbsolute/topic
/usb_cam/controls/ZoomAbsolute/type
$ rosrun dynamic_reconfigure_tools dr_topics.py __ns:=/usb_cam
[INFO] [/usb_cam/dr_topics] [/home/lucasw/catkin_ws/src/dynamic_reconfigure_tools/dynamic_reconfigure_tools/scripts/dr_topics.py]:[41] [/usb_cam/]
Saturation : /usb_cam/controls/Saturation/default
Zoom, Absolute : /usb_cam/controls/ZoomAbsolute/default
Brightness : /usb_cam/controls/Brightness/default
Exposure, Auto : /usb_cam/controls/ExposureAuto/default
Focus, Auto : /usb_cam/controls/FocusAuto/default
Pan (Absolute) : /usb_cam/controls/PanAbsolute/default
Sharpness : /usb_cam/controls/Sharpness/default
White Balance Temperature : /usb_cam/controls/WhiteBalanceTemperature/default
LED1 Frequency : /usb_cam/controls/LED1Frequency/default
LED1 Mode : /usb_cam/controls/LED1Mode/default
Backlight Compensation : /usb_cam/controls/BacklightCompensation/default
Focus (absolute) : /usb_cam/controls/Focusabsolute/default
Tilt (Absolute) : /usb_cam/controls/TiltAbsolute/default
Exposure (Absolute) : /usb_cam/controls/ExposureAbsolute/default
Gain : /usb_cam/controls/Gain/default
Exposure, Auto Priority : /usb_cam/controls/ExposureAutoPriority/default
Power Line Frequency : /usb_cam/controls/PowerLineFrequency/default
Contrast : /usb_cam/controls/Contrast/default
White Balance Temperature, Auto : /usb_cam/controls/WhiteBalanceTemperatureAuto/default
@lucasw
Copy link
Author

lucasw commented Oct 25, 2017

v4l2-ctl

laptop camera

$ v4l2-ctl --device=0 --list-formats-ext
ioctl: VIDIOC_ENUM_FMT
	Index       : 0
	Type        : Video Capture
	Pixel Format: 'YUYV'
	Name        : YUYV 4:2:2
		Size: Discrete 640x480
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
		Size: Discrete 640x360
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
		Size: Discrete 352x288
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
		Size: Discrete 320x240
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
		Size: Discrete 424x240
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
		Size: Discrete 176x144
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
		Size: Discrete 160x120
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
		Size: Discrete 1280x720
			Interval: Discrete 0.091s (11.000 fps)

	Index       : 1
	Type        : Video Capture
	Pixel Format: 'MJPG' (compressed)
	Name        : Motion-JPEG
		Size: Discrete 960x540
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
		Size: Discrete 1280x720
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
$ v4l2-ctl --all
Driver Info (not using libv4l2):
	Driver name   : uvcvideo
	Card type     : Laptop_Integrated_Webcam_HD
	Bus info      : usb-0000:00:1a.0-1.5
	Driver version: 4.4.90
	Capabilities  : 0x84200001
		Video Capture
		Streaming
		Extended Pix Format
		Device Capabilities
	Device Caps   : 0x04200001
		Video Capture
		Streaming
		Extended Pix Format
Priority: 2
Video input : 0 (Camera 1: ok)
Format Video Capture:
	Width/Height      : 320/240
	Pixel Format      : 'YUYV'
	Field             : None
	Bytes per Line    : 640
	Size Image        : 153600
	Colorspace        : sRGB
	Transfer Function : Default
	YCbCr Encoding    : Default
	Quantization      : Default
	Flags             : 
Crop Capability Video Capture:
	Bounds      : Left 0, Top 0, Width 320, Height 240
	Default     : Left 0, Top 0, Width 320, Height 240
	Pixel Aspect: 1/1
Selection: crop_default, Left 0, Top 0, Width 320, Height 240
Selection: crop_bounds, Left 0, Top 0, Width 320, Height 240
Streaming Parameters Video Capture:
	Capabilities     : timeperframe
	Frames per second: 30.000 (30/1)
	Read buffers     : 0
                     brightness (int)    : min=-64 max=64 step=1 default=0 value=-42
                       contrast (int)    : min=0 max=95 step=1 default=0 value=30
                     saturation (int)    : min=0 max=100 step=1 default=64 value=64
                            hue (int)    : min=-2000 max=2000 step=1 default=0 value=0
 white_balance_temperature_auto (bool)   : default=1 value=1
                          gamma (int)    : min=100 max=300 step=1 default=100 value=300
           power_line_frequency (menu)   : min=0 max=2 default=2 value=1
      white_balance_temperature (int)    : min=2800 max=6500 step=1 default=4600 value=4554 flags=inactive
                      sharpness (int)    : min=1 max=7 step=1 default=2 value=2
         backlight_compensation (int)    : min=0 max=3 step=1 default=3 value=3

Logitech c930e

$ v4l2-ctl --device=1 --list-formats-ext
ioctl: VIDIOC_ENUM_FMT
	Index       : 0
	Type        : Video Capture
	Pixel Format: 'YUYV'
	Name        : YUYV 4:2:2
		Size: Discrete 640x480
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.042s (24.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.133s (7.500 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 160x120
...
		Size: Discrete 176x144
...
		Size: Discrete 320x180
...
		Size: Discrete 320x240
...
		Size: Discrete 352x288
...
		Size: Discrete 424x240
...
		Size: Discrete 480x270
...
		Size: Discrete 640x360
..
		Size: Discrete 800x448
...
		Size: Discrete 800x600
			Interval: Discrete 0.042s (24.000 fps)
...
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 848x480
			Interval: Discrete 0.033s (30.000 fps)
...
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 960x540
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.133s (7.500 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 1024x576
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.133s (7.500 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 1280x720
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.133s (7.500 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 1600x896
			Interval: Discrete 0.133s (7.500 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 1920x1080
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 2304x1296
			Interval: Discrete 0.500s (2.000 fps)
		Size: Discrete 2304x1536
			Interval: Discrete 0.500s (2.000 fps)

	Index       : 1
	Type        : Video Capture
	Pixel Format: 'MJPG' (compressed)
	Name        : Motion-JPEG
		Size: Discrete 640x480
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.042s (24.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.133s (7.500 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 160x120
...
		Size: Discrete 176x144
...
		Size: Discrete 320x180
..
		Size: Discrete 320x240
...
		Size: Discrete 352x288
...
		Size: Discrete 424x240
...
		Size: Discrete 480x270
...
		Size: Discrete 640x360
...
		Size: Discrete 800x448
...
		Size: Discrete 800x600
...
		Size: Discrete 848x480
...
		Size: Discrete 960x540
...
		Size: Discrete 1024x576
...
		Size: Discrete 1280x720
...
		Size: Discrete 1600x896
...
		Size: Discrete 1920x1080
...
$ v4l2-ctl -d /dev/video1 --all
Driver Info (not using libv4l2):
	Driver name   : uvcvideo
	Card type     : Logitech Webcam C930e
	Bus info      : usb-0000:00:14.0-3
	Driver version: 4.4.90
	Capabilities  : 0x84200001
		Video Capture
		Streaming
		Extended Pix Format
		Device Capabilities
	Device Caps   : 0x04200001
		Video Capture
		Streaming
		Extended Pix Format
Priority: 2
Video input : 0 (Camera 1: ok)
Format Video Capture:
	Width/Height      : 640/480
	Pixel Format      : 'YUYV'
	Field             : None
	Bytes per Line    : 1280
	Size Image        : 614400
	Colorspace        : sRGB
	Transfer Function : Default
	YCbCr Encoding    : Default
	Quantization      : Default
	Flags             : 
Crop Capability Video Capture:
	Bounds      : Left 0, Top 0, Width 640, Height 480
	Default     : Left 0, Top 0, Width 640, Height 480
	Pixel Aspect: 1/1
Selection: crop_default, Left 0, Top 0, Width 640, Height 480
Selection: crop_bounds, Left 0, Top 0, Width 640, Height 480
Streaming Parameters Video Capture:
	Capabilities     : timeperframe
	Frames per second: 30.000 (30/1)
	Read buffers     : 0
                     brightness (int)    : min=0 max=255 step=1 default=128 value=128
                       contrast (int)    : min=0 max=255 step=1 default=128 value=128
                     saturation (int)    : min=0 max=255 step=1 default=128 value=128
 white_balance_temperature_auto (bool)   : default=1 value=1
                           gain (int)    : min=0 max=255 step=1 default=0 value=0
           power_line_frequency (menu)   : min=0 max=2 default=2 value=2
      white_balance_temperature (int)    : min=2000 max=7500 step=1 default=4000 value=4000 flags=inactive
                      sharpness (int)    : min=0 max=255 step=1 default=128 value=128
         backlight_compensation (int)    : min=0 max=1 step=1 default=0 value=0
                  exposure_auto (menu)   : min=0 max=3 default=3 value=3
              exposure_absolute (int)    : min=3 max=2047 step=1 default=250 value=250 flags=inactive
         exposure_auto_priority (bool)   : default=0 value=1
                   pan_absolute (int)    : min=-36000 max=36000 step=3600 default=0 value=0
                  tilt_absolute (int)    : min=-36000 max=36000 step=3600 default=0 value=0
                 focus_absolute (int)    : min=0 max=255 step=5 default=0 value=0 flags=inactive
                     focus_auto (bool)   : default=1 value=1
                  zoom_absolute (int)    : min=100 max=400 step=1 default=100 value=100
                      led1_mode (menu)   : min=0 max=3 default=0 value=3
                 led1_frequency (int)    : min=0 max=255 step=1 default=0 value=0

@lucasw
Copy link
Author

lucasw commented Nov 5, 2017

99-usb-serial.rules

Make a camera boot up with a consistent and readable name in /dev/video

SUBSYSTEM=="video4linux", ATTRS{idVendor}=="0c45", ATTRS{idProduct}=="64d0", ENV{ID_SERIAL}=="CN0767N97248751KB15VA01_Laptop_Integrated_Webcam_HD", SYMLINK+="video_front"
$ udevadm info -a -p $(udevadm info -q path -n /dev/video0) | grep "looking at device"
  looking at device '/devices/pci0000:00/0000:00:1a.0/usb1/1-1/1-1.5/1-1.5:1.0/video4linux/video0':
udevadm test /devices/pci0000:00/0000:00:1a.0/usb1/1-1/1-1.5/1-1.5:1.0/video4linux/video0 | grep ID_SERIAL
...
ID_SERIAL=CN0767N97248751KB15VA01_Laptop_Integrated_Webcam_HD

USB location without serial number

Not all usb devices have unique serial numbers though, but there is a USB path like pci-0000:00:14.0-usb-0:3:1.1

SUBSYSTEM=="video4linux", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", ENV{ID_PATH}=="pci-0000:00:14.0-usb-0:3:1.1", SYMLINK+="video_left"
udevadm test "$(udevadm info -q path -n /dev/video0)" 2>/dev/null | grep ID_PATH | head -n 1 | cut -c 9-
pci-0000:00:1a.0-usb-0:1.5:1.0

@lucasw
Copy link
Author

lucasw commented Nov 12, 2017

USB Hub with individual power switching

USB hub that allows power cycling individual usb ports- may be critical to power cycle a crashed camera without having to reboot the entire motherboard, restart the robot.

hub-ctrl (TODO make ROS version of this)
https://github.com/yy502/hub-ctrl - is this the best version? Several forks with different changes.

Not easy to find if hub has individual power switching capability.
If you have a bunch of different usb hubs, try them all (and publish your results if you find one that works).

https://github.com/mvp/uhubctl has a list of compatible hubs.

@lucasw
Copy link
Author

lucasw commented Nov 12, 2017

Publishing ROS Images to V4L

In Ubuntu 16.04

sudo apt install v4l2loopback-utils

https://github.com/lucasw/ros-virtual-cam

rosrun usb_cam usb_cam_node _image_width:=1280 _image_height:=720 _framerate:=5 _video_device:=/dev/video0 _pixel_format:=yuyv
sudo modprobe v4l2loopback video_nr=1
rosrun virtual_cam stream _device:=/dev/video1 _width:=1280 _height:=720 _fourcc:=YV12 image:=/usb_cam/image_raw
guvcview /dev/video1  # then select the dummy device

Cheese crashes when trying to view the republished stream, so virtual cam probably isn't working fully.

expected output:

[ INFO] [/stream_1510492700449845915] [/home/lucasw/catkin_ws/src/ros-virtual-cam/src/stream.cpp]:[90] [converting - width=1280, height=720, fourcc=YV12]
[ INFO] [/stream_1510492700449845915] [/home/lucasw/catkin_ws/src/ros-virtual-cam/src/stream.cpp]:[100] [opening '/dev/video1']
[ INFO] [/stream_1510492700449845915] [/home/lucasw/catkin_ws/src/ros-virtual-cam/src/stream.cpp]:[103] [setting '/dev/video1' format]
[ INFO] [/stream_1510492700449845915] [/home/lucasw/catkin_ws/src/ros-virtual-cam/src/video_device.cpp]:[111] [video device format:
  type                =2
  fmt.pix.width       =1280
  fmt.pix.height      =720
  fmt.pix.pixelformat =842094169
  fmt.pix.sizeimage   =1384448
  fmt.pix.field       =1
  fmt.pix.bytesperline=1280
  fmt.pix.colorspace  =8]
[ INFO] [/stream_1510492700449845915] [/home/lucasw/catkin_ws/src/ros-virtual-cam/src/stream.cpp]:[110] [turn on '/dev/video1' streaming]
[ INFO] [/stream_1510492700449845915] [/home/lucasw/catkin_ws/src/ros-virtual-cam/src/stream.cpp]:[121] ['/dev/video1' caps 0x85208001]
[ INFO] [/stream_1510492700449845915] [/home/lucasw/catkin_ws/src/ros-virtual-cam/src/stream.cpp]:[130] [streaming images from '/usb_cam/image_raw' to '/dev/video1' w/ queue-size=1]

If you get:

[ERROR] [/stream_1510492584402053642] [/home/lucasw/catkin_ws/src/ros-virtual-cam/src/video_device.cpp]:[17] [open('/dev/video1') failed - errno=2 ('No such file or directory')]
terminate called after throwing an instance of 'std::runtime_error'
  what():  open('/dev/video1') failed - errno=2 ('No such file or directory')

Then v4l2loopback isn't working or there is a device number mismatch.

@lucasw
Copy link
Author

lucasw commented Nov 12, 2017

usb_cam

uvc_cam works worse, stick with usb_cam.
Though it is still an orphan package- I believe the current status is that a maintainer is releasing new versions into new versions of ROS, but they aren't reviewing and merging pull-requests (due to lack of time/expertise), e.g. if you care about image timestamps ros-drivers/usb_cam#76 - maybe someone will sweep through the PRs prior to the next major ROS release.

https://github.com/ros-drivers/usb_cam

$ rosrun usb_cam usb_cam_node _image_width:=1920 _image_height:=1080 _framerate:=5 _video_device:=/dev/video1 _pixel_format:=yuyv
[ INFO] [/usb_cam] [/home/lucasw/catkin_ws/src/image_common/camera_info_manager/src/camera_info_manager.cpp]:[227] [using default calibration URL]
[ INFO] [/usb_cam] [/home/lucasw/catkin_ws/src/image_common/camera_info_manager/src/camera_info_manager.cpp]:[220] [camera calibration URL: file:///home/lucasw/.ros/camera_info/head_camera.yaml]
[ INFO] [/usb_cam] [/home/lucasw/catkin_ws/src/image_common/camera_calibration_parsers/src/parse_yml.cpp]:[231] [Unable to open camera calibration file [/home/lucasw/.ros/camera_info/head_camera.yaml]]
[ WARN] [/usb_cam] [/home/lucasw/catkin_ws/src/image_common/camera_info_manager/src/camera_info_manager.cpp]:[293] [Camera calibration file /home/lucasw/.ros/camera_info/head_camera.yaml not found.]
[ INFO] [/usb_cam] [/home/lucasw/catkin_ws/src/usb_cam/nodes/usb_cam_node.cpp]:[138] [Starting 'head_camera' (/dev/video1) at 1920x1080 via mmap (yuyv) at 5 FPS]

MJPG -> mjpeg

Notice that v4l2-ctl may show that resolutions and framerates are different in mjpg than other modes.

rosrun usb_cam usb_cam_node _image_width:=1280 _image_height:=720 _framerate:=15 _video_device:=/dev/video0 _pixel_format:=mjpeg

Annoying error output can be fixed:

[swscaler @ 0xa92ea0] deprecated pixel format used, make sure you did set range correctly

ros-drivers/usb_cam#67

@lucasw
Copy link
Author

lucasw commented Nov 12, 2017

uvc_cam

sudo apt install ros-kinetic-libuvc-camera

https://github.com/ros-drivers/libuvc_ros

http://wiki.ros.org/libuvc_camera

Under Linux, the user that runs camera_node must have write permissions to the /dev/bus/usb/... device that corresponds to the camera. You may run the node as root... However, use of udev rules is recommended. In /etc/udev/rules.d/99-uvc.rules, to give every user camera access:

Ugly!

Try to use rqt dynamic reconfigure:

Traceback (most recent call last):
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rqt_reconfigure/node_selector_widget.py", line 275, in _selection_changed_slot
    self._selection_selected(index_current, rosnode_name_selected)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rqt_reconfigure/node_selector_widget.py", line 225, in _selection_selected
    item_widget = item_child.get_dynreconf_widget()
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rqt_reconfigure/treenode_qstditem.py", line 154, in get_dynreconf_widget
    self._param_name_raw)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rqt_reconfigure/dynreconf_client_widget.py", line 86, in __init__
    self.reconf.config_callback = self.config_callback
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/dynamic_reconfigure/client.py", line 271, in set_config_callback
    self._config_callback(self.config)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rqt_reconfigure/dynreconf_client_widget.py", line 109, in config_callback
    widget.update_value(config[widget.param_name])
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rqt_reconfigure/param_editors.py", line 439, in update_value
    self._update_signal.emit(self.values.index(value))
ValueError: 2016960872 is not in list

@lucasw
Copy link
Author

lucasw commented Nov 12, 2017

Video capture cards

If a video capture card/usb device appears in /dev/video and cheese can view it, then usb_cam can use it also.

De-interlacing isn't supported, so plugging in old NTSC video sources won't get recorded that well.

There are also hdmi capture cards also.

@lucasw
Copy link
Author

lucasw commented Nov 12, 2017

Audio

audio_common

Not super robust- have had some experience with it working for a while, then crashing

gstreamer seems solid but also difficult to use properly.

@lucasw
Copy link
Author

lucasw commented Jan 19, 2018

Web Video Server

web_video_server

@lucasw
Copy link
Author

lucasw commented Jan 19, 2018

Calibration

Forward distortion demo

roslaunch vimjay distort.launch

camera calibrator demo

Camera calibrator lacks a lot of features, doesn't give a lot of information about quality of calibration.

There needs to be a white border around the pattern:

4x7:

chessboard_4x7

6x8:

chessboard_6x8

Gimp can generate chessboards Filters | Render | Pattern | Checkerboard... (don't use 'psychobilly)

The size is the number of squares in each direction -1, which is the number of intersections.

rosrun usb_cam usb_cam_node _image_width:=1280 _image_height:=720 _framerate:=15 _video_device:=/dev/video0 _pixel_format:=mjpeg
rosrun camera_calibration cameracalibrator.py --size 7x4 --square 0.10 image:=/usb_cam/image_raw camera:=/usb_cam

The square size doesn't matter.

Built-in camera is too blurry to use phone chessboard.

roslaunch vimjay webcam.launch
rosrun camera_calibration cameracalibrator.py --size 7x4 --square 0.10 image:=/usb_cam/image_raw camera:=/usb_cam

Each time the chessboard is successfully observed stdout will indicate:

...
*** Added sample 44, p_x = 0.411, p_y = 0.676, p_size = 0.206, skew = 0.144
*** Added sample 45, p_x = 0.250, p_y = 0.915, p_size = 0.329, skew = 0.282
*** Added sample 46, p_x = 0.275, p_y = 0.789, p_size = 0.502, skew = 0.401
*** Added sample 47, p_x = 0.248, p_y = 0.610, p_size = 0.481, skew = 0.458
*** Added sample 48, p_x = 0.477, p_y = 0.498, p_size = 0.489, skew = 0.684
...

camera_calibrator_with_phone_chessboard

Once the calibrator tool has determined enough coverage over the entire image and skew (rotation of the chessboard relative to the camera) has been observed the calibration button will be enabled.
Once it is pressed the application appears to lock up, but it is intensively processing the data and should produce stdout within a minute or two:

6x8 calibration output:

[image]

width
1920

height
1080

[narrow_stereo]

camera matrix
1201.788359 0.000000 922.051660
0.000000 1202.865472 562.699342
0.000000 0.000000 1.000000

distortion
0.081045 -0.147135 0.000397 -0.000847 0.000000

rectification
1.000000 0.000000 0.000000
0.000000 1.000000 0.000000
0.000000 0.000000 1.000000

projection
1188.404541 0.000000 913.190395 0.000000
0.000000 1216.601807 563.099257 0.000000
0.000000 0.000000 1.000000 0.000000


('Wrote calibration data to', '/tmp/calibrationdata.tar.gz')

Inside the tar.gz are all the images that contributed to the calibration, plus an ost.yaml file and ost.txt each with the same info as above, the yaml formatted differently:

image_width: 1920
image_height: 1080
camera_name: narrow_stereo
camera_matrix:
  rows: 3
  cols: 3
  data: [1201.788359, 0.000000, 922.051660, 0.000000, 1202.865472, 562.699342, 0.000000, 0.000000, 1.000000]
distortion_model: plumb_bob
distortion_coefficients:
  rows: 1
  cols: 5
  data: [0.081045, -0.147135, 0.000397, -0.000847, 0.000000]
rectification_matrix:
  rows: 3
  cols: 3
  data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]
projection_matrix:
  rows: 3
  cols: 4
  data: [1188.404541, 0.000000, 913.190395, 0.000000, 0.000000, 1216.601807, 563.099257, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]

The yaml can then be supplied to camera info manager nodes (like camera nodes - TBD usb_cam) which will then output the same parameters in the camera_info:

$ rostopic echo /usb_cam/camera_info
header: 
  seq: 106
  stamp: 
    secs: 1516338849
    nsecs: 791569527
  frame_id: "head_camera"
height: 1080
width: 1920
distortion_model: "plumb_bob"
D: [0.081045, -0.147135, 0.000397, -0.000847, 0.0]
K: [1201.788359, 0.0, 922.05166, 0.0, 1202.865472, 562.699342, 0.0, 0.0, 1.0]
R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
P: [1188.404541, 0.0, 913.190395, 0.0, 0.0, 1216.601807, 563.099257, 0.0, 0.0, 0.0, 1.0, 0.0]
binning_x: 0
binning_y: 0
roi: 
  x_offset: 0
  y_offset: 0
  height: 0
  width: 0
  do_rectify: False
---
...

There is one camera_info for every Image published.

One failing of camera calibrator is that if a low quality image is captured, there isn't a way to identify it as a problem and eliminate it and reprocess the calibration input images.

One indicator of consistency is to do multiple calibrations and make sure the parameters don't change much

rectify the image

(when camera_info has the calibration in it)

rosrun image_proc image_proc __ns:=/usb_cam

camera check

the image_rect needs to be available:

rosrun camera_calibration cameracheck.py --size 8x6 stereo:=/wide_stereo image:=image_rect  __ns:=/usb_cam
...
no chessboard
no chessboard
Linearity RMS Error: 0.271 Pixels      Reprojection RMS Error: 0.382 Pixels
no chessboard
no chessboard
...

more

http://wiki.ros.org/camera_calibration

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment