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  Distortion
 Rational distortion model with 8 coefficients: (k1, k2, p1, p2, k3, k4, k5, k6) More...
 
struct  DistortionFisheye
 Fisheye distortion model with 4 coefficients (k1, k2, k3, k4) More...
 
struct  Intrinsics
 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 Vec2f = std::array< float, 2 >
 2D vector (float)
 
using Vec3f = std::array< float, 3 >
 3D vector (float)
 
using Point2f = std::array< float, 2 >
 2D point (float)
 
using Point3f = std::array< float, 3 >
 3D point (float)
 
using Mat3x3f = std::array< std::array< float, 3 >, 3 >
 3x3 matrix (float, row-major)
 
using Mat3x4f = std::array< std::array< float, 4 >, 3 >
 3x4 matrix (float, row-major)
 
using Mat4x4f = std::array< std::array< float, 4 >, 4 >
 4x4 matrix (float, row-major)
 
using Rect2i = Rect2< std::int32_t >
 2D rectangle (int)
 
using Rect2d = Rect2< double >
 2D rectangle (double)
 

Enumerations

enum class  LogLevel : std::uint8_t {
  DEBUG , INFO , WARN , ERROR ,
  FATAL , OFF
}
 Logging verbosity levels for retinify. 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) -> Status
 Applies the colormap to the disparity 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 Multiply (const Mat3x3d &mat1, const Mat3x3d &mat2) noexcept -> Mat3x3d
 Multiply 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 Scale (const Vec3d &vec, double scale) noexcept -> Vec3d
 Scale 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 &omega) noexcept -> Mat3x3d
 Create a 3x3 skew-symmetric matrix from a 3D rotation vector.
 
RETINIFY_API auto Vee (const Mat3x3d &skew) noexcept -> Vec3d
 Convert a 3x3 skew-symmetric matrix to a 3D rotation vector.
 
RETINIFY_API auto Exp (const Vec3d &omega) noexcept -> Mat3x3d
 Compute the matrix exponential of a 3D rotation vector.
 
RETINIFY_API auto Log (const Mat3x3d &rotation) noexcept -> Vec3d
 Compute the matrix logarithm of a 3x3 rotation matrix.
 
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.
 
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 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 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 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 void SetLogLevel (LogLevel level) noexcept
 Sets the log level.
 
RETINIFY_API void LogDebug (const char *message, std::source_location location=std::source_location::current()) noexcept
 Logs a debug message.
 
RETINIFY_API void LogInfo (const char *message, std::source_location location=std::source_location::current()) noexcept
 Logs an informational message.
 
RETINIFY_API void LogWarn (const char *message, std::source_location location=std::source_location::current()) noexcept
 Logs a warning message.
 
RETINIFY_API void LogError (const char *message, std::source_location location=std::source_location::current()) noexcept
 Logs an error message.
 
RETINIFY_API void LogFatal (const char *message, std::source_location location=std::source_location::current()) noexcept
 Logs a fatal error message.
 
RETINIFY_API auto HomeDirectoryPath () noexcept -> const char *
 Returns the current user’s home directory path.
 
RETINIFY_API auto ConfigDirectoryPath () noexcept -> const char *
 Returns the configuration directory path for retinify.
 
RETINIFY_API auto CacheDirectoryPath () noexcept -> const char *
 Returns the cache directory path for retinify.
 
RETINIFY_API auto DataDirectoryPath () noexcept -> const char *
 Returns the data directory path for retinify.
 
RETINIFY_API auto StateDirectoryPath () noexcept -> const char *
 Returns the state directory path for retinify.
 
RETINIFY_API auto StereoMatchingOnnxFilePath () noexcept -> const char *
 Returns the path to the ONNX model file used for stereo matching.
 
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)

◆ Mat3x3f

using retinify::Mat3x3f = typedef std::array<std::array<float, 3>, 3>

3x3 matrix (float, row-major)

◆ Mat3x4d

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

3x4 matrix (double, row-major)

◆ Mat3x4f

using retinify::Mat3x4f = typedef std::array<std::array<float, 4>, 3>

3x4 matrix (float, row-major)

◆ Mat4x4d

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

4x4 matrix (double, row-major)

◆ Mat4x4f

using retinify::Mat4x4f = typedef std::array<std::array<float, 4>, 4>

4x4 matrix (float, row-major)

◆ Point2d

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

2D point (double)

◆ Point2f

using retinify::Point2f = typedef std::array<float, 2>

2D point (float)

◆ Point3d

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

3D point (double)

◆ Point3f

using retinify::Point3f = typedef std::array<float, 3>

3D point (float)

◆ Rect2d

using retinify::Rect2d = typedef Rect2<double>

2D rectangle (double)

◆ Rect2i

using retinify::Rect2i = typedef Rect2<std::int32_t>

2D rectangle (int)

◆ Vec2d

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

2D vector (double)

◆ Vec2f

using retinify::Vec2f = typedef std::array<float, 2>

2D vector (float)

◆ Vec3d

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

3D vector (double)

◆ Vec3f

using retinify::Vec3f = typedef std::array<float, 3>

3D vector (float)

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 for retinify.

Enumerator
DEBUG 

Debug messages.

INFO 

Informational messages.

WARN 

Warning messages.

ERROR 

Error messages.

FATAL 

Fatal Error messages.

OFF 

Disable all logging.

◆ 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

◆ CacheDirectoryPath()

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

Returns the cache directory path for retinify.

Returns
A null-terminated string with the cache directory path, or nullptr on failure

◆ 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

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 for normalization
Returns
A Status object that indicates whether the operation was successful

◆ ConfigDirectoryPath()

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

Returns the configuration directory path for retinify.

Returns
A null-terminated string with the config directory path, or nullptr on failure

◆ 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 ( ) -> const char *
noexcept

Returns the data directory path for retinify.

Returns
A null-terminated string with the data directory path, or nullptr on failure

◆ Determinant()

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

Compute the determinant of a 3x3 matrix.

Parameters
mat3x3 matrix
Returns
Determinant value

◆ 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 omega) -> Mat3x3d
noexcept

Compute the matrix exponential of a 3D rotation vector.

Parameters
omega3D rotation vector
Returns
3x3 rotation matrix

◆ GetLogLevel()

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

Returns the current log level.

Returns
The current log level

◆ Hat()

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

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

Parameters
omega3D rotation vector
Returns
3x3 skew-symmetric matrix

◆ HomeDirectoryPath()

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

Returns the current user’s home directory path.

Returns
A null-terminated string with the home directory path, or nullptr on failure

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

Initialize undistort and rectify maps for image remapping.

Parameters
intrinsicsCamera intrinsics
distortionDistortion parameters
rotationRectification rotation
projectionMatrixProjection matrix
imageWidthImage width (in pixels)
imageHeightImage height (in pixels)
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)
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 rotation) -> Vec3d
noexcept

Compute the matrix logarithm of a 3x3 rotation matrix.

Parameters
rotation3x3 rotation matrix
Returns
3D rotation vector

◆ LogDebug()

RETINIFY_API void retinify::LogDebug ( const char *  message,
std::source_location  location = std::source_location::current() 
)
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 void retinify::LogError ( const char *  message,
std::source_location  location = std::source_location::current() 
)
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 void retinify::LogFatal ( const char *  message,
std::source_location  location = std::source_location::current() 
)
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 void retinify::LogInfo ( const char *  message,
std::source_location  location = std::source_location::current() 
)
noexcept

Logs an informational message.

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

◆ LogWarn()

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

Logs a warning message.

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

◆ Multiply() [1/2]

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/2]

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

◆ 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

◆ 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

◆ Scale()

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

Scale a 3D vector by a scalar value.

Parameters
vec3D vector
scaleScalar value
Returns
Scaled 3D vector

◆ SetLogLevel()

RETINIFY_API void retinify::SetLogLevel ( LogLevel  level)
noexcept

Sets the log level.

Parameters
levelThe new log level to apply

◆ StateDirectoryPath()

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

Returns the state directory path for retinify.

Returns
A null-terminated string with the state directory path, or nullptr on failure

◆ StereoMatchingOnnxFilePath()

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

Returns the path to the ONNX model file used for stereo matching.

Returns
A null-terminated string with the ONNX model file path

◆ StereoRectify()

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 mappingMatrix,
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
mappingMatrixOutput mapping 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

◆ UndistortPoint()

RETINIFY_API auto retinify::UndistortPoint ( const Intrinsics intrinsics,
const Distortion distortion,
const Point2d pixel 
) -> Point2d
noexcept

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

Parameters
intrinsicsCamera intrinsic parameters
distortionDistortion parameters
pixelDistorted 2D point (in pixel coordinates)
Returns
Undistorted 2D point (in pixel coordinates)

◆ Vee()

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

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

Parameters
skew3x3 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