Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | List of all members
dai::CalibrationHandler Class Reference

#include <CalibrationHandler.hpp>

Public Member Functions

 CalibrationHandler ()=default
 
 CalibrationHandler (dai::Path calibrationDataPath, dai::Path boardConfigPath)
 
 CalibrationHandler (dai::Path eepromDataPath)
 
 CalibrationHandler (EepromData eepromData)
 
nlohmann::json eepromToJson () const
 
bool eepromToJsonFile (dai::Path destPath) const
 
float getBaselineDistance (CameraBoardSocket cam1=CameraBoardSocket::CAM_C, CameraBoardSocket cam2=CameraBoardSocket::CAM_B, bool useSpecTranslation=true) const
 
std::vector< std::vector< float > > getCameraExtrinsics (CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=false) const
 
std::vector< std::vector< float > > getCameraIntrinsics (CameraBoardSocket cameraId, int resizeWidth=-1, int resizeHeight=-1, Point2f topLeftPixelId=Point2f(), Point2f bottomRightPixelId=Point2f(), bool keepAspectRatio=true) const
 
std::vector< std::vector< float > > getCameraIntrinsics (CameraBoardSocket cameraId, Size2f destShape, Point2f topLeftPixelId=Point2f(), Point2f bottomRightPixelId=Point2f(), bool keepAspectRatio=true) const
 
std::vector< std::vector< float > > getCameraIntrinsics (CameraBoardSocket cameraId, std::tuple< int, int > destShape, Point2f topLeftPixelId=Point2f(), Point2f bottomRightPixelId=Point2f(), bool keepAspectRatio=true) const
 
std::vector< std::vector< float > > getCameraToImuExtrinsics (CameraBoardSocket cameraId, bool useSpecTranslation=false) const
 
std::vector< float > getCameraTranslationVector (CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=true) const
 
std::tuple< std::vector< std::vector< float > >, int, int > getDefaultIntrinsics (CameraBoardSocket cameraId) const
 
std::vector< float > getDistortionCoefficients (CameraBoardSocket cameraId) const
 
CameraModel getDistortionModel (CameraBoardSocket cameraId) const
 
dai::EepromData getEepromData () const
 
float getFov (CameraBoardSocket cameraId, bool useSpec=true) const
 
std::vector< std::vector< float > > getImuToCameraExtrinsics (CameraBoardSocket cameraId, bool useSpecTranslation=false) const
 
uint8_t getLensPosition (CameraBoardSocket cameraId) const
 
dai::CameraBoardSocket getStereoLeftCameraId () const
 
std::vector< std::vector< float > > getStereoLeftRectificationRotation () const
 
dai::CameraBoardSocket getStereoRightCameraId () const
 
std::vector< std::vector< float > > getStereoRightRectificationRotation () const
 
void setBoardInfo (std::string boardName, std::string boardRev)
 
void setBoardInfo (std::string deviceName, std::string productName, std::string boardName, std::string boardRev, std::string boardConf, std::string hardwareConf, std::string batchName, uint64_t batchTime, uint32_t boardOptions, std::string boardCustom="")
 
void setBoardInfo (std::string productName, std::string boardName, std::string boardRev, std::string boardConf, std::string hardwareConf, std::string batchName, uint64_t batchTime, uint32_t boardOptions, std::string boardCustom="")
 
void setCameraExtrinsics (CameraBoardSocket srcCameraId, CameraBoardSocket destCameraId, std::vector< std::vector< float >> rotationMatrix, std::vector< float > translation, std::vector< float > specTranslation={0, 0, 0})
 
void setCameraIntrinsics (CameraBoardSocket cameraId, std::vector< std::vector< float >> intrinsics, int width, int height)
 
void setCameraIntrinsics (CameraBoardSocket cameraId, std::vector< std::vector< float >> intrinsics, Size2f frameSize)
 
void setCameraIntrinsics (CameraBoardSocket cameraId, std::vector< std::vector< float >> intrinsics, std::tuple< int, int > frameSize)
 
void setCameraType (CameraBoardSocket cameraId, CameraModel cameraModel)
 
void setDeviceName (std::string deviceName)
 
void setDistortionCoefficients (CameraBoardSocket cameraId, std::vector< float > distortionCoefficients)
 
void setFov (CameraBoardSocket cameraId, float hfov)
 
void setImuExtrinsics (CameraBoardSocket destCameraId, std::vector< std::vector< float >> rotationMatrix, std::vector< float > translation, std::vector< float > specTranslation={0, 0, 0})
 
void setLensPosition (CameraBoardSocket cameraId, uint8_t lensPosition)
 
void setProductName (std::string productName)
 
void setStereoLeft (CameraBoardSocket cameraId, std::vector< std::vector< float >> rectifiedRotation)
 
void setStereoRight (CameraBoardSocket cameraId, std::vector< std::vector< float >> rectifiedRotation)
 
bool validateCameraArray () const
 

Static Public Member Functions

static CalibrationHandler fromJson (nlohmann::json eepromDataJson)
 

Private Member Functions

bool checkExtrinsicsLink (CameraBoardSocket srcCamera, CameraBoardSocket dstCamera) const
 
bool checkSrcLinks (CameraBoardSocket headSocket) const
 
std::vector< std::vector< float > > computeExtrinsicMatrix (CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=false) const
 

Private Attributes

dai::EepromData eepromData
 

Detailed Description

CalibrationHandler is an interface to read/load/write structured calibration and device data. The following fields are protected and aren't allowed to be overridden by default:

Definition at line 24 of file CalibrationHandler.hpp.

Constructor & Destructor Documentation

◆ CalibrationHandler() [1/4]

dai::CalibrationHandler::CalibrationHandler ( )
default

◆ CalibrationHandler() [2/4]

dai::CalibrationHandler::CalibrationHandler ( dai::Path  eepromDataPath)
explicit

Construct a new Calibration Handler object using the eeprom json file created from calibration procedure.

Parameters
eepromDataPathtakes the full path to the json file containing the calibration and device info.

Definition at line 52 of file CalibrationHandler.cpp.

◆ CalibrationHandler() [3/4]

dai::CalibrationHandler::CalibrationHandler ( dai::Path  calibrationDataPath,
dai::Path  boardConfigPath 
)

Construct a new Calibration Handler object using the board config json file and .calib binary files created using gen1 calibration.

Parameters
calibrationDataPathFull Path to the .calib binary file from the gen1 calibration. (Supports only Version 5)
boardConfigPathFull Path to the board config json file containing device information.

Definition at line 71 of file CalibrationHandler.cpp.

◆ CalibrationHandler() [4/4]

dai::CalibrationHandler::CalibrationHandler ( EepromData  eepromData)
explicit

Construct a new Calibration Handler object from EepromData object.

Parameters
eepromDataEepromData data structure containing the calibration data.

Definition at line 196 of file CalibrationHandler.cpp.

Member Function Documentation

◆ checkExtrinsicsLink()

bool dai::CalibrationHandler::checkExtrinsicsLink ( CameraBoardSocket  srcCamera,
CameraBoardSocket  dstCamera 
) const
private

Definition at line 532 of file CalibrationHandler.cpp.

◆ checkSrcLinks()

bool dai::CalibrationHandler::checkSrcLinks ( CameraBoardSocket  headSocket) const
private

Definition at line 797 of file CalibrationHandler.cpp.

◆ computeExtrinsicMatrix()

std::vector< std::vector< float > > dai::CalibrationHandler::computeExtrinsicMatrix ( CameraBoardSocket  srcCamera,
CameraBoardSocket  dstCamera,
bool  useSpecTranslation = false 
) const
private

Definition at line 480 of file CalibrationHandler.cpp.

◆ eepromToJson()

nlohmann::json dai::CalibrationHandler::eepromToJson ( ) const

Get JSON representation of calibration data

Returns
JSON structure

Definition at line 476 of file CalibrationHandler.cpp.

◆ eepromToJsonFile()

bool dai::CalibrationHandler::eepromToJsonFile ( dai::Path  destPath) const

Write raw calibration/board data to json file.

Parameters
destPathFull path to the json file in which raw calibration data will be stored
Returns
True on success, false otherwise

Definition at line 469 of file CalibrationHandler.cpp.

◆ fromJson()

CalibrationHandler dai::CalibrationHandler::fromJson ( nlohmann::json  eepromDataJson)
static

Construct a new Calibration Handler object from JSON EepromData.

Parameters
eepromDataJsonEepromData as JSON

Definition at line 65 of file CalibrationHandler.cpp.

◆ getBaselineDistance()

float dai::CalibrationHandler::getBaselineDistance ( CameraBoardSocket  cam1 = CameraBoardSocket::CAM_C,
CameraBoardSocket  cam2 = CameraBoardSocket::CAM_B,
bool  useSpecTranslation = true 
) const

Get the baseline distance between two specified cameras. By default it will get the baseline between CameraBoardSocket.CAM_C and CameraBoardSocket.CAM_B.

Parameters
cam1First camera
cam2Second camera
useSpecTranslationEnabling this bool uses the translation information from the board design data (not the calibration data)
Returns
baseline distance in centimeters

Definition at line 400 of file CalibrationHandler.cpp.

◆ getCameraExtrinsics()

std::vector< std::vector< float > > dai::CalibrationHandler::getCameraExtrinsics ( CameraBoardSocket  srcCamera,
CameraBoardSocket  dstCamera,
bool  useSpecTranslation = false 
) const

Get the Camera Extrinsics object between two cameras from the calibration data if there is a linked connection between any two cameras then the relative rotation and translation (in centimeters) is returned by this function.

Parameters
srcCameraCamera Id of the camera which will be considered as origin.
dstCameraCamera Id of the destination camera to which we are fetching the rotation and translation from the SrcCamera
useSpecTranslationEnabling this bool uses the translation information from the board design data
Returns
a transformationMatrix which is 4x4 in homogeneous coordinate system

Matrix representation of transformation matrix

\[ \text{Transformation Matrix} = \left [ \begin{matrix} r_{00} & r_{01} & r_{02} & T_x \\ r_{10} & r_{11} & r_{12} & T_y \\ r_{20} & r_{21} & r_{22} & T_z \\ 0 & 0 & 0 & 1 \end{matrix} \right ] \]

  1. Check if both camera ID exists.
  2. Check if the forward link exists from source to dest camera. if No go to step 5
  3. Call computeExtrinsicMatrix to get the projection matrix from source -> destination camera.
  4. Jump to end and return the projection matrix
  5. if no check if there is forward link from dest to source. if No return an error that link doesn't exist.
  6. Call computeExtrinsicMatrix to get the projection matrix from destination -> source camera.
  7. Carry Transpose on the rotation matrix and get neg of Final translation
  8. Return the Final TransformationMatrix containing both rotation matrix and Translation

Definition at line 357 of file CalibrationHandler.cpp.

◆ getCameraIntrinsics() [1/3]

std::vector< std::vector< float > > dai::CalibrationHandler::getCameraIntrinsics ( CameraBoardSocket  cameraId,
int  resizeWidth = -1,
int  resizeHeight = -1,
Point2f  topLeftPixelId = Point2f(),
Point2f  bottomRightPixelId = Point2f(),
bool  keepAspectRatio = true 
) const

Get the Camera Intrinsics object

Parameters
cameraIdUses the cameraId to identify which camera intrinsics to return
resizewidthresized width of the image for which intrinsics is requested. resizewidth = -1 represents width is same as default intrinsics
resizeHeightresized height of the image for which intrinsics is requested. resizeHeight = -1 represents height is same as default intrinsics
topLeftPixelId(x, y) point represents the top left corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped image
bottomRightPixelId(x, y) point represents the bottom right corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped image
keepAspectRatioEnabling this will scale on width or height depending on which provides the max resolution and crops the remaining part of the other side
Returns
Represents the 3x3 intrinsics matrix of the respective camera at the requested size and crop dimensions.

Matrix representation of intrinsic matrix

\[ \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \]

Definition at line 204 of file CalibrationHandler.cpp.

◆ getCameraIntrinsics() [2/3]

std::vector< std::vector< float > > dai::CalibrationHandler::getCameraIntrinsics ( CameraBoardSocket  cameraId,
Size2f  destShape,
Point2f  topLeftPixelId = Point2f(),
Point2f  bottomRightPixelId = Point2f(),
bool  keepAspectRatio = true 
) const

Get the Camera Intrinsics object

Parameters
cameraIdUses the cameraId to identify which camera intrinsics to return
destShaperesized width and height of the image for which intrinsics is requested.
topLeftPixelId(x, y) point represents the top left corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped image
bottomRightPixelId(x, y) point represents the bottom right corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped image
keepAspectRatioEnabling this will scale on width or height depending on which provides the max resolution and crops the remaining part of the other side
Returns
Represents the 3x3 intrinsics matrix of the respective camera at the requested size and crop dimensions.

Matrix representation of intrinsic matrix

\[ \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \]

Definition at line 280 of file CalibrationHandler.cpp.

◆ getCameraIntrinsics() [3/3]

std::vector< std::vector< float > > dai::CalibrationHandler::getCameraIntrinsics ( CameraBoardSocket  cameraId,
std::tuple< int, int >  destShape,
Point2f  topLeftPixelId = Point2f(),
Point2f  bottomRightPixelId = Point2f(),
bool  keepAspectRatio = true 
) const

Get the Camera Intrinsics object

Parameters
cameraIdUses the cameraId to identify which camera intrinsics to return
destShaperesized width and height of the image for which intrinsics is requested.
topLeftPixelId(x, y) point represents the top left corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped image
bottomRightPixelId(x, y) point represents the bottom right corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped image
keepAspectRatioEnabling this will scale on width or height depending on which provides the max resolution and crops the remaining part of the other side
Returns
Represents the 3x3 intrinsics matrix of the respective camera at the requested size and crop dimensions.

Matrix representation of intrinsic matrix

\[ \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \]

Definition at line 286 of file CalibrationHandler.cpp.

◆ getCameraToImuExtrinsics()

std::vector< std::vector< float > > dai::CalibrationHandler::getCameraToImuExtrinsics ( CameraBoardSocket  cameraId,
bool  useSpecTranslation = false 
) const

Get the Camera To Imu Extrinsics object From the data loaded if there is a linked connection between IMU and the given camera then there relative rotation and translation from the camera to IMU is returned.

Parameters
cameraIdCamera Id of the camera which will be considered as origin. from which Transformation matrix to the IMU will be found
useSpecTranslationEnabling this bool uses the translation information from the board design data
Returns
Returns a transformationMatrix which is 4x4 in homogeneous coordinate system

Matrix representation of transformation matrix

\[ \text{Transformation Matrix} = \left [ \begin{matrix} r_{00} & r_{01} & r_{02} & T_x \\ r_{10} & r_{11} & r_{12} & T_y \\ r_{20} & r_{21} & r_{22} & T_z \\ 0 & 0 & 0 & 1 \end{matrix} \right ] \]

Definition at line 409 of file CalibrationHandler.cpp.

◆ getCameraTranslationVector()

std::vector< float > dai::CalibrationHandler::getCameraTranslationVector ( CameraBoardSocket  srcCamera,
CameraBoardSocket  dstCamera,
bool  useSpecTranslation = true 
) const

Get the Camera translation vector between two cameras from the calibration data.

Parameters
srcCameraCamera Id of the camera which will be considered as origin.
dstCameraCamera Id of the destination camera to which we are fetching the translation vector from the SrcCamera
useSpecTranslationDisabling this bool uses the translation information from the calibration data (not the board design data)
Returns
a translation vector like [x, y, z] in centimeters

Definition at line 390 of file CalibrationHandler.cpp.

◆ getDefaultIntrinsics()

std::tuple< std::vector< std::vector< float > >, int, int > dai::CalibrationHandler::getDefaultIntrinsics ( CameraBoardSocket  cameraId) const

Get the Default Intrinsics object

Parameters
cameraIdUses the cameraId to identify which camera intrinsics to return
Returns
Represents the 3x3 intrinsics matrix of the respective camera along with width and height at which it was calibrated.

Matrix representation of intrinsic matrix

\[ \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \]

Definition at line 291 of file CalibrationHandler.cpp.

◆ getDistortionCoefficients()

std::vector< float > dai::CalibrationHandler::getDistortionCoefficients ( CameraBoardSocket  cameraId) const

Get the Distortion Coefficients object

Parameters
cameraIdUses the cameraId to identify which distortion Coefficients to return.
Returns
the distortion coefficients of the requested camera in this order: [k1,k2,p1,p2,k3,k4,k5,k6,s1,s2,s3,s4,tx,ty] for CameraModel::Perspective or [k1, k2, k3, k4] for CameraModel::Fisheye see https://docs.opencv.org/4.5.4/d9/d0c/group__calib3d.html for Perspective model (Rational Polynomial Model) see https://docs.opencv.org/4.5.4/db/d58/group__calib3d__fisheye.html for Fisheye model

Definition at line 304 of file CalibrationHandler.cpp.

◆ getDistortionModel()

CameraModel dai::CalibrationHandler::getDistortionModel ( CameraBoardSocket  cameraId) const

Get the distortion model of the given camera

Parameters
cameraIdof the camera with lens position is requested.
Returns
lens position of the camera with given cameraId at which it was calibrated.

Definition at line 350 of file CalibrationHandler.cpp.

◆ getEepromData()

dai::EepromData dai::CalibrationHandler::getEepromData ( ) const

Get the Eeprom Data object

Returns
EepromData object which contains the raw calibration data

Definition at line 200 of file CalibrationHandler.cpp.

◆ getFov()

float dai::CalibrationHandler::getFov ( CameraBoardSocket  cameraId,
bool  useSpec = true 
) const

Get the Fov of the camera

Parameters
cameraIdof the camera of which we are fetching fov.
useSpecDisabling this bool will calculate the fov based on intrinsics (focal length, image width), instead of getting it from the camera specs
Returns
field of view of the camera with given cameraId.

Definition at line 328 of file CalibrationHandler.cpp.

◆ getImuToCameraExtrinsics()

std::vector< std::vector< float > > dai::CalibrationHandler::getImuToCameraExtrinsics ( CameraBoardSocket  cameraId,
bool  useSpecTranslation = false 
) const

Get the Imu To Camera Extrinsics object from the data loaded if there is a linked connection between IMU and the given camera then there relative rotation and translation from the IMU to Camera is returned.

Parameters
cameraIdCamera Id of the camera which will be considered as destination. To which Transformation matrix from the IMU will be found.
useSpecTranslationEnabling this bool uses the translation information from the board design data
Returns
Returns a transformationMatrix which is 4x4 in homogeneous coordinate system

Matrix representation of transformation matrix

\[ \text{Transformation Matrix} = \left [ \begin{matrix} r_{00} & r_{01} & r_{02} & T_x \\ r_{10} & r_{11} & r_{12} & T_y \\ r_{20} & r_{21} & r_{22} & T_z \\ 0 & 0 & 0 & 1 \end{matrix} \right ] \]

Definition at line 415 of file CalibrationHandler.cpp.

◆ getLensPosition()

uint8_t dai::CalibrationHandler::getLensPosition ( CameraBoardSocket  cameraId) const

Get the lens position of the given camera

Parameters
cameraIdof the camera with lens position is requested.
Returns
lens position of the camera with given cameraId at which it was calibrated.

Definition at line 343 of file CalibrationHandler.cpp.

◆ getStereoLeftCameraId()

dai::CameraBoardSocket dai::CalibrationHandler::getStereoLeftCameraId ( ) const

Get the camera id of the camera which is used as left camera of the stereo setup

Returns
cameraID of the camera used as left camera

Definition at line 461 of file CalibrationHandler.cpp.

◆ getStereoLeftRectificationRotation()

std::vector< std::vector< float > > dai::CalibrationHandler::getStereoLeftRectificationRotation ( ) const

Get the Stereo Left Rectification Rotation object

Returns
returns a 3x3 rectification rotation matrix

Definition at line 452 of file CalibrationHandler.cpp.

◆ getStereoRightCameraId()

dai::CameraBoardSocket dai::CalibrationHandler::getStereoRightCameraId ( ) const

Get the camera id of the camera which is used as right camera of the stereo setup

Returns
cameraID of the camera used as right camera

Definition at line 465 of file CalibrationHandler.cpp.

◆ getStereoRightRectificationRotation()

std::vector< std::vector< float > > dai::CalibrationHandler::getStereoRightRectificationRotation ( ) const

Get the Stereo Right Rectification Rotation object

Returns
returns a 3x3 rectification rotation matrix

Definition at line 444 of file CalibrationHandler.cpp.

◆ setBoardInfo() [1/3]

void dai::CalibrationHandler::setBoardInfo ( std::string  boardName,
std::string  boardRev 
)

Set the Board Info object

Parameters
versionSets the version of the Calibration data(Current version is 6)
boardNameSets your board name.
boardRevset your board revision id.

Definition at line 545 of file CalibrationHandler.cpp.

◆ setBoardInfo() [2/3]

void dai::CalibrationHandler::setBoardInfo ( std::string  deviceName,
std::string  productName,
std::string  boardName,
std::string  boardRev,
std::string  boardConf,
std::string  hardwareConf,
std::string  batchName,
uint64_t  batchTime,
uint32_t  boardOptions,
std::string  boardCustom = "" 
)

Set the Board Info object. Creates version 7 EEPROM data

Parameters
deviceNameSets device name.
productNameSets product name (alias).
boardNameSets board name.
boardRevSets board revision id.
boardConfSets board configuration id.
hardwareConfSets hardware configuration id.
batchNameSets batch name. Not supported anymore
batchTimeSets batch time (unix timestamp).
boardCustomSets a custom board (Default empty string).

Definition at line 576 of file CalibrationHandler.cpp.

◆ setBoardInfo() [3/3]

void dai::CalibrationHandler::setBoardInfo ( std::string  productName,
std::string  boardName,
std::string  boardRev,
std::string  boardConf,
std::string  hardwareConf,
std::string  batchName,
uint64_t  batchTime,
uint32_t  boardOptions,
std::string  boardCustom = "" 
)

Set the Board Info object. Creates version 7 EEPROM data

Parameters
productNameSets product name (alias).
boardNameSets board name.
boardRevSets board revision id.
boardConfSets board configuration id.
hardwareConfSets hardware configuration id.
batchNameSets batch name.
batchTimeSets batch time (unix timestamp).
boardCustomSets a custom board (Default empty string).

Definition at line 550 of file CalibrationHandler.cpp.

◆ setCameraExtrinsics()

void dai::CalibrationHandler::setCameraExtrinsics ( CameraBoardSocket  srcCameraId,
CameraBoardSocket  destCameraId,
std::vector< std::vector< float >>  rotationMatrix,
std::vector< float >  translation,
std::vector< float >  specTranslation = {0, 0, 0} 
)

Set the Camera Extrinsics object

Parameters
srcCameraIdCamera Id of the camera which will be considered as relative origin.
destCameraIdCamera Id of the camera which will be considered as destination from srcCameraId.
rotationMatrixRotation between srcCameraId and destCameraId origins.
translationTranslation between srcCameraId and destCameraId origins.
specTranslationTranslation between srcCameraId and destCameraId origins from the design.

Definition at line 710 of file CalibrationHandler.cpp.

◆ setCameraIntrinsics() [1/3]

void dai::CalibrationHandler::setCameraIntrinsics ( CameraBoardSocket  cameraId,
std::vector< std::vector< float >>  intrinsics,
int  width,
int  height 
)

Set the Camera Intrinsics object

Parameters
cameraIdCameraId of the camera for which Camera intrinsics are being loaded
intrinsics3x3 intrinsics matrix
widthRepresents the width of the image at which intrinsics are calculated.
heightRepresents the height of the image at which intrinsics are calculated.

Matrix representation of intrinsic matrix

\[ \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \]

Definition at line 618 of file CalibrationHandler.cpp.

◆ setCameraIntrinsics() [2/3]

void dai::CalibrationHandler::setCameraIntrinsics ( CameraBoardSocket  cameraId,
std::vector< std::vector< float >>  intrinsics,
Size2f  frameSize 
)

Set the Camera Intrinsics object

Parameters
cameraIdCameraId of the camera for which Camera intrinsics are being loaded
intrinsics3x3 intrinsics matrix
frameSizeRepresents the width and height of the image at which intrinsics are calculated.

Matrix representation of intrinsic matrix

\[ \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \]

Definition at line 641 of file CalibrationHandler.cpp.

◆ setCameraIntrinsics() [3/3]

void dai::CalibrationHandler::setCameraIntrinsics ( CameraBoardSocket  cameraId,
std::vector< std::vector< float >>  intrinsics,
std::tuple< int, int >  frameSize 
)

Set the Camera Intrinsics object

Parameters
cameraIdCameraId of the camera for which Camera intrinsics are being loaded
intrinsics3x3 intrinsics matrix
frameSizeRepresents the width and height of the image at which intrinsics are calculated.

Matrix representation of intrinsic matrix

\[ \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \]

Definition at line 646 of file CalibrationHandler.cpp.

◆ setCameraType()

void dai::CalibrationHandler::setCameraType ( CameraBoardSocket  cameraId,
CameraModel  cameraModel 
)

Set the Camera Type object

Parameters
cameraIdCameraId of the camera for which cameraModel Type is being updated.
cameraModelType of the model the camera represents

Definition at line 699 of file CalibrationHandler.cpp.

◆ setDeviceName()

void dai::CalibrationHandler::setDeviceName ( std::string  deviceName)

Set the deviceName which responses to getDeviceName of Device

Parameters
deviceNameSets device name.

Definition at line 604 of file CalibrationHandler.cpp.

◆ setDistortionCoefficients()

void dai::CalibrationHandler::setDistortionCoefficients ( CameraBoardSocket  cameraId,
std::vector< float >  distortionCoefficients 
)

Sets the distortion Coefficients obtained from camera calibration

Parameters
cameraIdCamera Id of the camera for which distortion coefficients are computed
distortionCoefficientsDistortion Coefficients of the respective Camera.

Definition at line 651 of file CalibrationHandler.cpp.

◆ setFov()

void dai::CalibrationHandler::setFov ( CameraBoardSocket  cameraId,
float  hfov 
)

Set the Fov of the Camera

Parameters
cameraIdCamera Id of the camera
hfovHorizontal fov of the camera from Camera Datasheet

Definition at line 677 of file CalibrationHandler.cpp.

◆ setImuExtrinsics()

void dai::CalibrationHandler::setImuExtrinsics ( CameraBoardSocket  destCameraId,
std::vector< std::vector< float >>  rotationMatrix,
std::vector< float >  translation,
std::vector< float >  specTranslation = {0, 0, 0} 
)

Set the Imu to Camera Extrinsics object

Parameters
destCameraIdCamera Id of the camera which will be considered as destination from IMU.
rotationMatrixRotation between srcCameraId and destCameraId origins.
translationTranslation between IMU and destCameraId origins.
specTranslationTranslation between IMU and destCameraId origins from the design.

Definition at line 741 of file CalibrationHandler.cpp.

◆ setLensPosition()

void dai::CalibrationHandler::setLensPosition ( CameraBoardSocket  cameraId,
uint8_t  lensPosition 
)

Sets the distortion Coefficients obtained from camera calibration

Parameters
cameraIdCamera Id of the camera
lensPositionlens posiotion value of the camera at the time of calibration

Definition at line 688 of file CalibrationHandler.cpp.

◆ setProductName()

void dai::CalibrationHandler::setProductName ( std::string  productName)

Set the productName which acts as alisas for users to identify the device

Parameters
productNameSets product name (alias).

Definition at line 611 of file CalibrationHandler.cpp.

◆ setStereoLeft()

void dai::CalibrationHandler::setStereoLeft ( CameraBoardSocket  cameraId,
std::vector< std::vector< float >>  rectifiedRotation 
)

Set the Stereo Left Rectification object

Parameters
cameraIdCameraId of the camera which will be used as left Camera of stereo Setup
rectifiedRotationRectification rotation of the left camera required for feature matching

Homography of the Left Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_left)

Definition at line 764 of file CalibrationHandler.cpp.

◆ setStereoRight()

void dai::CalibrationHandler::setStereoRight ( CameraBoardSocket  cameraId,
std::vector< std::vector< float >>  rectifiedRotation 
)

Set the Stereo Right Rectification object

Parameters
cameraIdCameraId of the camera which will be used as left Camera of stereo Setup
rectifiedRotationRectification rotation of the left camera required for feature matching

Homography of the Right Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_right)

Definition at line 773 of file CalibrationHandler.cpp.

◆ validateCameraArray()

bool dai::CalibrationHandler::validateCameraArray ( ) const

Using left camera as the head it iterates over the camera extrinsics connection to check if all the camera extrinsics are connected and no loop exists.

Returns
true on proper connection with no loops.

Definition at line 782 of file CalibrationHandler.cpp.

Member Data Documentation

◆ eepromData

dai::EepromData dai::CalibrationHandler::eepromData
private

when the user is writing extrinsics do we validate if the connection between all the cameras exists ? Some users might not need that connection so they might ignore adding that in that case if the user calls the extrinsics betwwn those cameras it fails We can provide an appropriate error that connection doesn't exist between the requested camera id's.. And other option is making sure the connection exists all the time by validating the links.

Definition at line 547 of file CalibrationHandler.hpp.


The documentation for this class was generated from the following files:


depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:20