retinify 0.1.7
Real-Time AI Stereo Vision Library
Loading...
Searching...
No Matches
retinify Namespace Reference

Classes

struct  CalibrationParameters
 Stereo camera calibration parameters. More...
 
struct  DistortionCoefficients
 Rational distortion model with 8 coefficients: (k1, k2, p1, p2, k3, k4, k5, k6) More...
 
class  NoCopyMove
 Base class that disables copy and move operations for derived classes. More...
 
struct  PinholeIntrinsics
 Pinhole camera intrinsic parameters with focal lengths, principal point, and skew. More...
 
class  Pipeline
 A retinify::Pipeline provides an interface for running a stereo matching. More...
 
struct  Rect2
 Rectangle structure. More...
 
class  Status
 This class represents the status of an operation in the retinify library. More...
 

Typedefs

using Vec2d = std::array< double, 2 >
 2D vector (double)
 
using Vec3d = std::array< double, 3 >
 3D vector (double)
 
using Point2d = std::array< double, 2 >
 2D point (double)
 
using Point3d = std::array< double, 3 >
 3D point (double)
 
using Mat3x3d = std::array< std::array< double, 3 >, 3 >
 3x3 matrix (double, row-major)
 
using Mat3x4d = std::array< std::array< double, 4 >, 3 >
 3x4 matrix (double, row-major)
 
using Mat4x4d = std::array< std::array< double, 4 >, 4 >
 4x4 matrix (double, row-major)
 
using Rect2d = Rect2< double >
 2D rectangle (double)
 

Enumerations

enum class  LogLevel : std::uint8_t {
  DEBUG , INFO , WARN , ERROR ,
  FATAL , OFF
}
 Logging verbosity levels. More...
 
enum class  LogLocation : std::uint8_t { NONE , FUNCTION }
 Logging source location options. More...
 
enum class  PixelFormat : std::uint8_t { GRAY8 , RGB8 }
 The pixel format options for input images. More...
 
enum class  DepthMode : std::uint8_t { FAST , BALANCED , ACCURATE }
 The depth mode options for stereo matching pipeline. More...
 
enum class  StatusCategory : std::uint8_t {
  NONE , RETINIFY , SYSTEM , CUDA ,
  USER
}
 Status categories used by retinify. More...
 
enum class  StatusCode : std::uint8_t { OK , FAIL , INVALID_ARGUMENT }
 Status codes returned by retinify operations. More...
 

Functions

RETINIFY_API auto ColorizeDisparity (const float *src, std::size_t srcStride, std::uint8_t *dst, std::size_t dstStride, std::uint32_t imageWidth, std::uint32_t imageHeight, float maxDisparity) noexcept -> Status
 Applies the colormap to the disparity map.
 
RETINIFY_API auto ColorizeDepth (const float *src, std::size_t srcStride, std::uint8_t *dst, std::size_t dstStride, std::uint32_t imageWidth, std::uint32_t imageHeight, float maxDepth) noexcept -> Status
 Applies the colormap to the depth map.
 
RETINIFY_API auto Identity () noexcept -> Mat3x3d
 Create a 3x3 identity matrix.
 
RETINIFY_API auto Determinant (const Mat3x3d &mat) noexcept -> double
 Compute the determinant of a 3x3 matrix.
 
RETINIFY_API auto Transpose (const Mat3x3d &mat) noexcept -> Mat3x3d
 Transpose a 3x3 matrix.
 
RETINIFY_API auto Add (const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d
 Add two 3x3 matrices.
 
RETINIFY_API auto Multiply (const Mat3x3d &mat, const Vec3d &vec) noexcept -> Vec3d
 Multiply a 3x3 matrix and a 3D vector.
 
RETINIFY_API auto Multiply (const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d
 Multiply two 3x3 matrices.
 
RETINIFY_API auto Multiply (const Mat3x3d &mat, double scale) noexcept -> Mat3x3d
 Multiply a 3x3 matrix by a scalar value.
 
RETINIFY_API auto Multiply (const Vec3d &vec, double scale) noexcept -> Vec3d
 Multiply a 3D vector by a scalar value.
 
RETINIFY_API auto Length (const Vec3d &vec) noexcept -> double
 Compute the length (magnitude) of a 3D vector.
 
RETINIFY_API auto Normalize (const Vec3d &vec) noexcept -> Vec3d
 Normalize a 3D vector to unit length.
 
RETINIFY_API auto Dot (const Vec3d &vec1, const Vec3d &vec2) noexcept -> double
 Compute the dot product of two 3D vectors.
 
RETINIFY_API auto Cross (const Vec3d &vec1, const Vec3d &vec2) noexcept -> Vec3d
 Compute the cross product of two 3D vectors.
 
RETINIFY_API auto Hat (const Vec3d &vec) noexcept -> Mat3x3d
 Create a 3x3 skew-symmetric matrix from a 3D rotation vector.
 
RETINIFY_API auto Vee (const Mat3x3d &mat) noexcept -> Vec3d
 Convert a 3x3 skew-symmetric matrix to a 3D rotation vector.
 
RETINIFY_API auto Exp (const Vec3d &vec) noexcept -> Mat3x3d
 Compute the matrix exponential of 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 UndistortPoint (const PinholeIntrinsics &intrinsics, const DistortionCoefficients &distortion, const Point2d &point) noexcept -> Point2d
 Undistort a 2D point using the given camera intrinsics and distortion coefficients.
 
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 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 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 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.
 
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 Resize (const std::uint8_t *src, std::size_t srcStride, std::uint8_t *dst, std::size_t dstStride, std::size_t srcWidth, std::size_t srcHeight, std::size_t dstWidth, std::size_t dstHeight, std::size_t channels) noexcept -> Status
 Resize an 8-bit image using bilinear interpolation.
 
RETINIFY_API auto Remap (const std::uint8_t *src, std::size_t srcStride, std::uint8_t *dst, std::size_t dstStride, const float *mapX, std::size_t mapXStride, const float *mapY, std::size_t mapYStride, std::size_t imageWidth, std::size_t imageHeight, std::size_t channels) noexcept -> Status
 Remap an 8-bit image using the provided x/y coordinate maps.
 
RETINIFY_API auto SaveCalibrationParameters (const char *filename, const CalibrationParameters &parameters) noexcept -> Status
 Save stereo calibration parameters.
 
RETINIFY_API auto LoadCalibrationParameters (const char *filename, CalibrationParameters &parameters) noexcept -> Status
 Load stereo calibration parameters.
 
RETINIFY_API auto GetLogLevel () noexcept -> LogLevel
 Returns the current log level.
 
RETINIFY_API auto SetLogLevel (LogLevel level) noexcept -> void
 Sets the log level.
 
RETINIFY_API auto GetLogLocation () noexcept -> LogLocation
 Returns the current log location setting.
 
RETINIFY_API auto SetLogLocation (LogLocation location) noexcept -> void
 Sets the log location setting.
 
RETINIFY_API auto LogDebug (const char *message, std::source_location location=std::source_location::current()) noexcept -> void
 Logs a debug message.
 
RETINIFY_API auto LogInfo (const char *message, std::source_location location=std::source_location::current()) noexcept -> void
 Logs an informational message.
 
RETINIFY_API auto LogWarn (const char *message, std::source_location location=std::source_location::current()) noexcept -> void
 Logs a warning message.
 
RETINIFY_API auto LogError (const char *message, std::source_location location=std::source_location::current()) noexcept -> void
 Logs an error message.
 
RETINIFY_API auto LogFatal (const char *message, std::source_location location=std::source_location::current()) noexcept -> void
 Logs a fatal error message.
 
RETINIFY_API auto LogSoftwareInfo (std::source_location location=std::source_location::current()) noexcept -> void
 Logs basic information about the retinify library.
 
RETINIFY_API auto LogStrideError (std::size_t providedStride, std::size_t requiredStride, std::source_location location=std::source_location::current()) noexcept -> void
 Logs an error indicating that the provided stride is smaller than the required stride.
 
template<typename Function >
auto NoThrow (Function &&function) noexcept -> Status
 Executes a function and converts any exception into a Status.
 
RETINIFY_API auto HomeDirectoryPath (std::filesystem::path &path) noexcept -> Status
 Returns the current user’s home directory path.
 
RETINIFY_API auto ConfigDirectoryPath (std::filesystem::path &path) noexcept -> Status
 Returns the configuration directory path for retinify.
 
RETINIFY_API auto CacheDirectoryPath (std::filesystem::path &path) noexcept -> Status
 Returns the cache directory path for retinify.
 
RETINIFY_API auto DataDirectoryPath (std::filesystem::path &path) noexcept -> Status
 Returns the data directory path for retinify.
 
RETINIFY_API auto StateDirectoryPath (std::filesystem::path &path) noexcept -> Status
 Returns the state directory path for retinify.
 
RETINIFY_API auto Version () noexcept -> const char *
 Returns the retinify library version in semantic versioning format.
 

Typedef Documentation

◆ Mat3x3d

using retinify::Mat3x3d = typedef std::array<std::array<double, 3>, 3>

3x3 matrix (double, row-major)

◆ Mat3x4d

using retinify::Mat3x4d = typedef std::array<std::array<double, 4>, 3>

3x4 matrix (double, row-major)

◆ Mat4x4d

using retinify::Mat4x4d = typedef std::array<std::array<double, 4>, 4>

4x4 matrix (double, row-major)

◆ Point2d

using retinify::Point2d = typedef std::array<double, 2>

2D point (double)

◆ Point3d

using retinify::Point3d = typedef std::array<double, 3>

3D point (double)

◆ Rect2d

using retinify::Rect2d = typedef Rect2<double>

2D rectangle (double)

◆ Vec2d

using retinify::Vec2d = typedef std::array<double, 2>

2D vector (double)

◆ Vec3d

using retinify::Vec3d = typedef std::array<double, 3>

3D vector (double)

Enumeration Type Documentation

◆ DepthMode

enum class retinify::DepthMode : std::uint8_t
strong

The depth mode options for stereo matching pipeline.

Enumerator
FAST 

Fastest, with lowest accuracy.

BALANCED 

Balanced, with moderate accuracy and speed.

ACCURATE 

Most accurate, with slowest performance.

◆ LogLevel

enum class retinify::LogLevel : std::uint8_t
strong

Logging verbosity levels.

Enumerator
DEBUG 

Debug messages.

INFO 

Informational messages.

WARN 

Warning messages.

ERROR 

Error messages.

FATAL 

Fatal Error messages.

OFF 

Disable all logging.

◆ LogLocation

enum class retinify::LogLocation : std::uint8_t
strong

Logging source location options.

Enumerator
NONE 

No source location.

FUNCTION 

Function name.

◆ PixelFormat

enum class retinify::PixelFormat : std::uint8_t
strong

The pixel format options for input images.

Enumerator
GRAY8 

8-bit 1ch, Grayscale format

RGB8 

8-bit 3ch, RGB format

◆ StatusCategory

enum class retinify::StatusCategory : std::uint8_t
strong

Status categories used by retinify.

Enumerator
NONE 

No category.

RETINIFY 

Retinify-internal category.

SYSTEM 

System-related category.

CUDA 

CUDA-related category.

USER 

User-originated category.

◆ StatusCode

enum class retinify::StatusCode : std::uint8_t
strong

Status codes returned by retinify operations.

Enumerator
OK 

Operation succeeded.

FAIL 

Operation failed.

INVALID_ARGUMENT 

Invalid argument provided.

Function Documentation

◆ Add()

RETINIFY_API auto retinify::Add ( const Mat3x3d mat1,
const Mat3x3d mat2 
) -> Mat3x3d
noexcept

Add two 3x3 matrices.

Parameters
mat1First 3x3 matrix
mat2Second 3x3 matrix
Returns
3x3 matrix

◆ CacheDirectoryPath()

RETINIFY_API auto retinify::CacheDirectoryPath ( std::filesystem::path &  path) -> Status
noexcept

Returns the cache directory path for retinify.

Parameters
pathOutput cache directory path
Returns
A Status object that indicates whether the operation was successful

◆ ColorizeDepth()

RETINIFY_API auto retinify::ColorizeDepth ( const float *  src,
std::size_t  srcStride,
std::uint8_t *  dst,
std::size_t  dstStride,
std::uint32_t  imageWidth,
std::uint32_t  imageHeight,
float  maxDepth 
) -> Status
noexcept

Applies the colormap to the depth map.

Parameters
srcInput depth map (32-bit float)
srcStrideStride of the input depth map (in bytes)
dstOutput colored depth map (8-bit 3-channel RGB)
dstStrideStride of the output colored depth map (in bytes)
imageWidthWidth of the input and output depth maps (in pixels)
imageHeightHeight of the input and output depth maps (in pixels)
maxDepthMaximum depth value
Returns
A Status object that indicates whether the operation was successful

◆ ColorizeDisparity()

RETINIFY_API auto retinify::ColorizeDisparity ( const float *  src,
std::size_t  srcStride,
std::uint8_t *  dst,
std::size_t  dstStride,
std::uint32_t  imageWidth,
std::uint32_t  imageHeight,
float  maxDisparity 
) -> Status
noexcept

Applies the colormap to the disparity map.

Parameters
srcInput disparity map (32-bit float)
srcStrideStride of the input disparity map (in bytes)
dstOutput colored disparity map (8-bit 3-channel RGB)
dstStrideStride of the output colored disparity map (in bytes)
imageWidthWidth of the input and output disparity maps (in pixels)
imageHeightHeight of the input and output disparity maps (in pixels)
maxDisparityMaximum disparity value
Returns
A Status object that indicates whether the operation was successful

◆ ConfigDirectoryPath()

RETINIFY_API auto retinify::ConfigDirectoryPath ( std::filesystem::path &  path) -> Status
noexcept

Returns the configuration directory path for retinify.

Parameters
pathOutput configuration directory path
Returns
A Status object that indicates whether the operation was successful

◆ Cross()

RETINIFY_API auto retinify::Cross ( const Vec3d vec1,
const Vec3d vec2 
) -> Vec3d
noexcept

Compute the cross product of two 3D vectors.

Parameters
vec1First 3D vector
vec2Second 3D vector
Returns
Cross product vector

◆ DataDirectoryPath()

RETINIFY_API auto retinify::DataDirectoryPath ( std::filesystem::path &  path) -> Status
noexcept

Returns the data directory path for retinify.

Parameters
pathOutput data directory path
Returns
A Status object that indicates whether the operation was successful

◆ Determinant()

RETINIFY_API auto retinify::Determinant ( const Mat3x3d mat) -> double
noexcept

Compute the determinant of a 3x3 matrix.

Parameters
mat3x3 matrix
Returns
Determinant value

◆ DistortPoint()

RETINIFY_API auto retinify::DistortPoint ( const PinholeIntrinsics intrinsics,
const DistortionCoefficients distortion,
const Point2d point 
) -> Point2d
noexcept

Distort a normalized 2D point using the given camera intrinsics and distortion coefficients.

Parameters
intrinsicsCamera intrinsic parameters
distortionDistortion coefficients
pointUndistorted 2D point (normalized image coordinates)
Returns
Distorted 2D point (in pixel coordinates)

◆ Dot()

RETINIFY_API auto retinify::Dot ( const Vec3d vec1,
const Vec3d vec2 
) -> double
noexcept

Compute the dot product of two 3D vectors.

Parameters
vec1First 3D vector
vec2Second 3D vector
Returns
Dot product value

◆ Exp()

RETINIFY_API auto retinify::Exp ( const Vec3d vec) -> Mat3x3d
noexcept

Compute the matrix exponential of a 3D rotation vector.

Parameters
vec3D rotation vector
Returns
3x3 rotation matrix

◆ GetLogLevel()

RETINIFY_API auto retinify::GetLogLevel ( ) -> LogLevel
noexcept

Returns the current log level.

Returns
The current log level

◆ GetLogLocation()

RETINIFY_API auto retinify::GetLogLocation ( ) -> LogLocation
noexcept

Returns the current log location setting.

Returns
The current log location setting

◆ Hat()

RETINIFY_API auto retinify::Hat ( const Vec3d vec) -> Mat3x3d
noexcept

Create a 3x3 skew-symmetric matrix from a 3D rotation vector.

Parameters
vec3D rotation vector
Returns
3x3 skew-symmetric matrix

◆ HomeDirectoryPath()

RETINIFY_API auto retinify::HomeDirectoryPath ( std::filesystem::path &  path) -> Status
noexcept

Returns the current user’s home directory path.

Parameters
pathOutput home directory path
Returns
A Status object that indicates whether the operation was successful

◆ Identity()

RETINIFY_API auto retinify::Identity ( ) -> Mat3x3d
noexcept

Create a 3x3 identity matrix.

Returns
3x3 identity matrix

◆ InitIdentityMap()

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 
) -> Status
noexcept

Initialize identity maps for undistortion/rectification.

Parameters
mapXOutput map for x-coordinates
mapXStrideStride of a row in mapX (in bytes)
mapYOutput map for y-coordinates
mapYStrideStride of a row in mapY (in bytes)
imageWidthImage width (in pixels)
imageHeightImage height (in pixels)
Returns
A Status object that indicates whether the operation was successful

◆ InitUndistortRectifyMap()

RETINIFY_API auto retinify::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 
) -> Status
noexcept

Initialize undistort and rectify maps for image remapping.

Parameters
intrinsicsCamera intrinsics
distortionDistortion coefficients
rotationRectification rotation
projectionMatrixProjection matrix
mapXOutput map for x-coordinates
mapXStrideStride of a row in mapX (in bytes)
mapYOutput map for y-coordinates
mapYStrideStride of a row in mapY (in bytes)
imageWidthImage width (in pixels)
imageHeightImage height (in pixels)
Returns
A Status object that indicates whether the operation was successful

◆ Length()

RETINIFY_API auto retinify::Length ( const Vec3d vec) -> double
noexcept

Compute the length (magnitude) of a 3D vector.

Parameters
vec3D vector
Returns
Length value

◆ LoadCalibrationParameters()

RETINIFY_API auto retinify::LoadCalibrationParameters ( const char *  filename,
CalibrationParameters parameters 
) -> Status
noexcept

Load stereo calibration parameters.

Parameters
filenamePath to the input file
parametersCalibration parameters to load into
Returns
A Status object that indicates whether the operation was successful

◆ Log()

RETINIFY_API auto retinify::Log ( const Mat3x3d mat) -> Vec3d
noexcept

Compute the matrix logarithm of a 3x3 rotation matrix.

Parameters
mat3x3 rotation matrix
Returns
3D rotation vector

◆ LogDebug()

RETINIFY_API auto retinify::LogDebug ( const char *  message,
std::source_location  location = std::source_location::current() 
) -> void
noexcept

Logs a debug message.

Parameters
messageThe message to log
locationThe source location of the log call (defaults to the call site)

◆ LogError()

RETINIFY_API auto retinify::LogError ( const char *  message,
std::source_location  location = std::source_location::current() 
) -> void
noexcept

Logs an error message.

Parameters
messageThe message to log
locationThe source location of the log call (defaults to the call site)

◆ LogFatal()

RETINIFY_API auto retinify::LogFatal ( const char *  message,
std::source_location  location = std::source_location::current() 
) -> void
noexcept

Logs a fatal error message.

Parameters
messageThe message to log
locationThe source location of the log call (defaults to the call site)

◆ LogInfo()

RETINIFY_API auto retinify::LogInfo ( const char *  message,
std::source_location  location = std::source_location::current() 
) -> void
noexcept

Logs an informational message.

Parameters
messageThe message to log
locationThe source location of the log call (defaults to the call site)

◆ LogSoftwareInfo()

RETINIFY_API auto retinify::LogSoftwareInfo ( std::source_location  location = std::source_location::current()) -> void
noexcept

Logs basic information about the retinify library.

Parameters
locationThe source location of the log call (defaults to the call site)

◆ LogStrideError()

RETINIFY_API auto retinify::LogStrideError ( std::size_t  providedStride,
std::size_t  requiredStride,
std::source_location  location = std::source_location::current() 
) -> void
noexcept

Logs an error indicating that the provided stride is smaller than the required stride.

Parameters
providedStrideThe provided stride value (in bytes)
requiredStrideThe required stride value (in bytes)
locationThe source location of the log call (defaults to the call site)

◆ LogWarn()

RETINIFY_API auto retinify::LogWarn ( const char *  message,
std::source_location  location = std::source_location::current() 
) -> void
noexcept

Logs a warning message.

Parameters
messageThe message to log
locationThe source location of the log call (defaults to the call site)

◆ Multiply() [1/4]

RETINIFY_API auto retinify::Multiply ( const Mat3x3d mat,
const Vec3d vec 
) -> Vec3d
noexcept

Multiply a 3x3 matrix and a 3D vector.

Parameters
mat3x3 matrix
vec3D vector
Returns
3D vector

◆ Multiply() [2/4]

RETINIFY_API auto retinify::Multiply ( const Mat3x3d mat,
double  scale 
) -> Mat3x3d
noexcept

Multiply a 3x3 matrix by a scalar value.

Parameters
mat3x3 matrix
scaleScalar value
Returns
3x3 matrix

◆ Multiply() [3/4]

RETINIFY_API auto retinify::Multiply ( const Mat3x3d mat1,
const Mat3x3d mat2 
) -> Mat3x3d
noexcept

Multiply two 3x3 matrices.

Parameters
mat1First 3x3 matrix
mat2Second 3x3 matrix
Returns
3x3 matrix

◆ Multiply() [4/4]

RETINIFY_API auto retinify::Multiply ( const Vec3d vec,
double  scale 
) -> Vec3d
noexcept

Multiply a 3D vector by a scalar value.

Parameters
vec3D vector
scaleScalar value
Returns
3D vector

◆ Normalize()

RETINIFY_API auto retinify::Normalize ( const Vec3d vec) -> Vec3d
noexcept

Normalize a 3D vector to unit length.

Parameters
vec3D vector
Returns
Normalized 3D vector

◆ NoThrow()

template<typename Function >
auto retinify::NoThrow ( Function &&  function) -> Status
noexcept

Executes a function and converts any exception into a Status.

Template Parameters
FunctionThe type of the function to execute.
Parameters
functionThe function to execute.
Returns
A Status object that indicates whether the operation was successful

◆ Remap()

RETINIFY_API auto retinify::Remap ( const std::uint8_t *  src,
std::size_t  srcStride,
std::uint8_t *  dst,
std::size_t  dstStride,
const float *  mapX,
std::size_t  mapXStride,
const float *  mapY,
std::size_t  mapYStride,
std::size_t  imageWidth,
std::size_t  imageHeight,
std::size_t  channels 
) -> Status
noexcept

Remap an 8-bit image using the provided x/y coordinate maps.

Parameters
srcInput image data pointer
srcStrideStride of a row in the source image (in bytes)
dstOutput image data pointer
dstStrideStride of a row in the destination image (in bytes)
mapXMap for x-coordinates
mapXStrideStride of a row in mapX (in bytes)
mapYMap for y-coordinates
mapYStrideStride of a row in mapY (in bytes)
imageWidthImage width (in pixels)
imageHeightImage height (in pixels)
channelsNumber of channels (1 or 3)
Returns
A Status object that indicates whether the operation was successful

◆ Resize()

RETINIFY_API auto retinify::Resize ( const std::uint8_t *  src,
std::size_t  srcStride,
std::uint8_t *  dst,
std::size_t  dstStride,
std::size_t  srcWidth,
std::size_t  srcHeight,
std::size_t  dstWidth,
std::size_t  dstHeight,
std::size_t  channels 
) -> Status
noexcept

Resize an 8-bit image using bilinear interpolation.

Parameters
srcInput image data pointer
srcStrideStride of a row in the source image (in bytes)
dstOutput image data pointer
dstStrideStride of a row in the destination image (in bytes)
srcWidthSource image width (in pixels)
srcHeightSource image height (in pixels)
dstWidthDestination image width (in pixels)
dstHeightDestination image height (in pixels)
channelsNumber of channels (1 or 3)
Returns
A Status object that indicates whether the operation was successful

◆ SaveCalibrationParameters()

RETINIFY_API auto retinify::SaveCalibrationParameters ( const char *  filename,
const CalibrationParameters parameters 
) -> Status
noexcept

Save stereo calibration parameters.

Parameters
filenamePath to the output file
parametersCalibration parameters to save
Returns
A Status object that indicates whether the operation was successful

◆ SetLogLevel()

RETINIFY_API auto retinify::SetLogLevel ( LogLevel  level) -> void
noexcept

Sets the log level.

Parameters
levelThe new log level to apply

◆ SetLogLocation()

RETINIFY_API auto retinify::SetLogLocation ( LogLocation  location) -> void
noexcept

Sets the log location setting.

Parameters
locationThe new log location setting to apply

◆ StateDirectoryPath()

RETINIFY_API auto retinify::StateDirectoryPath ( std::filesystem::path &  path) -> Status
noexcept

Returns the state directory path for retinify.

Parameters
pathOutput state directory path
Returns
A Status object that indicates whether the operation was successful

◆ StereoRectify()

RETINIFY_API auto retinify::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 
) -> Status
noexcept

Perform stereo rectification for a pair of cameras.

Parameters
intrinsics1First camera intrinsics
distortion1First camera distortion
intrinsics2Second camera intrinsics
distortion2Second camera distortion
rotationRotation from the first to the second camera
translationTranslation from the first to the second camera
imageWidthImage width (in pixels)
imageHeightImage height (in pixels)
rotation1Output rectification rotation for the first camera
rotation2Output rectification rotation for the second camera
projectionMatrix1Output projection matrix for the first camera
projectionMatrix2Output projection matrix for the second camera
reprojectionMatrixOutput reprojection matrix
alphaA free scaling parameter that controls cropping after rectification: 0 keeps only valid pixels (no black borders), 1 preserves the full original image (black borders included), values between 0 and 1 yield intermediate results, and -1 applies the default behavior
Returns
A Status object that indicates whether the operation was successful

◆ Transpose()

RETINIFY_API auto retinify::Transpose ( const Mat3x3d mat) -> Mat3x3d
noexcept

Transpose a 3x3 matrix.

Parameters
mat3x3 matrix
Returns
Transposed 3x3 matrix

◆ Undistort()

RETINIFY_API auto retinify::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 
) -> Status
noexcept

Undistort an image using the given camera intrinsics and distortion coefficients.

Parameters
intrinsicsCamera intrinsic parameters
distortionDistortion coefficients
srcInput image data pointer
srcStrideStride of a row in the source image (in bytes)
dstOutput image data pointer
dstStrideStride of a row in the destination image (in bytes)
imageWidthImage width (in pixels)
imageHeightImage height (in pixels)
Returns
A Status object that indicates whether the operation was successful

◆ UndistortPoint()

RETINIFY_API auto retinify::UndistortPoint ( const PinholeIntrinsics intrinsics,
const DistortionCoefficients distortion,
const Point2d point 
) -> Point2d
noexcept

Undistort a 2D point using the given camera intrinsics and distortion coefficients.

Parameters
intrinsicsCamera intrinsic parameters
distortionDistortion coefficients
pointDistorted 2D point (in pixel coordinates)
Returns
Undistorted 2D point (normalized image coordinates)

◆ Vee()

RETINIFY_API auto retinify::Vee ( const Mat3x3d mat) -> Vec3d
noexcept

Convert a 3x3 skew-symmetric matrix to a 3D rotation vector.

Parameters
mat3x3 skew-symmetric matrix
Returns
3D rotation vector

◆ Version()

RETINIFY_API auto retinify::Version ( ) -> const char *
noexcept

Returns the retinify library version in semantic versioning format.

Returns
A string representing the retinify library version