xiaoqiang tutorial (21) get USB camera 30fps 1080p image stream and 120fps VGA resolution image stream

Xiaoqiang Homepage

Xiaoqiang's default USB camera node publishes a 30fps VGA (640*480) image stream that can satisfy most visual tasks. The USB camera hardware can actually output 120fps VGA image stream and up to 30fps 1080p image stream. This article will introduce how to obtain these two type of the image.

1.Upgrade usb_cam node source code

Taking into account the USB2.0 bandwidth, output 120fps VGA video and 30fps 1080p video, need to use mjpeg format. For Xiaoqiang's own USB camera ROS driver package usb_cam, it can not read Xiaoqiang usb camera in mjpeg way, so we need to upgrade usb_cam first. For the upgrade method, please refer to this post

2.Test 120fps VGA video output

First please turn off Xiaoqiang's startup task

sudo service startup stop

Modify the contents of the ov2610mjpg.launch file in the usb_cam package as shown below

<launch>
  <node name="camera_node" pkg="usb_cam" type="usb_cam_node">
    <param name="video_device" value="/dev/video0" />
    <param name="image_width" value="640" />
    <param name="image_height" value="480" />
    <param name="framerate" value="120" />  
    <param name="pixel_format" value="mjpeg" />
    <param name="camera_frame_id" value="ov2610" />
    <param name="io_method" value="mmap"/>
  </node>
</launch>

Launch the above launch file

roslaunch usb_cam ov2610mjpg.launch

Open a new window to print the published image topic frame rate

rostopic hz /camera_node/image_raw

Normal output similar to the following figure

subscribed to [/camera_node/image_raw]
average rate: 99.497
    min: 0.004s max: 0.016s std dev: 0.00246s window: 98
average rate: 99.324
    min: 0.004s max: 0.016s std dev: 0.00240s window: 198
average rate: 99.385
    min: 0.004s max: 0.016s std dev: 0.00236s window: 297
average rate: 99.247
    min: 0.004s max: 0.016s std dev: 0.00236s window: 396
average rate: 99.302
    min: 0.004s max: 0.016s std dev: 0.00232s window: 495
average rate: 99.296
    min: 0.004s max: 0.016s std dev: 0.00231s window: 595
average rate: 99.249
    min: 0.004s max: 0.016s std dev: 0.00230s window: 694

The above output shows that the camera frame rate is about 99fps and does not reach 120fps. This is due to the influence of ambient light, which can reach 120 frames if the ambient light is sufficient.

2.Test 1080p video output at 30fps

First please stop Xiaoqiang's startup service

sudo service startup stop

Modify the contents of the ov2610mjpg.launch file in the usb_cam package as shown below.

<launch>
  <node name="camera_node" pkg="usb_cam" type="usb_cam_node">
    <param name="video_device" value="/dev/video0" />
    <param name="image_width" value="1920" />
    <param name="image_height" value="1080" />
    <param name="framerate" value="30" />  
    <param name="pixel_format" value="mjpeg" />
    <param name="camera_frame_id" value="ov2610" />
    <param name="io_method" value="mmap"/>
  </node>
</launch>

Launch the above launch file

roslaunch usb_cam ov2610mjpg.launch

Open a new window to print the published image topic frame rate.

rostopic hz /camera_node/image_raw

Normal output similar to the following figure.

xiaoqiang@xiaoqiang-desktop:~$ rostopic hz /camera_node/image_raw
subscribed to [/camera_node/image_raw]
average rate: 29.986
    min: 0.028s max: 0.039s std dev: 0.00318s window: 30
average rate: 29.917
    min: 0.028s max: 0.039s std dev: 0.00296s window: 59
average rate: 29.912
    min: 0.028s max: 0.039s std dev: 0.00292s window: 89
average rate: 29.853
    min: 0.027s max: 0.042s std dev: 0.00308s window: 119
average rate: 29.874
    min: 0.027s max: 0.042s std dev: 0.00283s window: 149
average rate: 29.839
    min: 0.027s max: 0.042s std dev: 0.00282s window: 179
average rate: 29.849
    min: 0.027s max: 0.042s std dev: 0.00282s window: 202

Xiaoqiang Homepage Back To Index

results matching ""

    No results matching ""