Image Processing with ROS
Overview
This lecture is about how to interface ROS with cameras and vision processing libraries.
Cameras On Linux
- Cameras on Linux are viewed as files (like any other device).
- A driver in the Linux Kernel enables users to work with cameras using a common interface
- The driver framework for USB cameras in Linux is called V4l2
- Some machine-vision cameras use vendor-specific or proprietary Linux drivers rather than V4L2
- Some machine-vision cameras don't provide drivers for Linux
- USB cameras on Linux are usually called
/dev/videoX
, whereX
is a number- Some cameras create two video devices, the lower numbered one is usually the one to use
v4l2-ctl
is a command line tool for interfacing with cameras. Seeman v4l2-ctl
v4l2-ctl --list-formats-ext
prints useful information about the formats supported by cameras connected to your computer- You often need to specify these parameters to the ROS camera node, as parameters
v4l2-ctl --all
prints all information about your camerasv4l2-ctl --list-devices
Lists all the usb cameras. Some cameras have multiple/dev/video*
devices so it is useful to see what goes with what- When working with cameras you should use udev rules to give your cameras
the proper permissions and a persistent name.
- These rules are triggered when hardware is connected to the system and can (among other things) set permissions of the devices
ROS Camera "Drivers"
- A ros driver is a node (or set of nodes) that interacts with hardware and provides a standard ROS interface
- There are at least two packages that contain ROS drivers for interacting with USB cameras that operate via the v4l2 interface
- usb_cam and v4l2_camera
- Sometimes you need to experiment with camera drivers, as which one works better may depend on your hardware
- Nodes in these package access your camera via the video device file (
/dev/videoX
)- Parameters control options for the camera (such as framerate and resolution)
- Sometimes, you need to experiment with various options to get a usable webcam image, because every camera is different
- The image display type in rviz can be used to see the video from a camera
- However, all camera drivers ultimately provide a consistent ROS interface
Using usb_cam
- The usb_cam package can be used with many cameras
- The camera is one of the
/dev/videoX
devices, and can be specified with thevideo_device
parameter - Run the
usb_cam
node. A command with parameters that work well with the webcam on the System76 laptops areros2 run usb_cam usb_cam_node_exe --ros-args -p framerate:=30.0 -p pixel_format:=yuyv
- Cameras have many settings that are important for machine vision. Use
v4l2-ctl
to view and tweak them - The
camera_info_url
parameter can be passed to provide a camera calibration file that for most cameras you will need to generate.- Without this file images can still be processed but pixel coordinates in the images cannot be converted to real world coordinates via ROS
- After running you can view the image in several ways
- Use
rviz2
and add an Image view ros2 run usb_cam show_image.py
(Image might be laggy at high resolutions)ros2 run rqt_image_view rqt_image_view
ros2 run image_view image_view --ros-args -r image:=/topic_image_is_published_on
to view the image
- Use
Using v4l2_camera
- The v4l2_camera package is designed to expose many v4l2 camera options to ROS via parameters
- It automatically enumerates all available v4l2 options (which vary by camera model) and exposes them
- It can be used with
ros2 run v4l2_camera v4l2_camera_node
The Image Pipeline
Image Pipeline
The image_pipeline contains several packages relating to image manipulation in ROS.
- The idea is to chain various calibration and image processing steps together to complete computer vision tasks.
- The pipeline also applies to stereo-vision cameras and 3D point clouds as well as monocular images.
Camera Calibration
camera_calibration finds the intrinsic parameters of a camera using a checkerboard pattern and OpenCV.
- See this tutorial for information on how to calibrate a monocular camera in ROS 2.
- More information about camera calibration CameraInfo
- Some more information on calibration matrices for the pinhole camera model
- Matlab tutorial on camera calibration
- The calibration can be stored and used to provide a
camera_info
topic so that the calibration can be used by other nodes.- The CameraInfo has useful information about camera calibration
- Calibrations can be loaded by setting the
camera_info_url
parameter- Each driver may be different,
camera_info_url
is a ROS convention however
- Each driver may be different,
- It is also possible to perform a stereo calibration for two cameras, which results in receiving depth information
- The
camera_check
node can be used to check the calibrationros2 run camera_calibration cameracheck --ros-args -r /monocular/image:=image_rect-r /monocular/camera_info:=camera_info
Example
Here is an example for how to start the camera calibration using usb_cam
as the camera source.
ros2 run usb_cam usb_cam_node_exe --ros-args -p framerate:=30 -p pixel_format:=yuyv -r __ns:=/camera ros2 run camera_calibration cameracalibrator --size 8x6 --square 0.108 --ros-args -r camera/set_camera_info:=usb_cam/set_camera_info -r image:=/raw_image ros2 launch image_proc image_proc.launch.py
MrCal
- The mrcal package provides routines for calibrating (and verifying the calibration) in a way that is much more rigorous and precise than the usual calibration methods
Image Proc
- The image_proc package handles rectifying and debayering images.
- Rectification is a method to compensate for camera lens distortion (which can make parallel lines appear curved in an image)
- Debayering is a compensation that accounts for the individual color pixel layout on color cameras More Info
- Run
image_proc
withros2 launch image_proc image_proc.launch.py
- This launchfile launches several component nodes (that is nodes that all run in the same process) that subscribe to
/image_raw
and/camera_info
to create the rectified and debayerd images
- This launchfile launches several component nodes (that is nodes that all run in the same process) that subscribe to
image_proc
publishes the followingimage_mono
: A monochrome unrectified imageimage_rect
: A monochrome rectified imageimage_color
: A color unrectified image. These images are de-omsaiced (that is it accounts for the rgb pixel pattern of the camera)image_rect_color
A color rectified image.- The subtopics (e.g.,
image_rect/compressed
) are various compressed versions of the image. These are referred to astransports
. - Transmitting uncompressed images takes a lot of bandwidth (even with modern networks), so compressed images are preferred
- However, there is no convenient way in python of subscribing to compressed images
Depth Images
depth_image_proc Processes depth image
- In a depth image, each pixel corresponds to the depth (i.e., how far light has to travel before hitting something) in the scene.
- Used by RGB-D cameras such as the intel RealSense.
- Used to make point clouds (basically 3 dimensional pixelized images) from calibrated depth cameras
Other Image Tools
- image_transport determines how image data is sent across the system.
Rather than raw camera data, the image data can be compressed to use less bandwidth.
- For python usage, the
republish
node is the most important.- It can subscribe to a compressed image, decompress it, and publish it as a raw image
- Thus, you can publish a compressed image on a remote computer on the network, subscribe to it with the
republish
node, and have it republish the uncompressed image, allowing easier access from python.
- web_video_server is used to create an http stream of video, useful if interfacing your robot to a website.
OpenCV
OpenCV is a major image processing library. Their website has many tutorials on how to process images.
Some packages that use/relate to OpenCV are:
- cv_bridge
- Converts between OpenCV data and ROS messages.
- If you want to use opencv with ROS, you should use this package to convert between OpenCV formats and ROS 2 image messages
- image_geometry Using a camera calibration,
- lets you convert between pixel coordinates and the other frames in your system..
- Python API documentation is not hosted properly but can be build locally with
rosdoc2
. - For those too lazy to build the documentation, the ROS 1 python API is substantially similar and is documented online Python API documentation
Not In ROS 2 (yet)
- opencv_apps Each "app" is a node that performs a single image processing function using opencv. Thus you can chain together many computer vision algorithms by connecting some nodes together in a launchfile.
Tag Tracking
Tags are special 2-Dimensional patterns that are designed to be viewed with a camera. Computer vision algorithms can then determine the 6 Degree of freedom pose of the tag and often an identifier (thus Tags are like QR codes but they also contain geometric information.
- Information on the Theory of April Tags
- Includes code for generating the tags
- AprilTags User Guide
- STags are another type of tag that have been newly developed, and the linked paper provides a good overview of other tags
- The April tags library is April Tags
- This is a ros-independent library written in C (with python bindings).
- It can be used directly from python: https://github.com/AprilRobotics/apriltag/wiki/AprilTag-User-Guide
April Tags in ROS
- The apriltag_ros provides april-tag related functionality for ROS
- This is a meta-package that also installs the ROS-independent apriltag library (
ros-jazzy-apriltag
) and messages for apriltags (ros-jazzy-apriltag-msgs
).
- This is a meta-package that also installs the ROS-independent apriltag library (
- apriltag has documentation for apriltags.
- Choose a Tag Family
- Download images here: https://github.com/AprilRobotics/apriltag-imgs
- Resize the images and print them (for example, use
gimp
):- Choose
Image->Scale Image
- Set the Size of the image (choose the resolution and then set the size in real-world units (e.g. meters)
- Choose "None" for interpolation
- Print it out
- It is important that the tag's scaling is correct or the tag will not work.
- April tags must have a boarder around them. There are some tag families that have a white border and others that have a black border
- Choose
- See apriltag documentation for more instructions on how to use them.
Other Image Packages and Libraries
- Darknet ROS 2 - realtime object detection (last released for foxy)
- Up to date list of visual SLAM solutions
- face_detector
- facial_recognition You will need to compile this since it was last released for ROS indigo.
- 2D tracking of multiple objects
- Find object 2D Feature detection to find objects
- YoloV8 wrapper for ROS 2
Other Learning Resources
- Cameras and Lenses (Highly recommend this)
- mrcal NASA-quality lenses modeling and calibration software.