retinify 0.1.7
Real-Time AI Stereo Vision Library
Loading...
Searching...
No Matches
geometry.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
6#include "attributes.hpp"
7#include "status.hpp"
8
9#include <array>
10#include <cstddef>
11#include <cstdint>
12
13namespace retinify
14{
17using Vec2d = std::array<double, 2>;
18
21using Vec3d = std::array<double, 3>;
22
25using Point2d = std::array<double, 2>;
26
29using Point3d = std::array<double, 3>;
30
33using Mat3x3d = std::array<std::array<double, 3>, 3>;
34
37using Mat3x4d = std::array<std::array<double, 4>, 3>;
38
41using Mat4x4d = std::array<std::array<double, 4>, 4>;
42
47template <typename T> struct Rect2
48{
51 T x{0};
54 T y{0};
57 T width{0};
60 T height{0};
61};
62
66
71RETINIFY_API auto Identity() noexcept -> Mat3x3d;
72
79RETINIFY_API auto Determinant(const Mat3x3d &mat) noexcept -> double;
80
87RETINIFY_API auto Transpose(const Mat3x3d &mat) noexcept -> Mat3x3d;
88
97RETINIFY_API auto Add(const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d;
98
107RETINIFY_API auto Multiply(const Mat3x3d &mat, const Vec3d &vec) noexcept -> Vec3d;
108
117RETINIFY_API auto Multiply(const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d;
118
127RETINIFY_API auto Multiply(const Mat3x3d &mat, double scale) noexcept -> Mat3x3d;
128
137RETINIFY_API auto Multiply(const Vec3d &vec, double scale) noexcept -> Vec3d;
138
145RETINIFY_API auto Length(const Vec3d &vec) noexcept -> double;
146
153RETINIFY_API auto Normalize(const Vec3d &vec) noexcept -> Vec3d;
154
163RETINIFY_API auto Dot(const Vec3d &vec1, const Vec3d &vec2) noexcept -> double;
164
173RETINIFY_API auto Cross(const Vec3d &vec1, const Vec3d &vec2) noexcept -> Vec3d;
174
181RETINIFY_API auto Hat(const Vec3d &vec) noexcept -> Mat3x3d;
182
189RETINIFY_API auto Vee(const Mat3x3d &mat) noexcept -> Vec3d;
190
197RETINIFY_API auto Exp(const Vec3d &vec) noexcept -> Mat3x3d;
198
205RETINIFY_API auto Log(const Mat3x3d &mat) noexcept -> Vec3d;
206
210{
213 double fx{0};
216 double fy{0};
219 double cx{0};
222 double cy{0};
225 double skew{0};
226
227 [[nodiscard]] auto operator==(const Intrinsics &other) const noexcept -> bool
228 {
229 return fx == other.fx && //
230 fy == other.fy && //
231 cx == other.cx && //
232 cy == other.cy && //
233 skew == other.skew;
234 }
235};
236
240{
241 double k1{0};
242 double k2{0};
243 double p1{0};
244 double p2{0};
245 double k3{0};
246 double k4{0};
247 double k5{0};
248 double k6{0};
249
250 [[nodiscard]] auto operator==(const Distortion &other) const noexcept -> bool
251 {
252 return k1 == other.k1 && //
253 k2 == other.k2 && //
254 p1 == other.p1 && //
255 p2 == other.p2 && //
256 k3 == other.k3 && //
257 k4 == other.k4 && //
258 k5 == other.k5 && //
259 k6 == other.k6;
260 }
261};
262
266{
287 std::uint32_t imageWidth{};
290 std::uint32_t imageHeight{};
296 std::int64_t calibrationTime{};
297
298 [[nodiscard]] auto operator==(const CalibrationParameters &other) const noexcept -> bool
299 {
300 return leftIntrinsics == other.leftIntrinsics && //
301 leftDistortion == other.leftDistortion && //
302 rightIntrinsics == other.rightIntrinsics && //
303 rightDistortion == other.rightDistortion && //
304 rotation == other.rotation && //
305 translation == other.translation && //
306 imageWidth == other.imageWidth && //
307 imageHeight == other.imageHeight && //
308 calibrationError == other.calibrationError && //
309 calibrationTime == other.calibrationTime; //
310 }
311};
312
323RETINIFY_API auto UndistortPoint(const Intrinsics &intrinsics, const Distortion &distortion, const Point2d &point) noexcept -> Point2d;
324
335RETINIFY_API auto DistortPoint(const Intrinsics &intrinsics, const Distortion &distortion, const Point2d &point) noexcept -> Point2d;
336
373RETINIFY_API auto StereoRectify(const Intrinsics &intrinsics1, const Distortion &distortion1, const Intrinsics &intrinsics2, const Distortion &distortion2, const Mat3x3d &rotation, const Vec3d &translation, std::uint32_t imageWidth, std::uint32_t imageHeight, Mat3x3d &rotation1, Mat3x3d &rotation2, Mat3x4d &projectionMatrix1, Mat3x4d &projectionMatrix2, Mat4x4d &reprojectionMatrix, double alpha) noexcept -> Status;
374
399RETINIFY_API auto InitUndistortRectifyMap(const Intrinsics &intrinsics, const Distortion &distortion, const Mat3x3d &rotation, const Mat3x4d &projectionMatrix, std::uint32_t imageWidth, std::uint32_t imageHeight, float *mapX, std::size_t mapXStride, float *mapY, std::size_t mapYStride) noexcept -> Status;
400
417RETINIFY_API auto InitIdentityMap(float *mapX, std::size_t mapXStride, float *mapY, std::size_t mapYStride, std::size_t imageWidth, std::size_t imageHeight) noexcept -> Status;
418} // namespace retinify
#define RETINIFY_API
Defines a macro for setting API visibility to "default" for the retinify library.
Definition attributes.hpp:8
This class represents the status of an operation in the retinify library.
Definition status.hpp:51
Definition colormap.hpp:13
std::array< double, 2 > Vec2d
2D vector (double)
Definition geometry.hpp:17
RETINIFY_API auto Transpose(const Mat3x3d &mat) noexcept -> Mat3x3d
Transpose a 3x3 matrix.
RETINIFY_API auto Dot(const Vec3d &vec1, const Vec3d &vec2) noexcept -> double
Compute the dot product of two 3D vectors.
RETINIFY_API auto Multiply(const Mat3x3d &mat, const Vec3d &vec) noexcept -> Vec3d
Multiply a 3x3 matrix and a 3D vector.
RETINIFY_API auto DistortPoint(const Intrinsics &intrinsics, const Distortion &distortion, const Point2d &point) noexcept -> Point2d
Distort a normalized 2D point using the given camera intrinsics and distortion parameters.
std::array< double, 3 > Vec3d
3D vector (double)
Definition geometry.hpp:21
std::array< std::array< double, 3 >, 3 > Mat3x3d
3x3 matrix (double, row-major)
Definition geometry.hpp:33
std::array< double, 2 > Point2d
2D point (double)
Definition geometry.hpp:25
RETINIFY_API auto Exp(const Vec3d &vec) noexcept -> Mat3x3d
Compute the matrix exponential of a 3D rotation vector.
RETINIFY_API auto Identity() noexcept -> Mat3x3d
Create a 3x3 identity matrix.
RETINIFY_API auto Cross(const Vec3d &vec1, const Vec3d &vec2) noexcept -> Vec3d
Compute the cross product of two 3D vectors.
RETINIFY_API auto Length(const Vec3d &vec) noexcept -> double
Compute the length (magnitude) of a 3D vector.
std::array< double, 3 > Point3d
3D point (double)
Definition geometry.hpp:29
std::array< std::array< double, 4 >, 4 > Mat4x4d
4x4 matrix (double, row-major)
Definition geometry.hpp:41
RETINIFY_API auto Normalize(const Vec3d &vec) noexcept -> Vec3d
Normalize a 3D vector to unit length.
RETINIFY_API auto StereoRectify(const Intrinsics &intrinsics1, const Distortion &distortion1, const Intrinsics &intrinsics2, const Distortion &distortion2, const Mat3x3d &rotation, const Vec3d &translation, std::uint32_t imageWidth, std::uint32_t imageHeight, Mat3x3d &rotation1, Mat3x3d &rotation2, Mat3x4d &projectionMatrix1, Mat3x4d &projectionMatrix2, Mat4x4d &reprojectionMatrix, double alpha) noexcept -> Status
Perform stereo rectification for a pair of cameras.
RETINIFY_API auto InitUndistortRectifyMap(const Intrinsics &intrinsics, const Distortion &distortion, const Mat3x3d &rotation, const Mat3x4d &projectionMatrix, std::uint32_t imageWidth, std::uint32_t imageHeight, float *mapX, std::size_t mapXStride, float *mapY, std::size_t mapYStride) noexcept -> Status
Initialize undistort and rectify maps for image remapping.
RETINIFY_API auto InitIdentityMap(float *mapX, std::size_t mapXStride, float *mapY, std::size_t mapYStride, std::size_t imageWidth, std::size_t imageHeight) noexcept -> Status
Initialize identity maps for undistortion/rectification.
RETINIFY_API auto Vee(const Mat3x3d &mat) noexcept -> Vec3d
Convert a 3x3 skew-symmetric matrix to a 3D rotation vector.
RETINIFY_API auto Log(const Mat3x3d &mat) noexcept -> Vec3d
Compute the matrix logarithm of a 3x3 rotation matrix.
RETINIFY_API auto Hat(const Vec3d &vec) noexcept -> Mat3x3d
Create a 3x3 skew-symmetric matrix from a 3D rotation vector.
std::array< std::array< double, 4 >, 3 > Mat3x4d
3x4 matrix (double, row-major)
Definition geometry.hpp:37
RETINIFY_API auto Add(const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d
Add two 3x3 matrices.
RETINIFY_API auto Determinant(const Mat3x3d &mat) noexcept -> double
Compute the determinant of a 3x3 matrix.
RETINIFY_API auto UndistortPoint(const Intrinsics &intrinsics, const Distortion &distortion, const Point2d &point) noexcept -> Point2d
Undistort a 2D point using the given camera intrinsics and distortion parameters.
Stereo camera calibration parameters.
Definition geometry.hpp:266
Vec3d translation
Translation vector.
Definition geometry.hpp:284
std::uint32_t imageWidth
Image width (in pixels)
Definition geometry.hpp:287
Distortion leftDistortion
Distortion for the left camera.
Definition geometry.hpp:272
double calibrationError
Root mean square reprojection error (in pixels)
Definition geometry.hpp:293
Mat3x3d rotation
Rotation matrix.
Definition geometry.hpp:281
auto operator==(const CalibrationParameters &other) const noexcept -> bool
Definition geometry.hpp:298
Intrinsics rightIntrinsics
Intrinsics for the right camera.
Definition geometry.hpp:275
Distortion rightDistortion
Distortion for the right camera.
Definition geometry.hpp:278
std::uint32_t imageHeight
Image height (in pixels)
Definition geometry.hpp:290
std::int64_t calibrationTime
Calibration timestamp (in seconds since epoch, UTC)
Definition geometry.hpp:296
Intrinsics leftIntrinsics
Intrinsics for the left camera.
Definition geometry.hpp:269
Rational distortion model with 8 coefficients: (k1, k2, p1, p2, k3, k4, k5, k6)
Definition geometry.hpp:240
double p1
Definition geometry.hpp:243
double k6
Definition geometry.hpp:248
auto operator==(const Distortion &other) const noexcept -> bool
Definition geometry.hpp:250
double k4
Definition geometry.hpp:246
double k1
Definition geometry.hpp:241
double k2
Definition geometry.hpp:242
double p2
Definition geometry.hpp:244
double k3
Definition geometry.hpp:245
double k5
Definition geometry.hpp:247
Camera intrinsic parameters with focal lengths, principal point, and skew.
Definition geometry.hpp:210
auto operator==(const Intrinsics &other) const noexcept -> bool
Definition geometry.hpp:227
Rectangle structure.
Definition geometry.hpp:48
T y
Y coordinate of the top-left corner.
Definition geometry.hpp:54
T width
Width of the rectangle.
Definition geometry.hpp:57
T x
X coordinate of the top-left corner.
Definition geometry.hpp:51
T height
Height of the rectangle.
Definition geometry.hpp:60