|
| using | retinify::Vec2d = std::array< double, 2 > |
| | 2D vector (double)
|
| |
| using | retinify::Vec3d = std::array< double, 3 > |
| | 3D vector (double)
|
| |
| using | retinify::Point2d = std::array< double, 2 > |
| | 2D point (double)
|
| |
| using | retinify::Point3d = std::array< double, 3 > |
| | 3D point (double)
|
| |
| using | retinify::Mat3x3d = std::array< std::array< double, 3 >, 3 > |
| | 3x3 matrix (double, row-major)
|
| |
| using | retinify::Mat3x4d = std::array< std::array< double, 4 >, 3 > |
| | 3x4 matrix (double, row-major)
|
| |
| using | retinify::Mat4x4d = std::array< std::array< double, 4 >, 4 > |
| | 4x4 matrix (double, row-major)
|
| |
| using | retinify::Rect2d = Rect2< double > |
| | 2D rectangle (double)
|
| |
|
| RETINIFY_API auto | retinify::Identity () noexcept -> Mat3x3d |
| | Create a 3x3 identity matrix.
|
| |
| RETINIFY_API auto | retinify::Determinant (const Mat3x3d &mat) noexcept -> double |
| | Compute the determinant of a 3x3 matrix.
|
| |
| RETINIFY_API auto | retinify::Transpose (const Mat3x3d &mat) noexcept -> Mat3x3d |
| | Transpose a 3x3 matrix.
|
| |
| RETINIFY_API auto | retinify::Add (const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d |
| | Add two 3x3 matrices.
|
| |
| RETINIFY_API auto | retinify::Multiply (const Mat3x3d &mat, const Vec3d &vec) noexcept -> Vec3d |
| | Multiply a 3x3 matrix and a 3D vector.
|
| |
| RETINIFY_API auto | retinify::Multiply (const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d |
| | Multiply two 3x3 matrices.
|
| |
| RETINIFY_API auto | retinify::Multiply (const Mat3x3d &mat, double scale) noexcept -> Mat3x3d |
| | Multiply a 3x3 matrix by a scalar value.
|
| |
| RETINIFY_API auto | retinify::Multiply (const Vec3d &vec, double scale) noexcept -> Vec3d |
| | Multiply a 3D vector by a scalar value.
|
| |
| RETINIFY_API auto | retinify::Length (const Vec3d &vec) noexcept -> double |
| | Compute the length (magnitude) of a 3D vector.
|
| |
| RETINIFY_API auto | retinify::Normalize (const Vec3d &vec) noexcept -> Vec3d |
| | Normalize a 3D vector to unit length.
|
| |
| RETINIFY_API auto | retinify::Dot (const Vec3d &vec1, const Vec3d &vec2) noexcept -> double |
| | Compute the dot product of two 3D vectors.
|
| |
| RETINIFY_API auto | retinify::Cross (const Vec3d &vec1, const Vec3d &vec2) noexcept -> Vec3d |
| | Compute the cross product of two 3D vectors.
|
| |
| RETINIFY_API auto | retinify::Hat (const Vec3d &vec) noexcept -> Mat3x3d |
| | Create a 3x3 skew-symmetric matrix from a 3D rotation vector.
|
| |
| RETINIFY_API auto | retinify::Vee (const Mat3x3d &mat) noexcept -> Vec3d |
| | Convert a 3x3 skew-symmetric matrix to a 3D rotation vector.
|
| |
| RETINIFY_API auto | retinify::Exp (const Vec3d &vec) noexcept -> Mat3x3d |
| | Compute the matrix exponential of a 3D rotation vector.
|
| |
| RETINIFY_API auto | retinify::Log (const Mat3x3d &mat) noexcept -> Vec3d |
| | Compute the matrix logarithm of a 3x3 rotation matrix.
|
| |
| RETINIFY_API auto | retinify::UndistortPoint (const Intrinsics &intrinsics, const Distortion &distortion, const Point2d &point) noexcept -> Point2d |
| | Undistort a 2D point using the given camera intrinsics and distortion parameters.
|
| |
| RETINIFY_API auto | retinify::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.
|
| |
| RETINIFY_API auto | retinify::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 | retinify::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 | retinify::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.
|
| |