Program Listing for File CalibrationHandler.hpp

Return to documentation for file (include/depthai/device/CalibrationHandler.hpp)

#pragma once
#include <string>
#include <tuple>

#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<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::tuple<std::vector<std::vector<float>>, int, int> getDefaultIntrinsics(CameraBoardSocket cameraId) const;

    std::vector<float> 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<std::vector<float>> getCameraExtrinsics(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false) const;

    std::vector<float> 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<std::vector<float>> getCameraToImuExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation = false) const;

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

    std::vector<std::vector<float>> getStereoRightRectificationRotation() const;

    std::vector<std::vector<float>> 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<std::vector<float>> intrinsics, Size2f frameSize);

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

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

    void setDistortionCoefficients(CameraBoardSocket cameraId, std::vector<float> 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<std::vector<float>> rotationMatrix,
                             std::vector<float> translation,
                             std::vector<float> specTranslation = {0, 0, 0});

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

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

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

    bool validateCameraArray() const;

   private:
    // bool isCameraArrayConnected;
    dai::EepromData eepromData;
    std::vector<std::vector<float>> computeExtrinsicMatrix(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false) const;
    bool checkExtrinsicsLink(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera) const;
    bool checkSrcLinks(CameraBoardSocket headSocket) const;
};

}  // namespace dai