retinify 0.1.7
Real-Time AI Stereo Vision Library
Loading...
Searching...
No Matches
pipeline.hpp
Go to the documentation of this file.
1// SPDX-FileCopyrightText: Copyright (c) 2025 Sensui Yagi. All rights reserved.
2// SPDX-License-Identifier: Apache-2.0
3
4#pragma once
5
8#include "retinify/status.hpp"
9
10#include <array>
11#include <cstddef>
12#include <cstdint>
13
14namespace retinify
15{
18enum class PixelFormat : std::uint8_t
19{
22 GRAY8,
25 RGB8,
26};
27
30enum class DepthMode : std::uint8_t
31{
34 FAST,
41};
42
46{
47 public:
48 Pipeline() noexcept;
49 ~Pipeline() noexcept;
50
65 [[nodiscard]] auto Initialize(std::uint32_t imageWidth, std::uint32_t imageHeight, PixelFormat pixelFormat = PixelFormat::RGB8, DepthMode depthMode = DepthMode::ACCURATE, const CalibrationParameters &calibrationParameters = CalibrationParameters{}) noexcept -> Status;
66
81 [[nodiscard]] auto Execute(const std::uint8_t *leftImageData, std::size_t leftImageStride, const std::uint8_t *rightImageData, std::size_t rightImageStride) noexcept -> Status;
82
93 [[nodiscard]] auto RetrieveRectifiedLeftImage(std::uint8_t *leftImageData, std::size_t leftImageStride) noexcept -> Status;
94
105 [[nodiscard]] auto RetrieveRectifiedRightImage(std::uint8_t *rightImageData, std::size_t rightImageStride) noexcept -> Status;
106
121 [[nodiscard]] auto RetrieveRectifiedImages(std::uint8_t *leftImageData, std::size_t leftImageStride, std::uint8_t *rightImageData, std::size_t rightImageStride) noexcept -> Status;
122
133 [[nodiscard]] auto RetrieveDisparity(float *disparityData, std::size_t disparityStride) noexcept -> Status;
134
145 [[nodiscard]] auto RetrieveDepth(float *depthData, std::size_t depthStride) noexcept -> Status;
146
157 [[nodiscard]] auto RetrievePointCloud(float *pointCloudData, std::size_t pointCloudStride) noexcept -> Status;
158
159 private:
160 class Impl;
161 auto impl() noexcept -> Impl *;
162 [[nodiscard]] auto impl() const noexcept -> const Impl *;
163 static constexpr std::size_t BufferSize{2048};
164 alignas(alignof(std::max_align_t)) std::array<unsigned char, BufferSize> buffer_{};
165};
166} // namespace retinify
#define RETINIFY_API
Defines a macro for setting API visibility to "default" for the retinify library.
Definition attributes.hpp:8
Base class that disables copy and move operations for derived classes.
Definition nocopymove.hpp:11
A retinify::Pipeline provides an interface for running a stereo matching.
Definition pipeline.hpp:46
auto RetrieveDisparity(float *disparityData, std::size_t disparityStride) noexcept -> Status
Retrieves the computed disparity map.
auto RetrieveRectifiedRightImage(std::uint8_t *rightImageData, std::size_t rightImageStride) noexcept -> Status
Retrieves the rectified right image.
auto RetrieveDepth(float *depthData, std::size_t depthStride) noexcept -> Status
Retrieves the computed depth map.
auto RetrieveRectifiedLeftImage(std::uint8_t *leftImageData, std::size_t leftImageStride) noexcept -> Status
Retrieves the rectified left image.
auto RetrieveRectifiedImages(std::uint8_t *leftImageData, std::size_t leftImageStride, std::uint8_t *rightImageData, std::size_t rightImageStride) noexcept -> Status
Retrieves the rectified left and right images.
auto RetrievePointCloud(float *pointCloudData, std::size_t pointCloudStride) noexcept -> Status
Reprojects the computed disparity map to a 3D point cloud.
auto Execute(const std::uint8_t *leftImageData, std::size_t leftImageStride, const std::uint8_t *rightImageData, std::size_t rightImageStride) noexcept -> Status
Executes the stereo matching pipeline using the given left and right image data.
Pipeline() noexcept
This class represents the status of an operation in the retinify library.
Definition status.hpp:51
Definition colormap.hpp:13
PixelFormat
The pixel format options for input images.
Definition pipeline.hpp:19
@ RGB8
8-bit 3ch, RGB format
@ GRAY8
8-bit 1ch, Grayscale format
DepthMode
The depth mode options for stereo matching pipeline.
Definition pipeline.hpp:31
@ BALANCED
Balanced, with moderate accuracy and speed.
@ ACCURATE
Most accurate, with slowest performance.
@ FAST
Fastest, with lowest accuracy.
Stereo camera calibration parameters.
Definition geometry.hpp:266