Meanwhile ROS appears to have the opposite problem, with multiple developers writing drivers that perform the same basic tasks. I suppose it's better to have too many options than too few but figuring out which driver to use can take some time. So to save you time and energy we will be testing and rating various ROS drivers to save you time and energy.
This week we are testing USB camera drivers for performance and functionality.
Here are the options we are testing.
Probe
The probe driver, from the Brown Robotics Group, uses GStreamer to broadcast data to an image topic. The upside of this is that it is very flexible and it is easy to connect to just about any camera. It can also be used to connect to more than just cameras, for example with the right incantations it can be used to connect to things like mjpeg streams sent over http.
On the downside, figuring out the right incantations to get anything to work can take a while. One option is to launch the driver from a terminal, which may make it easier to get GStreamer setup.
$ export PROBE_CONFIG="v4l2src device=/dev/video1 ! video/x-raw-rgb, width=320, height=240, framerate=30/1 ! ffmpegcolorspace ! identity name=ros ! fakesink" $ rosrun probe probe
probe launch file
<launch> <env name="PROBE_CONFIG" value="v4l2src device=/dev/video1 ! video/x-raw-rgb, width=320, height=240, framerate=30/1 ! ffmpegcolorspace ! identity name=ros ! fakesink" /> <node name="probe" pkg="probe" type="probe" respawn="false" output="screen"/> </launch>
usb_cam
Developed by the Bosch Research and Technology Center for their Segway RMP based robot, the usb_cam driver offers good performance and reasonable configuration options. It is also the only driver considered that currently support the camera_info topic. Unfortunately it doesn't support saving the calibration to a file via set_camera_info. So tricking the camera calibration process into working in the boxturtle release requires editing the source.
~/ros/stacks/image_pipeline/camera_calibration/nodes/cameracalibrator.py
... class CalibrationNode: def __init__(self, chess_size, dim): # assume any non-default service names have been set. Wait for the service to become ready # for svcname in ["camera", "left_camera", "right_camera"]: for svcname in ["left_camera", "right_camera"]: remapped = rospy.remap_name(svcname) if remapped != svcname: fullservicename = "%s/set_camera_info" % remapped ...
usb_cam launch file
<launch> <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" > <param name="video_device" value="/dev/video1" /> <param name="image_width" value="640" /> <param name="image_height" value="480" /> <param name="pixel_format" value="yuyv" /> <param name="camera_frame_id" value="usb_cam" /> <param name="io_method" value="mmap"/> <rosparam param="D">[0.032095, -0.238155, 0.000104, -0.002138, 0.0000] <rosparam param="K">[723.715912, 0.000000, 318.180121, 0.000000, 719.919423, 280.697379, 0.000000, 0.000000, 1.000000] <rosparam param="R">[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] <rosparam param="P">[723.715912, 0.000000, 318.180121, 0.000000, 0.000000, 719.919423, 280.697379, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000] </node> </launch>
uvc_cam
Developed at the Stanford AI Lab, the uvc_cam driver may not have the highest performance but it seems to have more of the camera controls implemented. It also has some interesting support tools included, including a program that can be used to enumerate the available camera devices.
uvc_cam launch file
<launch> <node name="uvc_cam" pkg="uvc_cam" type="senderIT" output="screen" > <param name="device" value="/dev/video1" /> <param name="topic" value="/camera/image" /> <param name="width" value="640" /> <param name="height" value="480" /> <param name="fps" value="30" /> </node> </launch>
gencam_cu
Over at Colorado University they have developed the gencam_cu driver. This driver uses OpenCV to access the camera. The driver has pretty good performance however there appears to be no way to configure the resolution. It does however support compressed_image_transport which is convenient.
gencam_cu launch file
<launch> <node name="gencam_cu" pkg="gencam_cu" type="gencam_cu" output="screen" > <param name="camera_index" value="1" /> </node> </launch>
logitech_usb_webcam
Actually, this isn't another driver, it's just some launch files that work with usb_cam.
USB Ports
While it may seem like all USB ports are the same, depending on the bus topology and USB version, each USB port may provide vastly different performance. In some configurations testing showed a significant difference, with one USB port capable of providing 15 frames per second while another port provided 30 frames per second. You would think that two ports adjacent to each other would be on the same bus, but apparently not.
Performance
High resolution images at high frame rates tend to pin the CPU at 100% or more, which doesn't particularly make sense but that is software for you. There are probably some low hanging fruit in terms of optimizations, however they may be deep within the V4L2 stack. Profiling and optimization is left for those whose projects depend on it.
PID USER PR NI VIRT RES SHR S %CPU %MEM TIME+ COMMAND 1234 user 20 0 117m 34m 8992 R 110 1.7 0:23.92 probe
Camera Calibration
Out of all of these drivers, only the usb_cam driver currently supports the camera_info topic. Without this information, image rectification using image_proc will not work unless you write your own camera_info publisher. Fortunately the camera_info_manager support class appears to be shipping with the next stable release of ROS. This should help camera driver developers implement the camera_info topic consistently and improve the camera calibration process.
Cameras Tested
The following cameras were tested at 640x480 and 320x240 with 24 bit color. Most modern USB cameras that support the USB Video Class (UVC) interface should work.
- Logitech C600
- Logitech Quickcam 9000 Pro
- Built-in Laptop OmniVision OV2640 Webcam
Testing
For all of these tests, image_view is run at the same time as the camera driver to produce a simulated load and to ensure that the video is actually being transmitted.
Combo launch file
<launch> <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" > <param name="video_device" value="/dev/video1" /> <param name="image_width" value="320" /> <param name="image_height" value="240" /> <param name="pixel_format" value="mjpeg" /> <param name="camera_frame_id" value="usb_cam" /> <param name="io_method" value="mmap"/> </node> <node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen"> <remap from="image" to="/usb_cam/image_raw"/> </node> </launch>
The rostopic command is used to measure the update frequency of the camera image messages.
$ rostopic hz --window=1000 /image_raw
Results
320x240 C600 9000 Pro OV2640 Probe 29.942 29.945 15.006 usb_cam 30.035 30.036 7.503 uvc_cam 25.082 24.077 15.006
640x480 C600 9000 Pro OV2640 Probe 11.914 12.373 12.807 usb_cam 15.068 15.026 10.005 uvc_cam 12.651 12.851 8.267 gencam_cu 14.711 14.974 7.503
Conclusion
Overall each driver contains features and ideas not found in other drivers. Moving forward it would probably be in everyone's interest to focus on improving the performance of one of the drivers and to incorporate the best ideas from the other drivers. The usb_cam driver looks to be the best supported and may be an ideal starting point, however the bsd license may be a minor issue for some.
If you are trying to get a USB camera working with ROS, it is suggested that you start with the usb_cam driver and if that doesn't work for you, try one of the other drivers.
If you don't have ROS installed, instructions are here and if you have time I strongly suggest trying the tutorials. Now would be a great time to get ROS setup because later this week we will be showing you how to connect OpenCV to ROS to perform actual practical robotics tasks.
10 comments:
Excellent work, thanks for this information! It's definitely something I've wondered about.
-Fergs
While we believe these numbers should be generally correct. Additional testing has shown that the frame rate is often sensitive to lighting conditions.
Our testing methodology will be corrected for future reviews. Expect an update as we get closer to the C-Turtle release.
The point about USB ports is significant. It is always best to have a map of your USB ports with their internal hub structure and all connected devices. Watch out for internal connected devices on USB (sound, bluetooth, ...).The integral CPU USB controllers( often more than one) and internal hubs (usually present) are normally high speed USB 2.0, but most hubs only have a single transaction translator for low or full speed to high speed conversion.
Check the camera is true high speed USB 2.0 and have it on a seperate controller if possible
Just a note for future readers -- when calibrating a usb_cam camera, you can avoid modifying the calibration node by passing "--no-service-check" as a parameter to cameracalibration.py
looks like the new name for "probe" is "gscam"
i tried to run gscam with following launch file:
but it is showing the following error "Unable to open camera calibration file" my calibration file is in gscam directory itself.
what should i do?
rinosh1989 at GMAIL dot com
The launch file did not show up. If you can post the question on http://answers.ros.org I'll try to answer it there.
Thank you very much for the nice info!
Is this article still a good reference? Love to see an update if it needs it. Thanks!
Unfortunately, this somewhat out of date but the basic ideas are still relevant.
I'll see if we can allocate some interns to this problem and get this updated.
Post a Comment