#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 |
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.
|
default |
|
explicit |
Construct a new Calibration Handler object using the eeprom json file created from calibration procedure.
eepromDataPath | takes the full path to the json file containing the calibration and device info. |
Definition at line 52 of file CalibrationHandler.cpp.
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.
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. |
Definition at line 71 of file CalibrationHandler.cpp.
|
explicit |
Construct a new Calibration Handler object from EepromData object.
eepromData | EepromData data structure containing the calibration data. |
Definition at line 196 of file CalibrationHandler.cpp.
|
private |
Definition at line 532 of file CalibrationHandler.cpp.
|
private |
Definition at line 797 of file CalibrationHandler.cpp.
|
private |
Definition at line 480 of file CalibrationHandler.cpp.
nlohmann::json dai::CalibrationHandler::eepromToJson | ( | ) | const |
Get JSON representation of calibration data
Definition at line 476 of file CalibrationHandler.cpp.
bool dai::CalibrationHandler::eepromToJsonFile | ( | dai::Path | destPath | ) | const |
Write raw calibration/board data to json file.
destPath | Full path to the json file in which raw calibration data will be stored |
Definition at line 469 of file CalibrationHandler.cpp.
|
static |
Construct a new Calibration Handler object from JSON EepromData.
eepromDataJson | EepromData as JSON |
Definition at line 65 of file CalibrationHandler.cpp.
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.
cam1 | First camera |
cam2 | Second camera |
useSpecTranslation | Enabling this bool uses the translation information from the board design data (not the calibration data) |
Definition at line 400 of file CalibrationHandler.cpp.
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.
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 |
Matrix representation of transformation matrix
Definition at line 357 of file CalibrationHandler.cpp.
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
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 |
Matrix representation of intrinsic matrix
Definition at line 204 of file CalibrationHandler.cpp.
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
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 |
Matrix representation of intrinsic matrix
Definition at line 280 of file CalibrationHandler.cpp.
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
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 |
Matrix representation of intrinsic matrix
Definition at line 286 of file CalibrationHandler.cpp.
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.
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 |
Matrix representation of transformation matrix
Definition at line 409 of file CalibrationHandler.cpp.
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.
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) |
Definition at line 390 of file CalibrationHandler.cpp.
std::tuple< std::vector< std::vector< float > >, int, int > dai::CalibrationHandler::getDefaultIntrinsics | ( | CameraBoardSocket | cameraId | ) | const |
Get the Default Intrinsics object
cameraId | Uses the cameraId to identify which camera intrinsics to return |
Matrix representation of intrinsic matrix
Definition at line 291 of file CalibrationHandler.cpp.
std::vector< float > dai::CalibrationHandler::getDistortionCoefficients | ( | CameraBoardSocket | cameraId | ) | const |
Get the Distortion Coefficients object
cameraId | Uses the cameraId to identify which distortion Coefficients to return. |
Definition at line 304 of file CalibrationHandler.cpp.
CameraModel dai::CalibrationHandler::getDistortionModel | ( | CameraBoardSocket | cameraId | ) | const |
Get the distortion model of the given camera
cameraId | of the camera with lens position is requested. |
Definition at line 350 of file CalibrationHandler.cpp.
dai::EepromData dai::CalibrationHandler::getEepromData | ( | ) | const |
Get the Eeprom Data object
Definition at line 200 of file CalibrationHandler.cpp.
float dai::CalibrationHandler::getFov | ( | CameraBoardSocket | cameraId, |
bool | useSpec = true |
||
) | const |
Get the Fov of the camera
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 |
Definition at line 328 of file CalibrationHandler.cpp.
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.
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 |
Matrix representation of transformation matrix
Definition at line 415 of file CalibrationHandler.cpp.
uint8_t dai::CalibrationHandler::getLensPosition | ( | CameraBoardSocket | cameraId | ) | const |
Get the lens position of the given camera
cameraId | of the camera with lens position is requested. |
Definition at line 343 of file CalibrationHandler.cpp.
dai::CameraBoardSocket dai::CalibrationHandler::getStereoLeftCameraId | ( | ) | const |
Get the camera id of the camera which is used as left camera of the stereo setup
Definition at line 461 of file CalibrationHandler.cpp.
std::vector< std::vector< float > > dai::CalibrationHandler::getStereoLeftRectificationRotation | ( | ) | const |
Get the Stereo Left Rectification Rotation object
Definition at line 452 of file CalibrationHandler.cpp.
dai::CameraBoardSocket dai::CalibrationHandler::getStereoRightCameraId | ( | ) | const |
Get the camera id of the camera which is used as right camera of the stereo setup
Definition at line 465 of file CalibrationHandler.cpp.
std::vector< std::vector< float > > dai::CalibrationHandler::getStereoRightRectificationRotation | ( | ) | const |
Get the Stereo Right Rectification Rotation object
Definition at line 444 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setBoardInfo | ( | std::string | boardName, |
std::string | boardRev | ||
) |
Set the Board Info object
version | Sets the version of the Calibration data(Current version is 6) |
boardName | Sets your board name. |
boardRev | set your board revision id. |
Definition at line 545 of file CalibrationHandler.cpp.
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
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). |
Definition at line 576 of file CalibrationHandler.cpp.
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
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). |
Definition at line 550 of file CalibrationHandler.cpp.
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
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. |
Definition at line 710 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setCameraIntrinsics | ( | CameraBoardSocket | cameraId, |
std::vector< std::vector< float >> | intrinsics, | ||
int | width, | ||
int | height | ||
) |
Set the Camera Intrinsics object
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. |
Matrix representation of intrinsic matrix
Definition at line 618 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setCameraIntrinsics | ( | CameraBoardSocket | cameraId, |
std::vector< std::vector< float >> | intrinsics, | ||
Size2f | frameSize | ||
) |
Set the Camera Intrinsics object
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. |
Matrix representation of intrinsic matrix
Definition at line 641 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setCameraIntrinsics | ( | CameraBoardSocket | cameraId, |
std::vector< std::vector< float >> | intrinsics, | ||
std::tuple< int, int > | frameSize | ||
) |
Set the Camera Intrinsics object
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. |
Matrix representation of intrinsic matrix
Definition at line 646 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setCameraType | ( | CameraBoardSocket | cameraId, |
CameraModel | cameraModel | ||
) |
Set the Camera Type object
cameraId | CameraId of the camera for which cameraModel Type is being updated. |
cameraModel | Type of the model the camera represents |
Definition at line 699 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setDeviceName | ( | std::string | deviceName | ) |
Set the deviceName which responses to getDeviceName of Device
deviceName | Sets device name. |
Definition at line 604 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setDistortionCoefficients | ( | CameraBoardSocket | cameraId, |
std::vector< float > | distortionCoefficients | ||
) |
Sets the distortion Coefficients obtained from camera calibration
cameraId | Camera Id of the camera for which distortion coefficients are computed |
distortionCoefficients | Distortion Coefficients of the respective Camera. |
Definition at line 651 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setFov | ( | CameraBoardSocket | cameraId, |
float | hfov | ||
) |
Set the Fov of the Camera
cameraId | Camera Id of the camera |
hfov | Horizontal fov of the camera from Camera Datasheet |
Definition at line 677 of file CalibrationHandler.cpp.
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
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. |
Definition at line 741 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setLensPosition | ( | CameraBoardSocket | cameraId, |
uint8_t | lensPosition | ||
) |
Sets the distortion Coefficients obtained from camera calibration
cameraId | Camera Id of the camera |
lensPosition | lens posiotion value of the camera at the time of calibration |
Definition at line 688 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setProductName | ( | std::string | productName | ) |
Set the productName which acts as alisas for users to identify the device
productName | Sets product name (alias). |
Definition at line 611 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setStereoLeft | ( | CameraBoardSocket | cameraId, |
std::vector< std::vector< float >> | rectifiedRotation | ||
) |
Set the Stereo Left Rectification object
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 |
Homography of the Left Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_left)
Definition at line 764 of file CalibrationHandler.cpp.
void dai::CalibrationHandler::setStereoRight | ( | CameraBoardSocket | cameraId, |
std::vector< std::vector< float >> | rectifiedRotation | ||
) |
Set the Stereo Right Rectification object
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 |
Homography of the Right Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_right)
Definition at line 773 of file CalibrationHandler.cpp.
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.
Definition at line 782 of file CalibrationHandler.cpp.
|
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.