.. _program_listing_file_include_depthai_device_CalibrationHandler.hpp: Program Listing for File CalibrationHandler.hpp =============================================== |exhale_lsh| :ref:`Return to documentation for file ` (``include/depthai/device/CalibrationHandler.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #pragma once #include #include #include "depthai-shared/common/CameraBoardSocket.hpp" #include "depthai-shared/common/EepromData.hpp" #include "depthai-shared/common/Point2f.hpp" #include "depthai-shared/common/Size2f.hpp" #include "depthai/utility/Path.hpp" namespace dai { class CalibrationHandler { public: CalibrationHandler() = default; explicit CalibrationHandler(dai::Path eepromDataPath); CalibrationHandler(dai::Path calibrationDataPath, dai::Path boardConfigPath); explicit CalibrationHandler(EepromData eepromData); static CalibrationHandler fromJson(nlohmann::json eepromDataJson); dai::EepromData getEepromData() const; std::vector> getCameraIntrinsics(CameraBoardSocket cameraId, int resizeWidth = -1, int resizeHeight = -1, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true) const; std::vector> getCameraIntrinsics(CameraBoardSocket cameraId, Size2f destShape, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true) const; std::vector> getCameraIntrinsics(CameraBoardSocket cameraId, std::tuple destShape, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true) const; std::tuple>, int, int> getDefaultIntrinsics(CameraBoardSocket cameraId) const; std::vector getDistortionCoefficients(CameraBoardSocket cameraId) const; float getFov(CameraBoardSocket cameraId, bool useSpec = true) const; uint8_t getLensPosition(CameraBoardSocket cameraId) const; CameraModel getDistortionModel(CameraBoardSocket cameraId) const; std::vector> getCameraExtrinsics(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false) const; std::vector getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = true) const; float getBaselineDistance(CameraBoardSocket cam1 = CameraBoardSocket::CAM_C, CameraBoardSocket cam2 = CameraBoardSocket::CAM_B, bool useSpecTranslation = true) const; std::vector> getCameraToImuExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation = false) const; std::vector> getImuToCameraExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation = false) const; std::vector> getStereoRightRectificationRotation() const; std::vector> getStereoLeftRectificationRotation() const; dai::CameraBoardSocket getStereoLeftCameraId() const; dai::CameraBoardSocket getStereoRightCameraId() const; bool eepromToJsonFile(dai::Path destPath) const; nlohmann::json eepromToJson() const; void setBoardInfo(std::string boardName, std::string boardRev); 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 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 setDeviceName(std::string deviceName); void setProductName(std::string productName); void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector> intrinsics, Size2f frameSize); void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector> intrinsics, int width, int height); void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector> intrinsics, std::tuple frameSize); void setDistortionCoefficients(CameraBoardSocket cameraId, std::vector distortionCoefficients); void setFov(CameraBoardSocket cameraId, float hfov); void setLensPosition(CameraBoardSocket cameraId, uint8_t lensPosition); void setCameraType(CameraBoardSocket cameraId, CameraModel cameraModel); void setCameraExtrinsics(CameraBoardSocket srcCameraId, CameraBoardSocket destCameraId, std::vector> rotationMatrix, std::vector translation, std::vector specTranslation = {0, 0, 0}); void setImuExtrinsics(CameraBoardSocket destCameraId, std::vector> rotationMatrix, std::vector translation, std::vector specTranslation = {0, 0, 0}); void setStereoLeft(CameraBoardSocket cameraId, std::vector> rectifiedRotation); void setStereoRight(CameraBoardSocket cameraId, std::vector> rectifiedRotation); bool validateCameraArray() const; private: // bool isCameraArrayConnected; dai::EepromData eepromData; std::vector> computeExtrinsicMatrix(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false) const; bool checkExtrinsicsLink(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera) const; bool checkSrcLinks(CameraBoardSocket headSocket) const; }; } // namespace dai