Cameras
Cameras are sensors that publish:
- Messages of type
sensor_msgs/Image
to the/sensors/camera_#/color/image
topic. - Messages of type
sensor_msgs/CameraInfo
to the/sensors/camera_#/color/CameraInfo
topic.
This broad definition allows us to label a variety of different cameras under a single banner. Stereo cameras, for example, could publish multiple images, disparity maps, and even pointclouds. Other cameras have in built inertial measurement units that publish sensor_msgs/Imu
. Ultimately, all imaging devices fall into this category.
For further details on how to work with large camera data, see Camera Data Compression
Supported Cameras
Intel Realsense
|
Package and Setup
The Intel Realsense cameras use the realsense_ros
ROS 2 driver. The driver is open source, maintained by Intel, and hosted on GitHub. The realsense_ros
nodes depends on the the librealsense2
SDK. Both packages will be installed alongside the clearpath_sensors
package.
For specifics on the way Clearpath's configuration system launches the camera, see the Intel Realsense launch file and the default parameter file in clearpath_sensors
.
Device Type and Serial Number
The device_type
and serial_no
parameters must be set accurately to successfully launch the node. Both of these values can be found using the SDK utility.
Use the following command to see a list of connected Intel Realsense devices:
rs-fw-update
When ran without any arguments, the rs-fw-update
will return information about the connected devices, as is shown below:
Nothing to do, run again with -h for help
Connected devices:
1) Name: Intel RealSense D435, serial number: 045322073417, update serial number: 041323020523, firmware version: 5.12.13.50, USB type: 3.2
The device_type
is the alpha-numerical sequence in the name. In the example above, set device_type
to d435
.
The serial_no
is the string following the serial number entry. In the example above, set serial_no
to "045322073417"
. Make sure to use quotes to ensure that the serial number is interpreted as a string.
Flir BlackflyS
|
Package and Setup
The Flir Blackfly cameras use the spinnaker_camera_driver
ROS 2 package. The driver is open source, maintained by the ROS community, and hosted on GitHub. The spinnaker_camera_driver
depends on the Spinnaker SDK, which is installed automatically alongside the package.
Before using the camera, the computer needs further setup. The setup can be done automatically using the linux setup script:
ros2 run spinnaker_camera_driver linux_setup_flir
Or, manually by following the instructions on the GitHub README.
For specifics on the way Clearpath's configuration system launches the camera, see the Flir Blackfly launch file and the default parameter file in clearpath_sensors
.
Serial Number
The serial_number
parameter must be set to successfully launch the node. The serial number can be found on the label on the camera. However, if this label is not available and the camera is a USB camera, connect the camera to the computer and use lsusb
to its three digit Bus
and Device
number. Then, find the serial number using the following command, replacing BUS
and DEV
with the three digit numbers found in the previous step:
udevadm info --attribute-walk /dev/bus/usb/BUS/DEV | grep -i serial
The resulting output of the command should appear as:
ATTR{serial}=="013686A9"
Then, convert attribute serial hexadecimal value to decimal representation and set it to the serial_number
parameter. Convert values from hexadecimal to decimal representation using the following terminal command, where HEX
needs to be swapped with the hexadecimal value:
echo $((16#HEX))
For the example above, the hexadecimal serial number 013686A9
would be converted to 20350633
. Use the decimal representation to set the parameter: serial_number: 20350633
.
Resolution
The image_height
and image_width
parameters define the area of the raw image to crop. It does not downsample the image. Use the offset_x
and offset_y
parameters to change the origin of the cropped area. These parameters would be best used to define an area of interest.
To reduce the size of the image using downsampling, use the binning_x
and binning_y
parameters. These parameters define the number of pixels that will be binned together in each axis. If both binning_x
and binning_y
are set to 2
, then the resolution of the image will be quartered.
Reducing the resolution of the image improves the performance of the camera driver and network transit of image packets.
Image Compression
By default, the camera feed is also available in compressed formats including compressed
(JPEG) and ffmpeg
(H.264). Each of these topics is made available by an image transport plugin. Which plugins are active can be controlled by adding the following ROS parameters to the Blackfly section of the robot.yaml
:
ros_parameters:
flir_blackfly:
serial_number: ''
image_debayer:
image_mono:
enable_pub_plugins:
- image_transport/compressed
- image_transport/ffmpeg
- image_transport/raw
image_color:
enable_pub_plugins:
- image_transport/compressed
- image_transport/ffmpeg
- image_transport/raw
FFMPEG Compression Settings
To modify the FFMPEG compression settings, add the following ROS parameters to the Blackfly section of the robot.yaml
:
ros_parameters:
flir_blackfly:
serial_number: ''
image_debayer:
ffmpeg_image_transport:
qmax: 40
preset: superfast
tune: zerolatency
bit_rate: 1000000
gop_size: 15
For documentation on these parameters see the ffmpeg_image_transport GitHub repo.
Stereolabs Zed
|
Package and Setup
The Stereolabs Zed cameras use the zed-ros2-wrapper
ROS 2 driver. The driver is open source, maintained by Stereolabs, and hosted on GitHub. The zed_wrapper
nodes depend on the the ZED SDK. The zed-ros2-wrapper
ROS packages and the ZED SDK are not installed by ROS dependencies because the SDK and the wrapper depend on CUDA and need to be built against the specific version installed on your computer. Therefore, **you will have to install these manually by following the instructions in the zed-ros2-wrapper
repository.
For specifics on the way Clearpath's configuration system launches the camera, see the Stereolabs Zed launch file and the default parameter file in clearpath_sensors
.
Camera Model
The general.camera_model
parameter must be modified to the match the type of Zed camera being used. See the list below for all models:
zed
zedm
zed2
zed2i
zedx
zedxm
virtual
Serial Number
The general.serial_number
parameter can be left at 0
if only one camera is connected to that computer. If multiple cameras are connected, make sure to define a serial number for each.
Resolution
The general.grab_resolution
parameter can be modified to change the resolution preset of the camera. Not all cameras support all presets. See the list below for all presets:
AUTO
HD2K
HD1080
HD720
VGA
Post Processing Republishers
All cameras publish to the color/image
topic of type sensor_msgs/Image
. However, we understand that sometimes this image may require downsampling, rectification, or cropping. To facilitate post processing images, we have included a method to easily add image processing nodes, leveraging composable nodes to maximize efficiency.
For more information on the image processing nodes see the ROS wiki.
Adding a republisher is simple.
- Add a
republishers
tag under thecamera
entry. - Specify the
type
of republisher:rectify
orresize
. - Specify the
input
topic namespace. By default, it iscolor
because the standard image topic will becolor/image
. - Specify the
output
topic namespace. By default, it is the type of the republisher:{type}/image
.
Configuring a republisher can be done by setting its node parameters using the ros_parameters
section.
- Under
ros_parameters
add an entry for the nodeimage_TYPE_INPUT
. Note, the node name depends on thetype
of republisher and theinput
name. - Add any parameter key, value pair to configure the node. Otherwise, it can be left empty to use defaults.
Rectify
The rectify
node takes the camera_info
topic as a source of calibration parameters and applies an interpolation to rectify the raw images.
To add a rectify republisher, add the following entries to the camera
entry and its corresponding ros_parameters
section.
cameras:
- model: CAMERA_MODEL
republishers:
- type: rectify
input: color
output: rectify
ros_parameters:
CAMERA_NODE:
CAMERA_PARAMETER_KEY: CAMERA_PARAMETER_VALUE
image_rectify_color:
interpolation: 0
The interpolation
parameter must be one of the following:
- 0: Nearest-neighbour.
- 1: Linear.
- 2: Cubic.
- 3: Area. Resampling using pixel area relation.
- 4: Lanczos4. Lanczos interpolation over 8x8 neighbourhood.
All UPPERCASE entries must be replaced based on the specific camera being used.
Resize
The resize
node uses the input image and resizes it.
To add a resize republisher, add the following entries to the camera
entry and its corresponding ros_parameters
section.
cameras:
- model: CAMERA_MODEL
republishers:
- type: resize
input: color
output: resize
ros_parameters:
CAMERA_NODE:
CAMERA_PARAMETER_KEY: CAMERA_PARAMETER_VALUE
image_resize_color:
interpolation: 1
use_scale: True
scale_height: 1.0
scale_width: 1.0
height: -1
width: -1
If use_scale
is set to true
, then the scale_height
and scale_width
parameters will be used to resize the image. To reduce the size of the image by half, set scale_height: 0.5
and scale_width: 0.5
.
If use_scale
is set to false
, then the height
and width
parameters will be used to resize the image. In this case, the exact pixel values of the desired image size can be passed.
The scale_height
and scale_width
parameters must be floating point values.
The height
and width
parameters must be integer values.
The interpolation
parameters must be one of the following:
- 0: Nearest-neighbour.
- 1: Linear.
- 2: Cubic.
- 3: Area. Resampling using pixel area relation.
- 4: Lanczos4. Lanczos interpolation over 8x8 neighbourhood.