retinify 0.2.0
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
8#include <array>
9#include <cstddef>
10#include <cstdint>
11
12namespace retinify
13{
16using Vec2d = std::array<double, 2>;
17
20using Vec3d = std::array<double, 3>;
21
24using Point2d = std::array<double, 2>;
25
28using Point3d = std::array<double, 3>;
29
32using Mat3x3d = std::array<std::array<double, 3>, 3>;
33
36using Mat3x4d = std::array<std::array<double, 4>, 3>;
37
40using Mat4x4d = std::array<std::array<double, 4>, 4>;
41
44using Vec2f = std::array<float, 2>;
45
48using Vec3f = std::array<float, 3>;
49
52using Point2f = std::array<float, 2>;
53
56using Point3f = std::array<float, 3>;
57
60using Mat3x3f = std::array<std::array<float, 3>, 3>;
61
64using Mat3x4f = std::array<std::array<float, 4>, 3>;
65
68using Mat4x4f = std::array<std::array<float, 4>, 4>;
69
74template <typename T> struct Rect2
75{
77 T x{0};
79 T y{0};
81 T width{0};
83 T height{0};
84};
85
89
93
98RETINIFY_API auto Identity() noexcept -> Mat3x3d;
99
106RETINIFY_API auto Determinant(const Mat3x3d &mat) noexcept -> double;
107
114RETINIFY_API auto Transpose(const Mat3x3d &mat) noexcept -> Mat3x3d;
115
124RETINIFY_API auto Multiply(const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d;
125
134RETINIFY_API auto Multiply(const Mat3x3d &mat, const Vec3d &vec) noexcept -> Vec3d;
135
144RETINIFY_API auto Scale(const Vec3d &vec, double scale) noexcept -> Vec3d;
145
152RETINIFY_API auto Length(const Vec3d &vec) noexcept -> double;
153
160RETINIFY_API auto Normalize(const Vec3d &vec) noexcept -> Vec3d;
161
170RETINIFY_API auto Cross(const Vec3d &vec1, const Vec3d &vec2) noexcept -> Vec3d;
171
178RETINIFY_API auto Exp(const Vec3d &omega) noexcept -> Mat3x3d;
179
186RETINIFY_API auto Log(const Mat3x3d &rotation) noexcept -> Vec3d;
187
191{
194 double fx{0};
197 double fy{0};
200 double cx{0};
203 double cy{0};
206 double skew{0};
207
208 [[nodiscard]] auto operator==(const Intrinsics &other) const noexcept -> bool
209 {
210 return fx == other.fx && //
211 fy == other.fy && //
212 cx == other.cx && //
213 cy == other.cy && //
214 skew == other.skew;
215 }
216};
217
221{
222 double k1{0};
223 double k2{0};
224 double p1{0};
225 double p2{0};
226 double k3{0};
227 double k4{0};
228 double k5{0};
229 double k6{0};
230
231 [[nodiscard]] auto operator==(const Distortion &other) const noexcept -> bool
232 {
233 return k1 == other.k1 && //
234 k2 == other.k2 && //
235 p1 == other.p1 && //
236 p2 == other.p2 && //
237 k3 == other.k3 && //
238 k4 == other.k4 && //
239 k5 == other.k5 && //
240 k6 == other.k6;
241 }
242};
243
247{
248 double k1{0};
249 double k2{0};
250 double k3{0};
251 double k4{0};
252};
253
257{
278 std::uint32_t imageWidth{};
281 std::uint32_t imageHeight{};
287 std::uint64_t calibrationTime{};
290 std::array<char, 128> leftCameraSerial{};
293 std::array<char, 128> rightCameraSerial{};
294
295 [[nodiscard]] auto operator==(const CalibrationParameters &other) const noexcept -> bool
296 {
297 return leftIntrinsics == other.leftIntrinsics && //
298 leftDistortion == other.leftDistortion && //
299 rightIntrinsics == other.rightIntrinsics && //
300 rightDistortion == other.rightDistortion && //
301 rotation == other.rotation && //
302 translation == other.translation && //
303 imageWidth == other.imageWidth && //
304 imageHeight == other.imageHeight && //
305 reprojectionError == other.reprojectionError && //
306 calibrationTime == other.calibrationTime && //
307 leftCameraSerial == other.leftCameraSerial && //
308 rightCameraSerial == other.rightCameraSerial; //
309 }
310};
311
322RETINIFY_API auto UndistortPoint(const Intrinsics &intrinsics, const Distortion &distortion, const Point2d &pixel) noexcept -> Point2d;
323
358RETINIFY_API auto StereoRectify(const Intrinsics &intrinsics1, const Distortion &distortion1, //
359 const Intrinsics &intrinsics2, const Distortion &distortion2, //
360 const Mat3x3d &rotation, const Vec3d &translation, //
361 std::uint32_t imageWidth, std::uint32_t imageHeight, //
362 Mat3x3d &rotation1, Mat3x3d &rotation2, //
363 Mat3x4d &projectionMatrix1, Mat3x4d &projectionMatrix2, //
364 Mat4x4d &mappingMatrix, double alpha) noexcept -> void;
365
389RETINIFY_API auto InitUndistortRectifyMap(const Intrinsics &intrinsics, const Distortion &distortion, //
390 const Mat3x3d &rotation, const Mat3x4d &projectionMatrix, //
391 std::uint32_t imageWidth, std::uint32_t imageHeight, //
392 float *mapx, std::size_t mapxStride, //
393 float *mapy, std::size_t mapyStride) noexcept -> void;
394
409RETINIFY_API auto InitIdentityMap(float *mapx, std::size_t mapxStride, //
410 float *mapy, std::size_t mapyStride, //
411 std::size_t imageWidth, std::size_t imageHeight) noexcept -> void;
412} // namespace retinify
#define RETINIFY_API
Defines a macro for setting API visibility to "default" for the retinify library.
Definition attributes.hpp:8
Definition colormap.hpp:13
std::array< double, 2 > Vec2d
2D vector (double).
Definition geometry.hpp:16
RETINIFY_API auto Transpose(const Mat3x3d &mat) noexcept -> Mat3x3d
Transpose a 3x3 matrix.
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 -> void
Initialize identity maps for undistortion/rectification.
std::array< double, 3 > Vec3d
3D vector (double).
Definition geometry.hpp:20
std::array< std::array< double, 3 >, 3 > Mat3x3d
3x3 matrix (double, row-major).
Definition geometry.hpp:32
RETINIFY_API auto Scale(const Vec3d &vec, double scale) noexcept -> Vec3d
Scale a 3D vector by a scalar value.
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 -> void
Initialize undistort and rectify maps for image remapping.
std::array< double, 2 > Point2d
2D point (double).
Definition geometry.hpp:24
std::array< std::array< float, 4 >, 3 > Mat3x4f
3x4 matrix (float, row-major).
Definition geometry.hpp:64
std::array< std::array< float, 3 >, 3 > Mat3x3f
3x3 matrix (float, row-major).
Definition geometry.hpp:60
RETINIFY_API auto Log(const Mat3x3d &rotation) noexcept -> Vec3d
Compute the matrix logarithm of a 3x3 rotation matrix.
std::array< float, 2 > Vec2f
2D vector (float).
Definition geometry.hpp:44
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 &mappingMatrix, double alpha) noexcept -> void
Perform stereo rectification for a pair of cameras.
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.
std::array< std::array< float, 4 >, 4 > Mat4x4f
4x4 matrix (float, row-major).
Definition geometry.hpp:68
RETINIFY_API auto Length(const Vec3d &vec) noexcept -> double
Compute the length (magnitude) of a 3D vector.
RETINIFY_API auto UndistortPoint(const Intrinsics &intrinsics, const Distortion &distortion, const Point2d &pixel) noexcept -> Point2d
Undistort a 2D point using the given camera intrinsics and distortion parameters.
std::array< double, 3 > Point3d
3D point (double).
Definition geometry.hpp:28
std::array< std::array< double, 4 >, 4 > Mat4x4d
4x4 matrix (double, row-major).
Definition geometry.hpp:40
RETINIFY_API auto Normalize(const Vec3d &vec) noexcept -> Vec3d
Normalize a 3D vector to unit length.
std::array< float, 3 > Point3f
3D point (float).
Definition geometry.hpp:56
std::array< float, 3 > Vec3f
3D vector (float).
Definition geometry.hpp:48
RETINIFY_API auto Multiply(const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d
Multiply two 3x3 matrices.
std::array< std::array< double, 4 >, 3 > Mat3x4d
3x4 matrix (double, row-major).
Definition geometry.hpp:36
std::array< float, 2 > Point2f
2D point (float).
Definition geometry.hpp:52
RETINIFY_API auto Determinant(const Mat3x3d &mat) noexcept -> double
Compute the determinant of a 3x3 matrix.
RETINIFY_API auto Exp(const Vec3d &omega) noexcept -> Mat3x3d
Compute the matrix exponential of a 3D rotation vector.
Stereo camera calibration parameters.
Definition geometry.hpp:257
std::array< char, 128 > rightCameraSerial
Right camera hardware serial.
Definition geometry.hpp:293
Vec3d translation
Translation from the left to the right camera.
Definition geometry.hpp:275
std::uint32_t imageWidth
Image width [pixels].
Definition geometry.hpp:278
Distortion leftDistortion
Distortion for the left camera.
Definition geometry.hpp:263
std::uint64_t calibrationTime
Calibration timestamp in Unix time [nanoseconds].
Definition geometry.hpp:287
std::array< char, 128 > leftCameraSerial
Left camera hardware serial.
Definition geometry.hpp:290
double reprojectionError
Root mean square reprojection error [pixels].
Definition geometry.hpp:284
Mat3x3d rotation
Rotation from the left to the right camera.
Definition geometry.hpp:272
auto operator==(const CalibrationParameters &other) const noexcept -> bool
Definition geometry.hpp:295
Intrinsics rightIntrinsics
Intrinsics for the right camera.
Definition geometry.hpp:266
Distortion rightDistortion
Distortion for the right camera.
Definition geometry.hpp:269
std::uint32_t imageHeight
Image height [pixels].
Definition geometry.hpp:281
Intrinsics leftIntrinsics
Intrinsics for the left camera.
Definition geometry.hpp:260
Fisheye distortion model with 4 coefficients (k1, k2, k3, k4).
Definition geometry.hpp:247
double k1
Definition geometry.hpp:248
double k4
Definition geometry.hpp:251
double k3
Definition geometry.hpp:250
double k2
Definition geometry.hpp:249
Rational distortion model with 8 coefficients: (k1, k2, p1, p2, k3, k4, k5, k6).
Definition geometry.hpp:221
double p1
Definition geometry.hpp:224
double k6
Definition geometry.hpp:229
auto operator==(const Distortion &other) const noexcept -> bool
Definition geometry.hpp:231
double k4
Definition geometry.hpp:227
double k1
Definition geometry.hpp:222
double k2
Definition geometry.hpp:223
double p2
Definition geometry.hpp:225
double k3
Definition geometry.hpp:226
double k5
Definition geometry.hpp:228
Camera intrinsic parameters with focal lengths, principal point, and skew.
Definition geometry.hpp:191
auto operator==(const Intrinsics &other) const noexcept -> bool
Definition geometry.hpp:208
Rectangle structure.
Definition geometry.hpp:75
T y
Y coordinate of the top-left corner.
Definition geometry.hpp:79
T width
Width of the rectangle.
Definition geometry.hpp:81
T x
X coordinate of the top-left corner.
Definition geometry.hpp:77
T height
Height of the rectangle.
Definition geometry.hpp:83