Class CalibrationHandler
Defined in File CalibrationHandler.hpp
Class Documentation
-
class CalibrationHandler
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:
boardName
boardRev
boardConf
hardwareConf
batchName
batchTime
boardOptions
productName
Public Functions
-
CalibrationHandler() = default
-
explicit CalibrationHandler(std::filesystem::path eepromDataPath)
Construct a new Calibration Handler object using the eeprom json file created from calibration procedure.
- Parameters:
eepromDataPath – takes the full path to the json file containing the calibration and device info.
-
CalibrationHandler(std::filesystem::path calibrationDataPath, std::filesystem::path boardConfigPath)
Construct a new Calibration Handler object using the board config json file and .calib binary files created using gen1 calibration.
- Parameters:
calibrationDataPath – Full Path to the .calib binary file from the gen1 calibration. (Supports only Version 5)
boardConfigPath – Full Path to the board config json file containing device information.
-
explicit CalibrationHandler(EepromData eepromData)
Construct a new Calibration Handler object from EepromData object.
- Parameters:
eepromData – EepromData data structure containing the calibration data.
-
dai::EepromData getEepromData() const
Get the Eeprom Data object
- Returns:
EepromData object which contains the raw calibration data
-
std::vector<std::vector<float>> getCameraIntrinsics(CameraBoardSocket cameraId, int resizeWidth = -1, int resizeHeight = -1, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true) const
Get the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters:
cameraId – Uses the cameraId to identify which camera intrinsics to return
resizewidth – resized width of the image for which intrinsics is requested. resizewidth = -1 represents width is same as default intrinsics
resizeHeight – resized 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
keepAspectRatio – Enabling 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.
-
std::vector<std::vector<float>> getCameraIntrinsics(CameraBoardSocket cameraId, Size2f destShape, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true) const
Get the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters:
cameraId – Uses the cameraId to identify which camera intrinsics to return
destShape – resized 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
keepAspectRatio – Enabling 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.
-
std::vector<std::vector<float>> getCameraIntrinsics(CameraBoardSocket cameraId, std::tuple<int, int> destShape, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true) const
Get the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters:
cameraId – Uses the cameraId to identify which camera intrinsics to return
destShape – resized 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
keepAspectRatio – Enabling 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.
-
std::tuple<std::vector<std::vector<float>>, int, int> getDefaultIntrinsics(CameraBoardSocket cameraId) const
Get the Default Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters:
cameraId – Uses 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.
-
std::vector<float> getDistortionCoefficients(CameraBoardSocket cameraId) const
Get the Distortion Coefficients object
- Parameters:
cameraId – Uses 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,τx,τy] 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
-
float getFov(CameraBoardSocket cameraId, bool useSpec = true) const
Get the Fov of the camera
- Parameters:
cameraId – of the camera of which we are fetching fov.
useSpec – Disabling 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.
-
uint8_t getLensPosition(CameraBoardSocket cameraId) const
Get the lens position of the given camera
- Parameters:
cameraId – of the camera with lens position is requested.
- Returns:
lens position of the camera with given cameraId at which it was calibrated.
-
CameraModel getDistortionModel(CameraBoardSocket cameraId) const
Get the distortion model of the given camera
- Parameters:
cameraId – of the camera with lens position is requested.
- Returns:
lens position of the camera with given cameraId at which it was calibrated.
-
std::vector<std::vector<float>> 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.
Matrix representation of transformation matrix
\[\begin{split} \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 ] \end{split}\]- Parameters:
srcCamera – Camera Id of the camera which will be considered as origin.
dstCamera – Camera Id of the destination camera to which we are fetching the rotation and translation from the SrcCamera
useSpecTranslation – Enabling this bool uses the translation information from the board design data
- Returns:
a transformationMatrix which is 4x4 in homogeneous coordinate system
-
std::vector<float> getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = true) const
Get the Camera translation vector between two cameras from the calibration data.
- Parameters:
srcCamera – Camera Id of the camera which will be considered as origin.
dstCamera – Camera Id of the destination camera to which we are fetching the translation vector from the SrcCamera
useSpecTranslation – Disabling 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
-
std::vector<std::vector<float>> getCameraRotationMatrix(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera) const
Get the Camera rotation matrix between two cameras from the calibration data.
- Parameters:
srcCamera – Camera Id of the camera which will be considered as origin.
dstCamera – Camera Id of the destination camera to which we are fetching the rotation vector from the SrcCamera
- Returns:
a 3x3 rotation matrix Matrix representation of rotation matrix
\[\begin{split} \text{Rotation Matrix} = \left [ \begin{matrix} r_{00} & r_{01} & r_{02}\\ r_{10} & r_{11} & r_{12}\\ r_{20} & r_{21} & r_{22}\\ \end{matrix} \right ] \end{split}\]
-
float 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.RIGHT and CameraBoardSocket.LEFT.
- Parameters:
cam1 – First camera
cam2 – Second camera
useSpecTranslation – Enabling this bool uses the translation information from the board design data (not the calibration data)
- Returns:
baseline distance in centimeters
-
std::vector<std::vector<float>> 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.
Matrix representation of transformation matrix
\[\begin{split} \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 ] \end{split}\]- Parameters:
cameraId – Camera Id of the camera which will be considered as origin. from which Transformation matrix to the IMU will be found
useSpecTranslation – Enabling this bool uses the translation information from the board design data
- Returns:
Returns a transformationMatrix which is 4x4 in homogeneous coordinate system
-
std::vector<std::vector<float>> 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.
Matrix representation of transformation matrix
\[\begin{split} \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 ] \end{split}\]- Parameters:
cameraId – Camera Id of the camera which will be considered as destination. To which Transformation matrix from the IMU will be found.
useSpecTranslation – Enabling this bool uses the translation information from the board design data
- Returns:
Returns a transformationMatrix which is 4x4 in homogeneous coordinate system
-
std::vector<std::vector<float>> getStereoRightRectificationRotation() const
Get the Stereo Right Rectification Rotation object
- Returns:
returns a 3x3 rectification rotation matrix
-
std::vector<std::vector<float>> getStereoLeftRectificationRotation() const
Get the Stereo Left Rectification Rotation object
- Returns:
returns a 3x3 rectification rotation matrix
-
dai::CameraBoardSocket 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
-
dai::CameraBoardSocket 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
-
bool eepromToJsonFile(std::filesystem::path destPath) const
Write raw calibration/board data to json file.
- Parameters:
destPath – Full path to the json file in which raw calibration data will be stored
- Returns:
True on success, false otherwise
-
nlohmann::json eepromToJson() const
Get JSON representation of calibration data
- Returns:
JSON structure
-
void setBoardInfo(std::string boardName, std::string boardRev)
Set the Board Info object
- Parameters:
version – Sets the version of the Calibration data(Current version is 6)
boardName – Sets your board name.
boardRev – set your board revision id.
-
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 = "")
Set the Board Info object. Creates version 7 EEPROM data
- Parameters:
productName – Sets product name (alias).
boardName – Sets board name.
boardRev – Sets board revision id.
boardConf – Sets board configuration id.
hardwareConf – Sets hardware configuration id.
batchName – Sets batch name.
batchTime – Sets batch time (unix timestamp).
boardCustom – Sets a custom board (Default empty string).
-
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 = "")
Set the Board Info object. Creates version 7 EEPROM data
- Parameters:
deviceName – Sets device name.
productName – Sets product name (alias).
boardName – Sets board name.
boardRev – Sets board revision id.
boardConf – Sets board configuration id.
hardwareConf – Sets hardware configuration id.
batchName – Sets batch name. Not supported anymore
batchTime – Sets batch time (unix timestamp).
boardCustom – Sets a custom board (Default empty string).
-
void setDeviceName(std::string deviceName)
Set the deviceName which responses to getDeviceName of Device
- Parameters:
deviceName – Sets device name.
-
void setProductName(std::string productName)
Set the productName which acts as alisas for users to identify the device
- Parameters:
productName – Sets product name (alias).
-
void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, Size2f frameSize)
Set the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters:
cameraId – CameraId of the camera for which Camera intrinsics are being loaded
intrinsics – 3x3 intrinsics matrix
frameSize – Represents the width and height of the image at which intrinsics are calculated.
-
void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, int width, int height)
Set the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters:
cameraId – CameraId of the camera for which Camera intrinsics are being loaded
intrinsics – 3x3 intrinsics matrix
width – Represents the width of the image at which intrinsics are calculated.
height – Represents the height of the image at which intrinsics are calculated.
-
void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, std::tuple<int, int> frameSize)
Set the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters:
cameraId – CameraId of the camera for which Camera intrinsics are being loaded
intrinsics – 3x3 intrinsics matrix
frameSize – Represents the width and height of the image at which intrinsics are calculated.
-
void setDistortionCoefficients(CameraBoardSocket cameraId, std::vector<float> distortionCoefficients)
Sets the distortion Coefficients obtained from camera calibration
- Parameters:
cameraId – Camera Id of the camera for which distortion coefficients are computed
distortionCoefficients – Distortion Coefficients of the respective Camera.
-
void setFov(CameraBoardSocket cameraId, float hfov)
Set the Fov of the Camera
- Parameters:
cameraId – Camera Id of the camera
hfov – Horizontal fov of the camera from Camera Datasheet
-
void setLensPosition(CameraBoardSocket cameraId, uint8_t lensPosition)
Sets the distortion Coefficients obtained from camera calibration
- Parameters:
cameraId – Camera Id of the camera
lensPosition – lens posiotion value of the camera at the time of calibration
-
void setCameraType(CameraBoardSocket cameraId, CameraModel cameraModel)
Set the Camera Type object
- Parameters:
cameraId – CameraId of the camera for which cameraModel Type is being updated.
cameraModel – Type of the model the camera represents
-
void 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:
srcCameraId – Camera Id of the camera which will be considered as relative origin.
destCameraId – Camera Id of the camera which will be considered as destination from srcCameraId.
rotationMatrix – Rotation between srcCameraId and destCameraId origins.
translation – Translation between srcCameraId and destCameraId origins.
specTranslation – Translation between srcCameraId and destCameraId origins from the design.
-
void 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:
destCameraId – Camera Id of the camera which will be considered as destination from IMU.
rotationMatrix – Rotation between srcCameraId and destCameraId origins.
translation – Translation between IMU and destCameraId origins.
specTranslation – Translation between IMU and destCameraId origins from the design.
-
void setStereoLeft(CameraBoardSocket cameraId, std::vector<std::vector<float>> rectifiedRotation)
Set the Stereo Left Rectification object
Homography of the Left Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_left)
- Parameters:
cameraId – CameraId of the camera which will be used as left Camera of stereo Setup
rectifiedRotation – Rectification rotation of the left camera required for feature matching
-
void setStereoRight(CameraBoardSocket cameraId, std::vector<std::vector<float>> rectifiedRotation)
Set the Stereo Right Rectification object
Homography of the Right Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_right)
- Parameters:
cameraId – CameraId of the camera which will be used as left Camera of stereo Setup
rectifiedRotation – Rectification rotation of the left camera required for feature matching
-
bool 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.
Public Static Functions
-
static CalibrationHandler fromJson(nlohmann::json eepromDataJson)
Construct a new Calibration Handler object from JSON EepromData.
- Parameters:
eepromDataJson – EepromData as JSON