17using Vec2d = std::array<double, 2>;
21using Vec3d = std::array<double, 3>;
33using Mat3x3d = std::array<std::array<double, 3>, 3>;
37using Mat3x4d = std::array<std::array<double, 4>, 3>;
41using Mat4x4d = std::array<std::array<double, 4>, 4>;
47template <
typename T>
struct Rect2
229 return fx == other.fx &&
252 return k1 == other.k1 &&
395RETINIFY_API auto StereoRectify(
const PinholeIntrinsics &intrinsics1,
const DistortionCoefficients &distortion1,
const PinholeIntrinsics &intrinsics2,
const DistortionCoefficients &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;
#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.
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 Undistort(const PinholeIntrinsics &intrinsics, const DistortionCoefficients &distortion, const std::uint8_t *src, std::size_t srcStride, std::uint8_t *dst, std::size_t dstStride, std::uint32_t imageWidth, std::uint32_t imageHeight) noexcept -> Status
Undistort an image using the given camera intrinsics and distortion coefficients.
RETINIFY_API auto UndistortPoint(const PinholeIntrinsics &intrinsics, const DistortionCoefficients &distortion, const Point2d &point) noexcept -> Point2d
Undistort a 2D point using the given camera intrinsics and distortion coefficients.
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.
RETINIFY_API auto InitUndistortRectifyMap(const PinholeIntrinsics &intrinsics, const DistortionCoefficients &distortion, const Mat3x3d &rotation, const Mat3x4d &projectionMatrix, float *mapX, std::size_t mapXStride, float *mapY, std::size_t mapYStride, std::uint32_t imageWidth, std::uint32_t imageHeight) noexcept -> Status
Initialize undistort and rectify maps for image remapping.
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 DistortPoint(const PinholeIntrinsics &intrinsics, const DistortionCoefficients &distortion, const Point2d &point) noexcept -> Point2d
Distort a normalized 2D point using the given camera intrinsics and distortion coefficients.
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 StereoRectify(const PinholeIntrinsics &intrinsics1, const DistortionCoefficients &distortion1, const PinholeIntrinsics &intrinsics2, const DistortionCoefficients &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 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.
Stereo camera calibration parameters.
Definition geometry.hpp:266
DistortionCoefficients rightDistortion
Distortion coefficients for the right camera.
Definition geometry.hpp:278
Vec3d translation
Translation vector.
Definition geometry.hpp:284
std::uint32_t imageWidth
Image width (in pixels)
Definition geometry.hpp:287
DistortionCoefficients leftDistortion
Distortion coefficients for the left camera.
Definition geometry.hpp:272
PinholeIntrinsics leftIntrinsics
Pinhole intrinsics for the left camera.
Definition geometry.hpp:269
PinholeIntrinsics rightIntrinsics
Pinhole intrinsics for the right camera.
Definition geometry.hpp:275
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
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
Rational distortion model with 8 coefficients: (k1, k2, p1, p2, k3, k4, k5, k6)
Definition geometry.hpp:240
double k5
Definition geometry.hpp:247
double k3
Definition geometry.hpp:245
double k1
Definition geometry.hpp:241
double p1
Definition geometry.hpp:243
double k4
Definition geometry.hpp:246
auto operator==(const DistortionCoefficients &other) const noexcept -> bool
Definition geometry.hpp:250
double k6
Definition geometry.hpp:248
double k2
Definition geometry.hpp:242
double p2
Definition geometry.hpp:244
Pinhole camera intrinsic parameters with focal lengths, principal point, and skew.
Definition geometry.hpp:210
auto operator==(const PinholeIntrinsics &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