Skip to content

A library to provide hardware acceleration for image processing functions such as compression and rectification.

License

Notifications You must be signed in to change notification settings

tier4/accelerated_image_processor

Repository files navigation

accelerated_image_processor

A ROS2 package that provides GPU-accelerated image processing capabilities for efficient image rectification and compression. This package is designed to handle high-throughput image processing tasks using hardware acceleration when available.

Features

  • GPU-accelerated image rectification using:
    • NVIDIA Performance Primitives (NPP)
    • OpenCV CPU implementation
    • OpenCV CUDA implementation
  • Hardware-accelerated JPEG compression using:
    • NVIDIA JPEG encoder (for Jetson platforms)
    • NVIDIA NVJPEG library
    • TurboJPEG (CPU fallback)
  • Configurable processing pipeline
  • Support for RGB8 and BGR8 image formats
  • Task queue management for handling high-throughput scenarios
  • ROS2 component-based architecture

Dependencies

Required

  • OpenCV

For GPU/HW acceleration

  • CUDA Toolkit
  • NVIDIA Performance Primitives (NPP)
  • NVJPEG (for discrete GPU environment)
  • Jetson Multimedia API (for Jetson platforms)

For CPU acceleration

  • libturbojpeg

Installation

  1. Install the required dependencies:
sudo apt install ros-$ROS_DISTRO-cv-bridge ros-$ROS_DISTRO-image-geometry libturbojpeg0-dev
  1. Clone this repository into your ROS2 workspace:
cd ~/ros2_ws/src
git clone https://github.com/tier4/accelerated_image_processor.git
  1. Build the package:
cd ~/ros2_ws
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release --packages-up-to accelerated_image_processor

Usage

The package provides a ROS2 component that can be loaded either as a standalone node or as part of a component container.

Parameters

Parameter Type Default Description
rect_impl string "npp" Rectification implementation to use ("npp", "opencv_cpu", or "opencv_gpu")
alpha double 0.0 Rectification alpha parameter
jpeg_quality int 60 JPEG compression quality (0-100)
do_rectify bool true Enable/disable image rectification
max_task_queue_length int 5 Maximum number of images that can be queued for processing. A smaller value may cause dropped frames, while a larger value may lead to increased latency and higher memory usage.

Topics

Subscribed Topics

  • image_raw (sensor_msgs/Image): Raw input image
  • camera_info (sensor_msgs/CameraInfo): Camera calibration information

Published Topics

  • image_rect (sensor_msgs/Image): Rectified image
  • image_rect/compressed (sensor_msgs/CompressedImage): Compressed rectified image
  • image_raw/compressed (sensor_msgs/CompressedImage): Compressed raw image
  • camera_info_rect (sensor_msgs/CameraInfo): Camera calibration information for the rectified image

Launch Examples

  1. As a standalone node:
ros2 run accelerated_image_processor accelerated_image_processor_node
  1. With custom parameters:
ros2 run accelerated_image_processor accelerated_image_processor_node --ros-args -p rect_impl:=npp -p jpeg_quality:=80

Camera Intrinsics Publication

According to the definition of sensor_msgs/msg/CameraInfo, its parameters of K and P are described as follows:

Intrinsic camera matrix, for the raw (distorted) images
    [fx  0  cx]
K = [ 0 fy  cy]
    [ 0  0   1]
the intrinsic (camera) matrix of the processed (rectified) image
    [fx'  0  cx'  Tx]
P = [ 0  fy' cy'  Ty]
    [ 0   0   1    0]

The contents of K in camera_info_rect published by this node will be identical to the upper-left 3x3 portion of P from the input camera_info, as long as the specified alpha value is the same as the original (i.e., the one used during camera calibration). Typically, alpha==0.0 is used.

However, this node allows the input of an arbitrary alpha value, which may result in P from the input camera_info not accurately representing the intrinsic values for undistorted output images.

Therefore, this node publishes the camera info for the undistorted images. The updated camera info is generated by:

  1. Calculating a new camera matrix based on K and D from the input camera_info
  2. Copying the contents of input camera_info into the output camera_info_rect
  3. Filling K in the output camera_info_rect with the values calculated during step 1
  4. Setting D in the output camera_info_rect to zeros
  5. Filling the upper-left 3x3 portion of P in the output camera_info_rect with the values calculated during step 1.

This updated camera info is useful for applications that require the intrinsic parameters of the rectified image for further processing.

About

A library to provide hardware acceleration for image processing functions such as compression and rectification.

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Contributors 6