ヴェズルフェルニルの研究ノート

座右の銘「ただ一人犀の角のように歩め」的な研究活動ノート

【ROS】libuvc_camera | フォーマット指定でのカメラ映像取得

前記事でlibuvc_cameraパッケージを利用してROS上でのUVCカメラの映像取得を行ったが、そこでは、カメラに対する映像フォーマットなどのパラメータ指定はしていなかった。

blog.ketus-ix.work

前記事の操作によって取得されるカメラ映像の解像度サイズは640x480ピクセルになっている。また、カメラ映像取得動作中に、rostopic hz /image_rawコマンドによってフレームレートを調べてみると、下のように15fps程度の転送速度しか出ていないことが判る。

$ rostopic hz /image_raw
subscribed to [/image_raw]
average rate: 15.036
    min: 0.059s max: 0.070s std dev: 0.00279s window: 14
average rate: 14.959
    min: 0.059s max: 0.070s std dev: 0.00224s window: 29
average rate: 14.967
    min: 0.059s max: 0.070s std dev: 0.00211s window: 44
average rate: 14.958
    min: 0.059s max: 0.070s std dev: 0.00199s window: 59
average rate: 14.950
    min: 0.059s max: 0.070s std dev: 0.00193s window: 74
....    ....
....    ....

この結果は、libuvc_cameraによるデフォルトのカメラ映像設定パラメータがこれらの値に固定されているからだと思われる。

そこで、libuvc_cameraによるROS上でのフォーマットパラメータしてカメラ映像を取得することを試みてみた。

UVCカメラ映像フォーマットの調査

対象のUVCカメラが対応している映像フォーマット情報を調べる必要がある。

まずは、lsusbコマンドによって、対象カメラのidProductidVendorの値(ID 046d:081bの箇所)を特定する。

$ lsusb
Bus 001 Device 003: ID 046d:081b Logitech, Inc. Webcam C310
Bus 001 Device 002: ID 203a:fffc  
Bus 001 Device 001: ID 1d6b:0002 Linux Foundation 2.0 root hub
Bus 004 Device 003: ID 203a:fff9  
Bus 004 Device 002: ID 203a:fff9  
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 002 Device 001: ID 1d6b:0001 Linux Foundation 1.1 root hub

その後、デバイスファイル/dev/video*の存在を確認する。

$ ls /dev/video*
/dev/video0  /dev/video1  /dev/video2  /dev/video3  /dev/video4  /dev/video5

そして、すべてのデバイスファイルに対してudevadm info --name=/dev/videoX --attribute-walkコマンドを順番に実行する。

$ udevadm info --name=/dev/video4 --attribute-walk

Udevadm info starts with the device specified by the devpath and then
walks up the chain of parent devices. It prints for every device
found, all possible attributes in the udev rules key format.
A rule to match, can be composed by the attributes of the device
and the attributes from one single parent device.

  looking at device '/devices/pci0000:00/0000:00:1d.7/usb1/1-11/1-11:1.0/video4linux/video4':
    KERNEL=="video4"
    SUBSYSTEM=="video4linux"
    DRIVER==""
    ATTR{dev_debug}=="0"
    ATTR{index}=="0"
    ATTR{name}=="UVC Camera (046d:081b)"

  looking at parent device '/devices/pci0000:00/0000:00:1d.7/usb1/1-11/1-11:1.0':
    KERNELS=="1-11:1.0"
    SUBSYSTEMS=="usb"
    DRIVERS=="uvcvideo"
    ATTRS{authorized}=="1"
    ATTRS{bAlternateSetting}==" 0"
    ATTRS{bInterfaceClass}=="0e"
    ATTRS{bInterfaceNumber}=="00"
    ATTRS{bInterfaceProtocol}=="00"
    ATTRS{bInterfaceSubClass}=="01"
    ATTRS{bNumEndpoints}=="01"
    ATTRS{iad_bFirstInterface}=="00"
    ATTRS{iad_bFunctionClass}=="0e"
    ATTRS{iad_bFunctionProtocol}=="00"
    ATTRS{iad_bFunctionSubClass}=="03"
    ATTRS{iad_bInterfaceCount}=="02"
    ATTRS{supports_autosuspend}=="1"

  looking at parent device '/devices/pci0000:00/0000:00:1d.7/usb1/1-11':
    KERNELS=="1-11"
    SUBSYSTEMS=="usb"
    DRIVERS=="usb"
    ATTRS{authorized}=="1"
    ATTRS{avoid_reset_quirk}=="0"
    ATTRS{bConfigurationValue}=="1"
    ATTRS{bDeviceClass}=="ef"
    ATTRS{bDeviceProtocol}=="01"
    ATTRS{bDeviceSubClass}=="02"
    ATTRS{bMaxPacketSize0}=="64"
    ATTRS{bMaxPower}=="500mA"
    ATTRS{bNumConfigurations}=="1"
    ATTRS{bNumInterfaces}==" 4"
    ATTRS{bcdDevice}=="0012"
    ATTRS{bmAttributes}=="80"
    ATTRS{busnum}=="1"
    ATTRS{configuration}==""
    ATTRS{devnum}=="3"
    ATTRS{devpath}=="11"
    ATTRS{idProduct}=="081b"
    ATTRS{idVendor}=="046d"
    ATTRS{ltm_capable}=="no"
    ATTRS{maxchild}=="0"
    ATTRS{quirks}=="0x2"
    ATTRS{removable}=="unknown"
    ATTRS{rx_lanes}=="1"
    ATTRS{serial}=="F941C3A0"
    ATTRS{speed}=="480"
    ATTRS{tx_lanes}=="1"
    ATTRS{urbnum}=="5068"
    ATTRS{version}==" 2.00"

  looking at parent device '/devices/pci0000:00/0000:00:1d.7/usb1':
    KERNELS=="usb1"
    SUBSYSTEMS=="usb"
    DRIVERS=="usb"
    ATTRS{authorized}=="1"
    ATTRS{authorized_default}=="1"
    ATTRS{avoid_reset_quirk}=="0"
    ATTRS{bConfigurationValue}=="1"
    ATTRS{bDeviceClass}=="09"
    ATTRS{bDeviceProtocol}=="00"
    ATTRS{bDeviceSubClass}=="00"
    ATTRS{bMaxPacketSize0}=="64"
    ATTRS{bMaxPower}=="0mA"
    ATTRS{bNumConfigurations}=="1"
    ATTRS{bNumInterfaces}==" 1"
    ATTRS{bcdDevice}=="0504"
    ATTRS{bmAttributes}=="e0"
    ATTRS{busnum}=="1"
    ATTRS{configuration}==""
    ATTRS{devnum}=="1"
    ATTRS{devpath}=="0"
    ATTRS{idProduct}=="0002"
    ATTRS{idVendor}=="1d6b"
    ATTRS{interface_authorized_default}=="1"
    ATTRS{ltm_capable}=="no"
    ATTRS{manufacturer}=="Linux 5.4.0-150-generic ehci_hcd"
    ATTRS{maxchild}=="15"
    ATTRS{product}=="EHCI Host Controller"
    ATTRS{quirks}=="0x0"
    ATTRS{removable}=="unknown"
    ATTRS{rx_lanes}=="1"
    ATTRS{serial}=="0000:00:1d.7"
    ATTRS{speed}=="480"
    ATTRS{tx_lanes}=="1"
    ATTRS{urbnum}=="67"
    ATTRS{version}==" 2.00"

  looking at parent device '/devices/pci0000:00/0000:00:1d.7':
    KERNELS=="0000:00:1d.7"
    SUBSYSTEMS=="pci"
    DRIVERS=="ehci-pci"
    ATTRS{ari_enabled}=="0"
    ATTRS{broken_parity_status}=="0"
    ATTRS{class}=="0x0c0320"
    ATTRS{companion}==""
    ATTRS{consistent_dma_mask_bits}=="32"
    ATTRS{d3cold_allowed}=="0"
    ATTRS{device}=="0x265c"
    ATTRS{dma_mask_bits}=="32"
    ATTRS{driver_override}=="(null)"
    ATTRS{enable}=="1"
    ATTRS{irq}=="19"
    ATTRS{local_cpulist}=="0-3"
    ATTRS{local_cpus}=="0000000f"
    ATTRS{msi_bus}=="1"
    ATTRS{numa_node}=="-1"
    ATTRS{revision}=="0x02"
    ATTRS{subsystem_device}=="0x0400"
    ATTRS{subsystem_vendor}=="0x1ab8"
    ATTRS{uframe_periodic_max}=="100"
    ATTRS{vendor}=="0x8086"

  looking at parent device '/devices/pci0000:00':
    KERNELS=="pci0000:00"
    SUBSYSTEMS==""
    DRIVERS==""
  

上の出力情報中のATTRS{idProduct}=="081b"ATTRS{idVendor}=="046d"から、この/dev/video4が対象カメラのデバイスファイルであることが判る。

バイスファイルが特定できたら、v4l2-ctl --list-formats-ext -d /dev/videoXコマンドによって対象カメラの対応フォーマット情報を知ることができる。

$ v4l2-ctl --list-formats-ext -d /dev/video4
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.040s (25.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.200s (5.000 fps)
        Size: Discrete 160x120
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 176x144
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 320x176
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 320x240
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 352x288
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 432x240
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 544x288
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 640x360
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 752x416
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 800x448
            Interval: Discrete 0.050s (20.000 fps)
            Interval: Discrete 0.067s (15.000 fps)
            Interval: Discrete 0.100s (10.000 fps)
            Interval: Discrete 0.200s (5.000 fps)
        Size: Discrete 800x600
            Interval: Discrete 0.050s (20.000 fps)
            Interval: Discrete 0.067s (15.000 fps)
            Interval: Discrete 0.100s (10.000 fps)
            Interval: Discrete 0.200s (5.000 fps)
        Size: Discrete 864x480
            Interval: Discrete 0.050s (20.000 fps)
            Interval: Discrete 0.067s (15.000 fps)
            Interval: Discrete 0.100s (10.000 fps)
            Interval: Discrete 0.200s (5.000 fps)
        Size: Discrete 960x544
            Interval: Discrete 0.067s (15.000 fps)
            Interval: Discrete 0.100s (10.000 fps)
            Interval: Discrete 0.200s (5.000 fps)
        Size: Discrete 960x720
            Interval: Discrete 0.100s (10.000 fps)
            Interval: Discrete 0.200s (5.000 fps)
        Size: Discrete 1024x576
            Interval: Discrete 0.100s (10.000 fps)
            Interval: Discrete 0.200s (5.000 fps)
        Size: Discrete 1184x656
            Interval: Discrete 0.100s (10.000 fps)
            Interval: Discrete 0.200s (5.000 fps)
        Size: Discrete 1280x720
            Interval: Discrete 0.133s (7.500 fps)
            Interval: Discrete 0.200s (5.000 fps)
        Size: Discrete 1280x960
            Interval: Discrete 0.133s (7.500 fps)
            Interval: Discrete 0.200s (5.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.040s (25.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.200s (5.000 fps)
        Size: Discrete 160x120
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 176x144
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 320x176
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 320x240
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 352x288
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 432x240
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 544x288
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 640x360
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 752x416
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 800x448
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 800x600
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 864x480
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 960x544
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 960x720
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 1024x576
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 1184x656
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 1280x720
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
        Size: Discrete 1280x960
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.040s (25.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.200s (5.000 fps)
  

映像フォーマット指定でのUVCカメラ映像取得

ROSワークスペースを利用して、UVCカメラ映像取得処理をバッケージ化してしまおう。

$ cd ~/catkin_ws/src
$ catkin create pkg my_camera --catkin-deps libuvc_camera
$ mkdir my_camera/launch
$ vi my_camera/launch/uvc_camera.launch

以下のようなXML形式ファイルを作成し、この中でカメラの映像取得パラメータを指定する。

  • ~/catkin_ws/src/my_camera/launch/uvc_camera.launch
<?xml version="1.0"?>
<launch>
  <node pkg="libuvc_camera" type="camera_node" name="my_camera">
    <param name="width" value="1280"/>
    <param name="height" value="720"/>
    <param name="frame_rate" value="30"/>
    <param name="video_mode" value="mjpeg"/>
  </node>
  <node name="image_view" pkg="image_view" type="image_view" >
    <remap from="image" to="/image_raw"/>
  </node>
</launch>
  • width : 出力映像イメージの横幅ピクセルサイズ
  • height : 出力映像イメージの縦幅ピクセルサイズ
  • frame_rate : 出力映像イメージのフレームレート
  • video_mode : 出力映像イメージのフォーマット

これらの値は前述のカメラの対応フォーマット出力情報のいずれかのモードの値と一致していなければならない。

上の操作が済んだら、下のコマンドを実行すればバッケージを作成できる。

$ catkin build

パッケージが作成できたら、下のコマンドを実行すれば、そのプログラムを起動できる。

$ source ~/catkin_ws/devel/setup.bash
$ roslaunch my_camera uvc_camera.launch

本プログラムが起動すると、下のような1280x720サイズのカメラ映像ウィンドウが表示される。

本プログラムの動作中に、再度rostopic hz /image_rawコマンドによってフレームレートを調べると、今度は30fps程度の転送速度が出ていることが確認できる。

$ rostopic hz /image_raw
subscribed to [/image_raw]
average rate: 30.283
    min: 0.025s max: 0.043s std dev: 0.00374s window: 28
average rate: 30.015
    min: 0.025s max: 0.043s std dev: 0.00288s window: 58
average rate: 29.927
    min: 0.025s max: 0.043s std dev: 0.00272s window: 88
average rate: 29.881
    min: 0.025s max: 0.043s std dev: 0.00263s window: 118
average rate: 29.880
    min: 0.025s max: 0.043s std dev: 0.00250s window: 148
....    ....
....    ....

【参照サイト】

qiita.com

msadowski.github.io