Skip to content

Commit

Permalink
Closes: #355
Browse files Browse the repository at this point in the history
  • Loading branch information
themarpe committed Oct 18, 2022
1 parent eeb2577 commit fe71aa2
Show file tree
Hide file tree
Showing 2 changed files with 110 additions and 103 deletions.
47 changes: 25 additions & 22 deletions include/depthai/device/CalibrationHandler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ class CalibrationHandler {
int resizeHeight = -1,
Point2f topLeftPixelId = Point2f(),
Point2f bottomRightPixelId = Point2f(),
bool keepAspectRatio = true);
bool keepAspectRatio = true) const;

/**
* Get the Camera Intrinsics object
Expand All @@ -112,8 +112,11 @@ class CalibrationHandler {
* \end{matrix} \right ] \f]
*
*/
std::vector<std::vector<float>> getCameraIntrinsics(
CameraBoardSocket cameraId, Size2f destShape, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true);
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
Expand All @@ -140,7 +143,7 @@ class CalibrationHandler {
std::tuple<int, int> destShape,
Point2f topLeftPixelId = Point2f(),
Point2f bottomRightPixelId = Point2f(),
bool keepAspectRatio = true);
bool keepAspectRatio = true) const;

/**
* Get the Default Intrinsics object
Expand All @@ -156,15 +159,15 @@ class CalibrationHandler {
* \end{matrix} \right ] \f]
*
*/
std::tuple<std::vector<std::vector<float>>, int, int> getDefaultIntrinsics(CameraBoardSocket cameraId);
std::tuple<std::vector<std::vector<float>>, int, int> getDefaultIntrinsics(CameraBoardSocket cameraId) const;

/**
* Get the Distortion Coefficients object
*
* @param cameraId Uses the cameraId to identify which distortion Coefficients to return.
* @return the distortion coefficients of the requested camera in this order: [k1,k2,p1,p2,k3,k4,k5,k6,s1,s2,s3,s4,τx,τy]
*/
std::vector<float> getDistortionCoefficients(CameraBoardSocket cameraId);
std::vector<float> getDistortionCoefficients(CameraBoardSocket cameraId) const;

/**
* Get the Fov of the camera
Expand All @@ -173,23 +176,23 @@ class CalibrationHandler {
* @param useSpec Disabling this bool will calculate the fov based on intrinsics (focal length, image width), instead of getting it from the camera specs
* @return field of view of the camera with given cameraId.
*/
float getFov(CameraBoardSocket cameraId, bool useSpec = true);
float getFov(CameraBoardSocket cameraId, bool useSpec = true) const;

/**
* Get the lens position of the given camera
*
* @param cameraId of the camera with lens position is requested.
* @return lens position of the camera with given cameraId at which it was calibrated.
*/
uint8_t getLensPosition(CameraBoardSocket cameraId);
uint8_t getLensPosition(CameraBoardSocket cameraId) const;

/**
* Get the distortion model of the given camera
*
* @param cameraId of the camera with lens position is requested.
* @return lens position of the camera with given cameraId at which it was calibrated.
*/
CameraModel getDistortionModel(CameraBoardSocket cameraId);
CameraModel getDistortionModel(CameraBoardSocket cameraId) const;

/**
* Get the Camera Extrinsics object between two cameras from the calibration data if there is a linked connection
Expand All @@ -209,7 +212,7 @@ class CalibrationHandler {
* \end{matrix} \right ] \f]
*
*/
std::vector<std::vector<float>> getCameraExtrinsics(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false);
std::vector<std::vector<float>> getCameraExtrinsics(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false) const;

/**
* Get the Camera translation vector between two cameras from the calibration data.
Expand All @@ -219,7 +222,7 @@ class CalibrationHandler {
* @param useSpecTranslation Disabling this bool uses the translation information from the calibration data (not the board design data)
* @return a translation vector like [x, y, z] in centimeters
*/
std::vector<float> getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = true);
std::vector<float> getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = true) const;

/**
* Get the baseline distance between two specified cameras. By default it will get the baseline between CameraBoardSocket.RIGHT
Expand All @@ -232,7 +235,7 @@ class CalibrationHandler {
*/
float getBaselineDistance(CameraBoardSocket cam1 = CameraBoardSocket::RIGHT,
CameraBoardSocket cam2 = CameraBoardSocket::LEFT,
bool useSpecTranslation = true);
bool useSpecTranslation = true) const;

/**
* Get the Camera To Imu Extrinsics object
Expand All @@ -252,7 +255,7 @@ class CalibrationHandler {
* \end{matrix} \right ] \f]
*
*/
std::vector<std::vector<float>> getCameraToImuExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation = false);
std::vector<std::vector<float>> getCameraToImuExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation = false) const;

/**
* Get the Imu To Camera Extrinsics object from the data loaded if there is a linked connection
Expand All @@ -272,36 +275,36 @@ class CalibrationHandler {
* \end{matrix} \right ] \f]
*
*/
std::vector<std::vector<float>> getImuToCameraExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation = false);
std::vector<std::vector<float>> getImuToCameraExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation = false) const;

/**
*
* Get the Stereo Right Rectification Rotation object
*
* @return returns a 3x3 rectification rotation matrix
*/
std::vector<std::vector<float>> getStereoRightRectificationRotation();
std::vector<std::vector<float>> getStereoRightRectificationRotation() const;

/**
* Get the Stereo Left Rectification Rotation object
*
* @return returns a 3x3 rectification rotation matrix
*/
std::vector<std::vector<float>> getStereoLeftRectificationRotation();
std::vector<std::vector<float>> getStereoLeftRectificationRotation() const;

/**
* Get the camera id of the camera which is used as left camera of the stereo setup
*
* @return cameraID of the camera used as left camera
*/
dai::CameraBoardSocket getStereoLeftCameraId();
dai::CameraBoardSocket getStereoLeftCameraId() const;

/**
* Get the camera id of the camera which is used as right camera of the stereo setup
*
* @return cameraID of the camera used as right camera
*/
dai::CameraBoardSocket getStereoRightCameraId();
dai::CameraBoardSocket getStereoRightCameraId() const;

/**
* Write raw calibration/board data to json file.
Expand Down Expand Up @@ -495,7 +498,7 @@ class CalibrationHandler {
*
* @return true on proper connection with no loops.
*/
bool validateCameraArray();
bool validateCameraArray() const;

private:
/** when the user is writing extrinsics do we validate if
Expand All @@ -507,9 +510,9 @@ class CalibrationHandler {
*/
// bool isCameraArrayConnected;
dai::EepromData eepromData;
std::vector<std::vector<float>> computeExtrinsicMatrix(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false);
bool checkExtrinsicsLink(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera);
bool checkSrcLinks(CameraBoardSocket headSocket);
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
Loading

0 comments on commit fe71aa2

Please sign in to comment.