CalibrationHandler.hpp
Go to the documentation of this file.
1 #pragma once
2 #include <string>
3 #include <tuple>
4 
10 
11 namespace dai {
25  public:
26  CalibrationHandler() = default;
27 
34  explicit CalibrationHandler(dai::Path eepromDataPath);
35 
43  CalibrationHandler(dai::Path calibrationDataPath, dai::Path boardConfigPath);
44 
51 
57  static CalibrationHandler fromJson(nlohmann::json eepromDataJson);
58 
65 
88  std::vector<std::vector<float>> getCameraIntrinsics(CameraBoardSocket cameraId,
89  int resizeWidth = -1,
90  int resizeHeight = -1,
91  Point2f topLeftPixelId = Point2f(),
92  Point2f bottomRightPixelId = Point2f(),
93  bool keepAspectRatio = true) const;
94 
116  std::vector<std::vector<float>> getCameraIntrinsics(CameraBoardSocket cameraId,
117  Size2f destShape,
118  Point2f topLeftPixelId = Point2f(),
119  Point2f bottomRightPixelId = Point2f(),
120  bool keepAspectRatio = true) const;
121 
143  std::vector<std::vector<float>> getCameraIntrinsics(CameraBoardSocket cameraId,
144  std::tuple<int, int> destShape,
145  Point2f topLeftPixelId = Point2f(),
146  Point2f bottomRightPixelId = Point2f(),
147  bool keepAspectRatio = true) const;
148 
163  std::tuple<std::vector<std::vector<float>>, int, int> getDefaultIntrinsics(CameraBoardSocket cameraId) const;
164 
174  std::vector<float> getDistortionCoefficients(CameraBoardSocket cameraId) const;
175 
183  float getFov(CameraBoardSocket cameraId, bool useSpec = true) const;
184 
191  uint8_t getLensPosition(CameraBoardSocket cameraId) const;
192 
200 
219  std::vector<std::vector<float>> getCameraExtrinsics(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false) const;
220 
229  std::vector<float> getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = true) const;
230 
242  bool useSpecTranslation = true) const;
243 
262  std::vector<std::vector<float>> getCameraToImuExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation = false) const;
263 
282  std::vector<std::vector<float>> getImuToCameraExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation = false) const;
283 
290  std::vector<std::vector<float>> getStereoRightRectificationRotation() const;
291 
297  std::vector<std::vector<float>> getStereoLeftRectificationRotation() const;
298 
305 
312 
319  bool eepromToJsonFile(dai::Path destPath) const;
320 
326  nlohmann::json eepromToJson() const;
327 
335  void setBoardInfo(std::string boardName, std::string boardRev);
336 
349  void setBoardInfo(std::string productName,
350  std::string boardName,
351  std::string boardRev,
352  std::string boardConf,
353  std::string hardwareConf,
354  std::string batchName,
355  uint64_t batchTime,
356  uint32_t boardOptions,
357  std::string boardCustom = "");
358 
372  void setBoardInfo(std::string deviceName,
373  std::string productName,
374  std::string boardName,
375  std::string boardRev,
376  std::string boardConf,
377  std::string hardwareConf,
378  std::string batchName,
379  uint64_t batchTime,
380  uint32_t boardOptions,
381  std::string boardCustom = "");
382 
388  void setDeviceName(std::string deviceName);
389 
396  void setProductName(std::string productName);
397 
413  void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, Size2f frameSize);
414 
431  void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, int width, int height);
432 
448  void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, std::tuple<int, int> frameSize);
449 
456  void setDistortionCoefficients(CameraBoardSocket cameraId, std::vector<float> distortionCoefficients);
457 
464  void setFov(CameraBoardSocket cameraId, float hfov);
465 
472  void setLensPosition(CameraBoardSocket cameraId, uint8_t lensPosition);
473 
480  void setCameraType(CameraBoardSocket cameraId, CameraModel cameraModel);
481 
491  void setCameraExtrinsics(CameraBoardSocket srcCameraId,
492  CameraBoardSocket destCameraId,
493  std::vector<std::vector<float>> rotationMatrix,
494  std::vector<float> translation,
495  std::vector<float> specTranslation = {0, 0, 0});
496 
505  void setImuExtrinsics(CameraBoardSocket destCameraId,
506  std::vector<std::vector<float>> rotationMatrix,
507  std::vector<float> translation,
508  std::vector<float> specTranslation = {0, 0, 0});
509 
518  void setStereoLeft(CameraBoardSocket cameraId, std::vector<std::vector<float>> rectifiedRotation);
519 
528  void setStereoRight(CameraBoardSocket cameraId, std::vector<std::vector<float>> rectifiedRotation);
529 
536  bool validateCameraArray() const;
537 
538  private:
546  // bool isCameraArrayConnected;
548  std::vector<std::vector<float>> computeExtrinsicMatrix(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false) const;
549  bool checkExtrinsicsLink(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera) const;
550  bool checkSrcLinks(CameraBoardSocket headSocket) const;
551 };
552 
553 } // namespace dai
dai::CalibrationHandler::setCameraExtrinsics
void setCameraExtrinsics(CameraBoardSocket srcCameraId, CameraBoardSocket destCameraId, std::vector< std::vector< float >> rotationMatrix, std::vector< float > translation, std::vector< float > specTranslation={0, 0, 0})
Definition: CalibrationHandler.cpp:710
dai::CalibrationHandler::checkExtrinsicsLink
bool checkExtrinsicsLink(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera) const
Definition: CalibrationHandler.cpp:532
dai::CalibrationHandler::getCameraExtrinsics
std::vector< std::vector< float > > getCameraExtrinsics(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=false) const
Definition: CalibrationHandler.cpp:357
dai::CalibrationHandler::setCameraIntrinsics
void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector< std::vector< float >> intrinsics, Size2f frameSize)
Definition: CalibrationHandler.cpp:641
dai::CalibrationHandler::eepromToJsonFile
bool eepromToJsonFile(dai::Path destPath) const
Definition: CalibrationHandler.cpp:469
dai::CalibrationHandler::getDefaultIntrinsics
std::tuple< std::vector< std::vector< float > >, int, int > getDefaultIntrinsics(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:291
CameraBoardSocket.hpp
dai::CameraBoardSocket
CameraBoardSocket
Definition: shared/depthai-shared/include/depthai-shared/common/CameraBoardSocket.hpp:9
dai::CalibrationHandler::getStereoLeftRectificationRotation
std::vector< std::vector< float > > getStereoLeftRectificationRotation() const
Definition: CalibrationHandler.cpp:452
dai::CalibrationHandler::getCameraIntrinsics
std::vector< std::vector< float > > getCameraIntrinsics(CameraBoardSocket cameraId, int resizeWidth=-1, int resizeHeight=-1, Point2f topLeftPixelId=Point2f(), Point2f bottomRightPixelId=Point2f(), bool keepAspectRatio=true) const
Definition: CalibrationHandler.cpp:204
dai::CalibrationHandler::checkSrcLinks
bool checkSrcLinks(CameraBoardSocket headSocket) const
Definition: CalibrationHandler.cpp:797
dai::CalibrationHandler::getCameraTranslationVector
std::vector< float > getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=true) const
Definition: CalibrationHandler.cpp:390
dai::CalibrationHandler::setStereoRight
void setStereoRight(CameraBoardSocket cameraId, std::vector< std::vector< float >> rectifiedRotation)
Definition: CalibrationHandler.cpp:773
dai::Point2f
Definition: Point2f.hpp:16
dai::CalibrationHandler::setDeviceName
void setDeviceName(std::string deviceName)
Definition: CalibrationHandler.cpp:604
dai::CalibrationHandler::validateCameraArray
bool validateCameraArray() const
Definition: CalibrationHandler.cpp:782
dai::CalibrationHandler::setBoardInfo
void setBoardInfo(std::string boardName, std::string boardRev)
Definition: CalibrationHandler.cpp:545
dai::CalibrationHandler::setDistortionCoefficients
void setDistortionCoefficients(CameraBoardSocket cameraId, std::vector< float > distortionCoefficients)
Definition: CalibrationHandler.cpp:651
dai::CalibrationHandler::eepromToJson
nlohmann::json eepromToJson() const
Definition: CalibrationHandler.cpp:476
dai::CameraBoardSocket::CAM_B
@ CAM_B
dai::CalibrationHandler::getImuToCameraExtrinsics
std::vector< std::vector< float > > getImuToCameraExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation=false) const
Definition: CalibrationHandler.cpp:415
dai::CalibrationHandler::getDistortionCoefficients
std::vector< float > getDistortionCoefficients(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:304
dai::CalibrationHandler::setFov
void setFov(CameraBoardSocket cameraId, float hfov)
Definition: CalibrationHandler.cpp:677
dai::CalibrationHandler::getBaselineDistance
float getBaselineDistance(CameraBoardSocket cam1=CameraBoardSocket::CAM_C, CameraBoardSocket cam2=CameraBoardSocket::CAM_B, bool useSpecTranslation=true) const
Definition: CalibrationHandler.cpp:400
dai::CalibrationHandler::fromJson
static CalibrationHandler fromJson(nlohmann::json eepromDataJson)
Definition: CalibrationHandler.cpp:65
dai::CameraModel
CameraModel
Definition: CameraModel.hpp:9
EepromData.hpp
dai::CameraBoardSocket::CAM_C
@ CAM_C
dai::CalibrationHandler::computeExtrinsicMatrix
std::vector< std::vector< float > > computeExtrinsicMatrix(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=false) const
Definition: CalibrationHandler.cpp:480
dai::CalibrationHandler::setProductName
void setProductName(std::string productName)
Definition: CalibrationHandler.cpp:611
dai::CalibrationHandler::getStereoLeftCameraId
dai::CameraBoardSocket getStereoLeftCameraId() const
Definition: CalibrationHandler.cpp:461
dai::Size2f
Definition: Size2f.hpp:15
dai::CalibrationHandler::getDistortionModel
CameraModel getDistortionModel(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:350
dai::CalibrationHandler::getFov
float getFov(CameraBoardSocket cameraId, bool useSpec=true) const
Definition: CalibrationHandler.cpp:328
dai::CalibrationHandler::setStereoLeft
void setStereoLeft(CameraBoardSocket cameraId, std::vector< std::vector< float >> rectifiedRotation)
Definition: CalibrationHandler.cpp:764
dai::CalibrationHandler
Definition: CalibrationHandler.hpp:24
Path.hpp
dai::CalibrationHandler::getStereoRightCameraId
dai::CameraBoardSocket getStereoRightCameraId() const
Definition: CalibrationHandler.cpp:465
dai::CalibrationHandler::setCameraType
void setCameraType(CameraBoardSocket cameraId, CameraModel cameraModel)
Definition: CalibrationHandler.cpp:699
Size2f.hpp
dai::CalibrationHandler::getLensPosition
uint8_t getLensPosition(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:343
Point2f.hpp
dai::CalibrationHandler::setImuExtrinsics
void setImuExtrinsics(CameraBoardSocket destCameraId, std::vector< std::vector< float >> rotationMatrix, std::vector< float > translation, std::vector< float > specTranslation={0, 0, 0})
Definition: CalibrationHandler.cpp:741
dai::CalibrationHandler::getStereoRightRectificationRotation
std::vector< std::vector< float > > getStereoRightRectificationRotation() const
Definition: CalibrationHandler.cpp:444
dai::CalibrationHandler::getEepromData
dai::EepromData getEepromData() const
Definition: CalibrationHandler.cpp:200
dai::CalibrationHandler::setLensPosition
void setLensPosition(CameraBoardSocket cameraId, uint8_t lensPosition)
Definition: CalibrationHandler.cpp:688
dai::CalibrationHandler::getCameraToImuExtrinsics
std::vector< std::vector< float > > getCameraToImuExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation=false) const
Definition: CalibrationHandler.cpp:409
dai::CalibrationHandler::CalibrationHandler
CalibrationHandler()=default
dai::Path
Represents paths on a filesystem; accepts utf-8, Windows utf-16 wchar_t, or std::filesystem::path.
Definition: Path.hpp:27
dai::CalibrationHandler::eepromData
dai::EepromData eepromData
Definition: CalibrationHandler.hpp:547
dai
Definition: CameraExposureOffset.hpp:6
dai::EepromData
Definition: EepromData.hpp:19


depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:18