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
45using Vec2f = std::array<float, 2>;
46
49using Vec3f = std::array<float, 3>;
50
53using Point2f = std::array<float, 2>;
54
57using Point3f = std::array<float, 3>;
58
61using Mat3x3f = std::array<std::array<float, 3>, 3>;
62
65using Mat3x4f = std::array<std::array<float, 4>, 3>;
66
69using Mat4x4f = std::array<std::array<float, 4>, 4>;
70
75template <typename T> struct Rect2
76{
79 T x{0};
82 T y{0};
85 T width{0};
88 T height{0};
89};
90
94
98
103RETINIFY_API auto Identity() noexcept -> Mat3x3d;
104
111RETINIFY_API auto Determinant(const Mat3x3d &mat) noexcept -> double;
112
119RETINIFY_API auto Transpose(const Mat3x3d &mat) noexcept -> Mat3x3d;
120
129RETINIFY_API auto Multiply(const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d;
130
139RETINIFY_API auto Multiply(const Mat3x3d &mat, const Vec3d &vec) noexcept -> Vec3d;
140
149RETINIFY_API auto Scale(const Vec3d &vec, double scale) noexcept -> Vec3d;
150
157RETINIFY_API auto Length(const Vec3d &vec) noexcept -> double;
158
165RETINIFY_API auto Normalize(const Vec3d &vec) noexcept -> Vec3d;
166
175RETINIFY_API auto Dot(const Vec3d &vec1, const Vec3d &vec2) noexcept -> double;
176
185RETINIFY_API auto Cross(const Vec3d &vec1, const Vec3d &vec2) noexcept -> Vec3d;
186
193RETINIFY_API auto Hat(const Vec3d &omega) noexcept -> Mat3x3d;
194
201RETINIFY_API auto Vee(const Mat3x3d &skew) noexcept -> Vec3d;
202
209RETINIFY_API auto Exp(const Vec3d &omega) noexcept -> Mat3x3d;
210
217RETINIFY_API auto Log(const Mat3x3d &rotation) noexcept -> Vec3d;
218
222{
225 double fx{0};
228 double fy{0};
231 double cx{0};
234 double cy{0};
237 double skew{0};
238
239 [[nodiscard]] auto operator==(const Intrinsics &other) const noexcept -> bool
240 {
241 return fx == other.fx && //
242 fy == other.fy && //
243 cx == other.cx && //
244 cy == other.cy && //
245 skew == other.skew;
246 }
247};
248
252{
253 double k1{0};
254 double k2{0};
255 double p1{0};
256 double p2{0};
257 double k3{0};
258 double k4{0};
259 double k5{0};
260 double k6{0};
261
262 [[nodiscard]] auto operator==(const Distortion &other) const noexcept -> bool
263 {
264 return k1 == other.k1 && //
265 k2 == other.k2 && //
266 p1 == other.p1 && //
267 p2 == other.p2 && //
268 k3 == other.k3 && //
269 k4 == other.k4 && //
270 k5 == other.k5 && //
271 k6 == other.k6;
272 }
273};
274
278{
279 double k1{0};
280 double k2{0};
281 double k3{0};
282 double k4{0};
283};
284
288{
309 std::uint32_t imageWidth{};
312 std::uint32_t imageHeight{};
318 std::int64_t calibrationTime{};
319
320 [[nodiscard]] auto operator==(const CalibrationParameters &other) const noexcept -> bool
321 {
322 return leftIntrinsics == other.leftIntrinsics && //
323 leftDistortion == other.leftDistortion && //
324 rightIntrinsics == other.rightIntrinsics && //
325 rightDistortion == other.rightDistortion && //
326 rotation == other.rotation && //
327 translation == other.translation && //
328 imageWidth == other.imageWidth && //
329 imageHeight == other.imageHeight && //
330 calibrationError == other.calibrationError && //
331 calibrationTime == other.calibrationTime; //
332 }
333};
334
345RETINIFY_API auto UndistortPoint(const Intrinsics &intrinsics, const Distortion &distortion, const Point2d &pixel) noexcept -> Point2d;
346
383RETINIFY_API auto StereoRectify(const Intrinsics &intrinsics1, const Distortion &distortion1, //
384 const Intrinsics &intrinsics2, const Distortion &distortion2, //
385 const Mat3x3d &rotation, const Vec3d &translation, //
386 std::uint32_t imageWidth, std::uint32_t imageHeight, //
387 Mat3x3d &rotation1, Mat3x3d &rotation2, //
388 Mat3x4d &projectionMatrix1, Mat3x4d &projectionMatrix2, //
389 Mat4x4d &mappingMatrix, double alpha) noexcept -> Status;
390
415RETINIFY_API auto InitUndistortRectifyMap(const Intrinsics &intrinsics, const Distortion &distortion, //
416 const Mat3x3d &rotation, const Mat3x4d &projectionMatrix, //
417 std::uint32_t imageWidth, std::uint32_t imageHeight, //
418 float *mapx, std::size_t mapxStride, //
419 float *mapy, std::size_t mapyStride) noexcept -> Status;
420
437RETINIFY_API auto InitIdentityMap(float *mapx, std::size_t mapxStride, //
438 float *mapy, std::size_t mapyStride, //
439 std::size_t imageWidth, std::size_t imageHeight) noexcept -> Status;
440} // 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.
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
RETINIFY_API auto Scale(const Vec3d &vec, double scale) noexcept -> Vec3d
Scale a 3D vector by a scalar value.
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 -> Status
Perform stereo rectification for a pair of cameras.
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 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.
std::array< double, 2 > Point2d
2D point (double)
Definition geometry.hpp:25
std::array< std::array< float, 4 >, 3 > Mat3x4f
3x4 matrix (float, row-major)
Definition geometry.hpp:65
std::array< std::array< float, 3 >, 3 > Mat3x3f
3x3 matrix (float, row-major)
Definition geometry.hpp:61
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:45
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:69
RETINIFY_API auto Vee(const Mat3x3d &skew) noexcept -> Vec3d
Convert a 3x3 skew-symmetric matrix to a 3D rotation vector.
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: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.
std::array< float, 3 > Point3f
3D point (float)
Definition geometry.hpp:57
std::array< float, 3 > Vec3f
3D vector (float)
Definition geometry.hpp:49
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:37
RETINIFY_API auto Hat(const Vec3d &omega) noexcept -> Mat3x3d
Create a 3x3 skew-symmetric matrix from a 3D rotation vector.
std::array< float, 2 > Point2f
2D point (float)
Definition geometry.hpp:53
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:288
Vec3d translation
Translation vector.
Definition geometry.hpp:306
std::uint32_t imageWidth
Image width (in pixels)
Definition geometry.hpp:309
Distortion leftDistortion
Distortion for the left camera.
Definition geometry.hpp:294
double calibrationError
Root mean square reprojection error (in pixels)
Definition geometry.hpp:315
Mat3x3d rotation
Rotation matrix.
Definition geometry.hpp:303
auto operator==(const CalibrationParameters &other) const noexcept -> bool
Definition geometry.hpp:320
Intrinsics rightIntrinsics
Intrinsics for the right camera.
Definition geometry.hpp:297
Distortion rightDistortion
Distortion for the right camera.
Definition geometry.hpp:300
std::uint32_t imageHeight
Image height (in pixels)
Definition geometry.hpp:312
std::int64_t calibrationTime
Calibration timestamp (in seconds since epoch, UTC)
Definition geometry.hpp:318
Intrinsics leftIntrinsics
Intrinsics for the left camera.
Definition geometry.hpp:291
Fisheye distortion model with 4 coefficients (k1, k2, k3, k4)
Definition geometry.hpp:278
double k1
Definition geometry.hpp:279
double k4
Definition geometry.hpp:282
double k3
Definition geometry.hpp:281
double k2
Definition geometry.hpp:280
Rational distortion model with 8 coefficients: (k1, k2, p1, p2, k3, k4, k5, k6)
Definition geometry.hpp:252
double p1
Definition geometry.hpp:255
double k6
Definition geometry.hpp:260
auto operator==(const Distortion &other) const noexcept -> bool
Definition geometry.hpp:262
double k4
Definition geometry.hpp:258
double k1
Definition geometry.hpp:253
double k2
Definition geometry.hpp:254
double p2
Definition geometry.hpp:256
double k3
Definition geometry.hpp:257
double k5
Definition geometry.hpp:259
Camera intrinsic parameters with focal lengths, principal point, and skew.
Definition geometry.hpp:222
auto operator==(const Intrinsics &other) const noexcept -> bool
Definition geometry.hpp:239
Rectangle structure.
Definition geometry.hpp:76
T y
Y coordinate of the top-left corner.
Definition geometry.hpp:82
T width
Width of the rectangle.
Definition geometry.hpp:85
T x
X coordinate of the top-left corner.
Definition geometry.hpp:79
T height
Height of the rectangle.
Definition geometry.hpp:88