Skip to content

Conversation

@ktro2828
Copy link
Contributor

PR Type

  • Improvement

Related Links

TIER IV INTERNAL LINK

Description

This pull request introduces a new package, accelerated_image_processor_pipeline, which provides an extensible and modular image processing pipeline with support for multiple rectification backends (CPU, OpenCV CUDA, and NVIDIA NPP). The changes include initial implementation of the pipeline structure, backend selection logic, and documentation, as well as support for camera calibration data. The most important changes are summarized below:

Pipeline Core and Backend Selection:

  • Added the accelerated_image_processor_pipeline package, including a CMake build system, ROS 2 package manifest, and a README.md with usage examples. This package provides a unified interface for image rectification using multiple backends (CPU, OpenCV CUDA, and NPP), and includes logic to select the best available backend at runtime. [1] [2] [3]
  • Implemented the Rectifier abstract base class and backend-specific rectifier classes (CpuRectifier, OpenCvCudaRectifier, and NppRectifier), each encapsulating their respective processing logic and resource management. [1] [2] [3]

API and Builder Utilities:

  • Introduced builder functions in builder.hpp and builder.cpp to create rectifier instances, supporting both free and member function callbacks for post-processing. The builder automatically selects the optimal backend based on compilation flags and hardware availability. [1] [2]

Camera Calibration Support:

  • Added a new CameraInfo struct to the common datatypes, supporting camera frame identification, timestamping, calibration matrices, and distortion coefficients, which are used by the rectifiers for accurate image processing. [1] [2]

These changes lay the foundation for a flexible, hardware-accelerated image processing pipeline with ROS 2 integration and extensible backend support.

Remarks

The following demonstrates how to use the rectifier on ROS 2 codebase:

#include <accelerated_image_processor_common/datatype.hpp>
#include <accelerated_image_processor_pipeline/builder.hpp>

#include <rclcpp/rclcpp.hpp>

using namespace accelerated_image_processor;

class SomeNode final : public rclcpp::Node
{
public:
  explicit SomeNode(const rclcpp::NodeOptions & options) : Node("some_node", options)
  {
    rectifier_ = pipeline::create_rectifier<SomeNode, &SomeNode::publish>(this);

    // Update parameters of the compressor
    for (auto & [name, value] : compressor_->parameters()) {
      std::visit([&](auto & v) {
        using T = std::decay_t<decltype(v)>;
        v = this->declare_parameter<T>(name, v);
      }, value);
    }

    // Create a subscription and publisher
    image_subscription_ = this->create_subscription<sensor_msgs::msg::Image>(
      "~/input/image", 10, [this](const sensor_msgs::msg::Image::ConstSharedPtr msg) { this->image_callback(msg); });
    camera_info_subscription_ = this->create_subscription<sensor_msgs::msg::CameraInfo>(
      "~/input/camera_info", 10, [this](const sensor_msgs::msg::CameraInfo::ConstSharedPtr msg) { this->camera_info_callback(msg); });
    image_publisher_ = this->create_publisher<sensor_msgs::msg::CompressedImage>("~/output/image", 10);
    camera_info_publisher_ = this->create_publisher<sensor_msgs::msg::CameraInfo>("~/output/camera_info", 10);
  }

private:
  void image_callback(const sensor_msgs::msg::Image::ConstSharedPtr msg)
  {
    common::Image image;
    // Convert the message to image...
    if (rectifier_->is_ready()) {
      rectifier_->process(image);
    }
  }

  void camera_info_callback(const sensor_msgs::msg::CameraInfo::ConstSharedPtr msg)
  {
    rectifier_->set_camera_info(msg);
  }

  void publish(const common::Image & image)
  {
    const common::CameraInfo & camera_info = rectifier_->get_camera_info();

    sensor_msgs::msg::CompressedImage image_msg;
    sensor_msgs::msg::CameraInfo camera_info_msg;
    // Convert the image and camera info to message...
    image_publisher_->publish(image_msg);
    camera_info_publisher_->publish(camera_info_msg);
  }

  std::unique_ptr<pipeline::Rectifier> rectifier_; //!< Rectifier

  rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr image_subscription_; //!< Image subscription
  rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr camera_info_subscription_; //!< CameraInfo subscription
  rclcpp::Publisher<sensor_msgs::msg::CompressedImage>::SharedPtr image_publisher_; //!< Image publisher
  rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr camera_info_publisher_; //!< CameraInfo publisher
};

Pre-Review Checklist for the PR Author

PR Author should check the checkboxes below when creating the PR.

  • Assign PR to reviewer

Checklist for the PR Reviewer

Reviewers should check the checkboxes below before approval.

  • Commits are properly organized and messages are according to the guideline
  • (Optional) Unit tests have been written for new behavior
  • PR title describes the changes

Post-Review Checklist for the PR Author

PR Author should check the checkboxes below before merging.

  • All open points are addressed and tracked via issues or tickets

CI Checks

  • Build and test for PR: Required to pass before the merge.

Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
@ktro2828 ktro2828 force-pushed the refactor/pipeline-package branch from 5e86a8c to 8be29af Compare January 1, 2026 10:29
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants