Go to the documentation of this file.
90 int resizeHeight = -1,
93 bool keepAspectRatio =
true)
const;
120 bool keepAspectRatio =
true)
const;
144 std::tuple<int, int> destShape,
147 bool keepAspectRatio =
true)
const;
242 bool useSpecTranslation =
true)
const;
335 void setBoardInfo(std::string boardName, std::string boardRev);
350 std::string boardName,
351 std::string boardRev,
352 std::string boardConf,
353 std::string hardwareConf,
354 std::string batchName,
356 uint32_t boardOptions,
357 std::string boardCustom =
"");
373 std::string productName,
374 std::string boardName,
375 std::string boardRev,
376 std::string boardConf,
377 std::string hardwareConf,
378 std::string batchName,
380 uint32_t boardOptions,
381 std::string boardCustom =
"");
493 std::vector<std::vector<float>> rotationMatrix,
494 std::vector<float> translation,
495 std::vector<float> specTranslation = {0, 0, 0});
506 std::vector<std::vector<float>> rotationMatrix,
507 std::vector<float> translation,
508 std::vector<float> specTranslation = {0, 0, 0});
void setCameraExtrinsics(CameraBoardSocket srcCameraId, CameraBoardSocket destCameraId, std::vector< std::vector< float >> rotationMatrix, std::vector< float > translation, std::vector< float > specTranslation={0, 0, 0})
bool checkExtrinsicsLink(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera) const
std::vector< std::vector< float > > getCameraExtrinsics(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=false) const
void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector< std::vector< float >> intrinsics, Size2f frameSize)
bool eepromToJsonFile(dai::Path destPath) const
std::tuple< std::vector< std::vector< float > >, int, int > getDefaultIntrinsics(CameraBoardSocket cameraId) const
std::vector< std::vector< float > > getStereoLeftRectificationRotation() 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
bool checkSrcLinks(CameraBoardSocket headSocket) const
std::vector< float > getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=true) const
void setStereoRight(CameraBoardSocket cameraId, std::vector< std::vector< float >> rectifiedRotation)
void setDeviceName(std::string deviceName)
bool validateCameraArray() const
void setBoardInfo(std::string boardName, std::string boardRev)
void setDistortionCoefficients(CameraBoardSocket cameraId, std::vector< float > distortionCoefficients)
nlohmann::json eepromToJson() const
std::vector< std::vector< float > > getImuToCameraExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation=false) const
std::vector< float > getDistortionCoefficients(CameraBoardSocket cameraId) const
void setFov(CameraBoardSocket cameraId, float hfov)
float getBaselineDistance(CameraBoardSocket cam1=CameraBoardSocket::CAM_C, CameraBoardSocket cam2=CameraBoardSocket::CAM_B, bool useSpecTranslation=true) const
static CalibrationHandler fromJson(nlohmann::json eepromDataJson)
std::vector< std::vector< float > > computeExtrinsicMatrix(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=false) const
void setProductName(std::string productName)
dai::CameraBoardSocket getStereoLeftCameraId() const
CameraModel getDistortionModel(CameraBoardSocket cameraId) const
float getFov(CameraBoardSocket cameraId, bool useSpec=true) const
void setStereoLeft(CameraBoardSocket cameraId, std::vector< std::vector< float >> rectifiedRotation)
dai::CameraBoardSocket getStereoRightCameraId() const
void setCameraType(CameraBoardSocket cameraId, CameraModel cameraModel)
uint8_t getLensPosition(CameraBoardSocket cameraId) const
void setImuExtrinsics(CameraBoardSocket destCameraId, std::vector< std::vector< float >> rotationMatrix, std::vector< float > translation, std::vector< float > specTranslation={0, 0, 0})
std::vector< std::vector< float > > getStereoRightRectificationRotation() const
dai::EepromData getEepromData() const
void setLensPosition(CameraBoardSocket cameraId, uint8_t lensPosition)
std::vector< std::vector< float > > getCameraToImuExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation=false) const
CalibrationHandler()=default
Represents paths on a filesystem; accepts utf-8, Windows utf-16 wchar_t, or std::filesystem::path.
dai::EepromData eepromData
depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:18