16using Vec2d = std::array<double, 2>;
20using Vec3d = std::array<double, 3>;
32using Mat3x3d = std::array<std::array<double, 3>, 3>;
36using Mat3x4d = std::array<std::array<double, 4>, 3>;
40using Mat4x4d = std::array<std::array<double, 4>, 4>;
44using Vec2f = std::array<float, 2>;
48using Vec3f = std::array<float, 3>;
60using Mat3x3f = std::array<std::array<float, 3>, 3>;
64using Mat3x4f = std::array<std::array<float, 4>, 3>;
68using Mat4x4f = std::array<std::array<float, 4>, 4>;
74template <
typename T>
struct Rect2
210 return fx == other.fx &&
233 return k1 == other.k1 &&
361 std::uint32_t imageWidth, std::uint32_t imageHeight,
364 Mat4x4d &mappingMatrix,
double alpha)
noexcept -> void;
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;
410 float *mapy, std::size_t mapyStride,
411 std::size_t imageWidth, std::size_t imageHeight)
noexcept -> void;
#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