Skip to content

Conversation

@ktro2828
Copy link
Contributor

@ktro2828 ktro2828 commented Dec 26, 2025

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 rectifier
    for (auto & [name, value] : rectifier_->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

Unit testings summary
$ colcon test --packages-select accelerated_image_processor_pipeline --event-handlers console_cohesion+
Starting >>> accelerated_image_processor_pipeline
--- output: accelerated_image_processor_pipeline
UpdateCTestConfiguration  from :/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/CTestConfiguration.ini
Parse Config file:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/CTestConfiguration.ini
   Site: ktro2828-desktop
   Build name: (empty)
 Add coverage exclude regular expressions.
Create new tag: 20260105-1332 - Experimental
UpdateCTestConfiguration  from :/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/CTestConfiguration.ini
Parse Config file:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/CTestConfiguration.ini
Test project /home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline
Constructing a list of tests
Done constructing a list of tests
Updating test list for fixtures
Added 0 tests to meet fixture requirements
Checking test dependency graph...
Checking test dependency graph end
test 1
    Start 1: builder.cpp_accelerated_image_processor_pipeline

1: Test command: /usr/bin/python3 "-u" "/opt/ros/humble/share/ament_cmake_test/cmake/run_test.py" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/builder.cpp_accelerated_image_processor_pipeline.gtest.xml" "--package-name" "accelerated_image_processor_pipeline" "--output-file" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/ament_cmake_gtest/builder.cpp_accelerated_image_processor_pipeline.txt" "--command" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/builder.cpp_accelerated_image_processor_pipeline" "--gtest_output=xml:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/builder.cpp_accelerated_image_processor_pipeline.gtest.xml"
1: Test timeout computed to be: 60
1: -- run_test.py: invoking following command in '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline':
1:  - /home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/builder.cpp_accelerated_image_processor_pipeline --gtest_output=xml:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/builder.cpp_accelerated_image_processor_pipeline.gtest.xml
1: Running main() from /opt/ros/humble/src/gtest_vendor/src/gtest_main.cc
1: [==========] Running 3 tests from 1 test suite.
1: [----------] Global test environment set-up.
1: [----------] 3 tests from TestRectifierBuilder
1: [ RUN      ] TestRectifierBuilder.CreateRectifier1
1: [       OK ] TestRectifierBuilder.CreateRectifier1 (114 ms)
1: [ RUN      ] TestRectifierBuilder.CreateRectifier2
1: [       OK ] TestRectifierBuilder.CreateRectifier2 (1 ms)
1: [ RUN      ] TestRectifierBuilder.CreateRectifier3
1: [       OK ] TestRectifierBuilder.CreateRectifier3 (0 ms)
1: [----------] 3 tests from TestRectifierBuilder (115 ms total)
1:
1: [----------] Global test environment tear-down
1: [==========] 3 tests from 1 test suite ran. (115 ms total)
1: [  PASSED  ] 3 tests.
1: -- run_test.py: return code 0
1: -- run_test.py: inject classname prefix into gtest result file '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/builder.cpp_accelerated_image_processor_pipeline.gtest.xml'
1: -- run_test.py: verify result file '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/builder.cpp_accelerated_image_processor_pipeline.gtest.xml'
1/4 Test #1: builder.cpp_accelerated_image_processor_pipeline .................   Passed    0.20 sec
test 2
    Start 2: cpu_rectifier.cpp_accelerated_image_processor_pipeline

2: Test command: /usr/bin/python3 "-u" "/opt/ros/humble/share/ament_cmake_test/cmake/run_test.py" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/cpu_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml" "--package-name" "accelerated_image_processor_pipeline" "--output-file" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/ament_cmake_gtest/cpu_rectifier.cpp_accelerated_image_processor_pipeline.txt" "--command" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/cpu_rectifier.cpp_accelerated_image_processor_pipeline" "--gtest_output=xml:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/cpu_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml"
2: Test timeout computed to be: 60
2: -- run_test.py: invoking following command in '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline':
2:  - /home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/cpu_rectifier.cpp_accelerated_image_processor_pipeline --gtest_output=xml:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/cpu_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml
2: [==========] Running 3 tests from 1 test suite.
2: [----------] Global test environment set-up.
2: [----------] 3 tests from TestRectifier
2: [ RUN      ] TestRectifier.CpuRectificationDefault
2: [       OK ] TestRectifier.CpuRectificationDefault (12 ms)
2: [ RUN      ] TestRectifier.CpuRectificationLowAlpha
2: [       OK ] TestRectifier.CpuRectificationLowAlpha (7 ms)
2: [ RUN      ] TestRectifier.CpuRectificationHighAlpha
2: [       OK ] TestRectifier.CpuRectificationHighAlpha (3 ms)
2: [----------] 3 tests from TestRectifier (22 ms total)
2:
2: [----------] Global test environment tear-down
2: [==========] 3 tests from 1 test suite ran. (22 ms total)
2: [  PASSED  ] 3 tests.
2: -- run_test.py: return code 0
2: -- run_test.py: inject classname prefix into gtest result file '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/cpu_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml'
2: -- run_test.py: verify result file '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/cpu_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml'
2/4 Test #2: cpu_rectifier.cpp_accelerated_image_processor_pipeline ...........   Passed    0.06 sec
test 3
    Start 3: npp_rectifier.cpp_accelerated_image_processor_pipeline

3: Test command: /usr/bin/python3 "-u" "/opt/ros/humble/share/ament_cmake_test/cmake/run_test.py" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/npp_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml" "--package-name" "accelerated_image_processor_pipeline" "--output-file" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/ament_cmake_gtest/npp_rectifier.cpp_accelerated_image_processor_pipeline.txt" "--command" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/npp_rectifier.cpp_accelerated_image_processor_pipeline" "--gtest_output=xml:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/npp_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml"
3: Test timeout computed to be: 60
3: -- run_test.py: invoking following command in '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline':
3:  - /home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/npp_rectifier.cpp_accelerated_image_processor_pipeline --gtest_output=xml:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/npp_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml
3: [==========] Running 3 tests from 1 test suite.
3: [----------] Global test environment set-up.
3: [----------] 3 tests from TestRectifier
3: [ RUN      ] TestRectifier.NppRectificationDefault
3: [       OK ] TestRectifier.NppRectificationDefault (107 ms)
3: [ RUN      ] TestRectifier.NppRectificationLowAlpha
3: [       OK ] TestRectifier.NppRectificationLowAlpha (6 ms)
3: [ RUN      ] TestRectifier.NppRectificationHighAlpha
3: [       OK ] TestRectifier.NppRectificationHighAlpha (5 ms)
3: [----------] 3 tests from TestRectifier (118 ms total)
3:
3: [----------] Global test environment tear-down
3: [==========] 3 tests from 1 test suite ran. (118 ms total)
3: [  PASSED  ] 3 tests.
3: -- run_test.py: return code 0
3: -- run_test.py: inject classname prefix into gtest result file '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/npp_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml'
3: -- run_test.py: verify result file '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/npp_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml'
3/4 Test #3: npp_rectifier.cpp_accelerated_image_processor_pipeline ...........   Passed    0.21 sec
test 4
    Start 4: opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline

4: Test command: /usr/bin/python3 "-u" "/opt/ros/humble/share/ament_cmake_test/cmake/run_test.py" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml" "--package-name" "accelerated_image_processor_pipeline" "--output-file" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/ament_cmake_gtest/opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline.txt" "--command" "/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline" "--gtest_output=xml:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml"
4: Test timeout computed to be: 60
4: -- run_test.py: invoking following command in '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline':
4:  - /home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline --gtest_output=xml:/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml
4: [==========] Running 1 test from 1 test suite.
4: [----------] Global test environment set-up.
4: [----------] 1 test from OpenCvCudaRectifierSkip
4: [ RUN      ] OpenCvCudaRectifierSkip.OpenCvCudaUnavailable
4: [  SKIPPED ] OpenCvCudaRectifierSkip.OpenCvCudaUnavailable (0 ms)
4: [----------] 1 test from OpenCvCudaRectifierSkip (0 ms total)
4:
4: [----------] Global test environment tear-down
4: [==========] 1 test from 1 test suite ran. (0 ms total)
4: [  PASSED  ] 0 tests.
4: [  SKIPPED ] 1 test, listed below:
4: [  SKIPPED ] OpenCvCudaRectifierSkip.OpenCvCudaUnavailable
4: -- run_test.py: return code 0
4: -- run_test.py: inject classname prefix into gtest result file '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml'
4: -- run_test.py: verify result file '/home/ktro2828/workspace/accelerated_image_processor/build/accelerated_image_processor_pipeline/test_results/accelerated_image_processor_pipeline/opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline.gtest.xml'
4/4 Test #4: opencv_cuda_rectifier.cpp_accelerated_image_processor_pipeline ...   Passed    0.03 sec

100% tests passed, 0 tests failed out of 4

Label Time Summary:
gtest    =   0.50 sec*proc (4 tests)

Total Test time (real) =   0.50 sec
---
Finished <<< accelerated_image_processor_pipeline [0.52s]

Summary: 1 package finished [0.70s]

@ktro2828 ktro2828 force-pushed the refactor/pipeline-package branch from 5e86a8c to 8be29af Compare January 1, 2026 10:29
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>
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
@ktro2828 ktro2828 force-pushed the refactor/pipeline-package branch from 238f099 to 63a54c5 Compare January 6, 2026 05:36
@ktro2828 ktro2828 requested a review from Copilot January 6, 2026 05:36
@ktro2828 ktro2828 marked this pull request as ready for review January 6, 2026 05:36
@ktro2828 ktro2828 requested a review from manato January 6, 2026 05:37
Copy link

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

This PR introduces a new accelerated_image_processor_pipeline package that provides a modular image rectification pipeline with support for multiple backends (NPP, OpenCV CUDA, and CPU). The package includes a builder pattern for automatic backend selection, a unified rectifier interface, and comprehensive test coverage.

Key Changes:

  • Implements a flexible rectifier abstraction with three backend implementations (NPP, OpenCV CUDA, CPU)
  • Adds builder utilities for automatic backend selection and postprocess callback registration
  • Extends common datatypes with CameraInfo struct for camera calibration support

Reviewed changes

Copilot reviewed 17 out of 17 changed files in this pull request and generated 4 comments.

Show a summary per file
File Description
CMakeLists.txt Build configuration with conditional compilation for NPP and OpenCV CUDA backends
package.xml ROS 2 package manifest declaring dependencies
include/accelerated_image_processor_pipeline/builder.hpp Builder interface for creating rectifiers with optional postprocess callbacks
include/accelerated_image_processor_pipeline/rectifier.hpp Abstract rectifier base class and backend enumeration
src/builder.cpp Implementation of backend selection logic
src/rectifier/cpu.cpp CPU-based rectification using OpenCV
src/rectifier/npp.cpp GPU-based rectification using NVIDIA NPP
src/rectifier/opencv_cuda.cpp GPU-based rectification using OpenCV CUDA
src/rectifier/utility.hpp Utility header for rectification map computation
src/rectifier/utility.cpp Shared logic for computing rectification maps
test/*.cpp Unit tests for builder and each rectifier backend
test/test_utility.hpp Test fixture and utilities
README.md Package documentation and usage examples
accelerated_image_processor_common/datatype.hpp Added CameraInfo struct

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

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 7fce1f7 to 17501e3 Compare January 7, 2026 07:55
Copy link
Collaborator

@manato manato left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@ktro2828
I appreciate your ongoing contribution to the refactoring task! The PR-ed code is sophisticated and well organized, including newly introduced tests.

I found a point that we need to pay extra attention toward CUDA stream synchronization, so I left a comment on it. Besides, I left some "nits" comments. I'd appreciate it if you could consider them!

camera_info_ = prepare_maps(camera_info);
}

const common::CameraInfo & get_camera_info() const { return camera_info_.value(); }
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nit: Only this getter function has get_ prefix. It might be good to get rid of this prefix or add a similar prefix to other getters like alpha() and backend() for consistency.

Copy link
Contributor Author

@ktro2828 ktro2828 Jan 7, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@manato Thank you! I got rid of get_ prefix and modified this function to return std::optional<...> camera_info_ as it is in 10656b1.


private:
common::Image process_impl(const common::Image & image) override
{
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is it possible to consider adding

if (is_ready()) {
 /* return invalid image */
}

for better encapsulation (despite the current accelerated_image_processor does not doing this)?

To this end, we may have to update accelerated_image_processor::common::BaseProcessor::process method (or override in accelerated_image_processor::pipeline::Rectifier ) so that it will check the result of process_impl is valid one.

In future expansion, such as video encoding, the process_impl (the function that takes an input image) may return nothing the because encoded result should be acquired in another thread. Considering this as well, checking the validity of the process_impl result would be great.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@manato Thank you for catching, I agree with you. I addressed that in d8bfaac.
I added is_ready() to BaseProcessor as virtual public function, and modified to check if processor is ready before calling process_impl() and registered postprocess function.

dst_step_,
image.width * 3 * sizeof(Npp8u), // in byte
image.height, cudaMemcpyDeviceToHost, stream_));

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Because the current accelerated_image_processor_compression::JetsonJPEGCompressor and accelerated_image_processor_compression::NvJPEGCompressor have own CUDA stream, and no way to provide another CUDA stream is provided, we need to call cudaStreamSynchronize(stream_) here.

If we imagine a case that users want to do distortion collection then compress it, sharing CUDA stream between Rectifier and JPEGCompressor could reduce latency because we can skip synchronization here.
This stream sharing is realized here in the current accelerated_image_processor.
(Apologize, I completely missed this point during the review of accelerated_image_processor_compression)

Copy link
Contributor Author

@ktro2828 ktro2828 Jan 7, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@manato Sorry, I missed this too...
I think we have some possible approaches. Anyway, let me discuss with you in person later when I address ROS dependent package!

Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
…urn optional

Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
…only if is_ready() returns true

Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
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.

3 participants